From 7c6ecd95a8ef21e4fb5a33b3d3d4b00aa229dc2f Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 14 Mar 2024 17:19:34 +0100 Subject: [PATCH 001/652] mc_wind_estimator_tuning: optionally use GNSS velocity Sometimes GNSS is logged but not used --- .../mc_wind_estimator_tuning.py | 24 ++++++++++++------- 1 file changed, 16 insertions(+), 8 deletions(-) diff --git a/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/mc_wind_estimator_tuning.py b/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/mc_wind_estimator_tuning.py index 61b746fb3886..c0047a00f3ed 100644 --- a/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/mc_wind_estimator_tuning.py +++ b/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/mc_wind_estimator_tuning.py @@ -45,14 +45,20 @@ import quaternion from scipy import optimize -def getAllData(logfile): +def getAllData(logfile, use_gnss): log = ULog(logfile) - v_local = np.matrix([getData(log, 'vehicle_local_position', 'vx'), - getData(log, 'vehicle_local_position', 'vy'), - getData(log, 'vehicle_local_position', 'vz')]) + if use_gnss: + v_local = np.array([getData(log, 'vehicle_gps_position', 'vel_n_m_s'), + getData(log, 'vehicle_gps_position', 'vel_e_m_s'), + getData(log, 'vehicle_gps_position', 'vel_d_m_s')]) + t_v_local = ms2s(getData(log, 'vehicle_gps_position', 'timestamp')) - t_v_local = ms2s(getData(log, 'vehicle_local_position', 'timestamp')) + else: + v_local = np.array([getData(log, 'vehicle_local_position', 'vx'), + getData(log, 'vehicle_local_position', 'vy'), + getData(log, 'vehicle_local_position', 'vz')]) + t_v_local = ms2s(getData(log, 'vehicle_local_position', 'timestamp')) accel = np.matrix([getData(log, 'sensor_combined', 'accelerometer_m_s2[0]'), getData(log, 'sensor_combined', 'accelerometer_m_s2[1]'), @@ -126,8 +132,8 @@ def getData(log, topic_name, variable_name, instance=0): def ms2s(time_ms): return time_ms * 1e-6 -def run(logfile): - (t, v_body, a_body) = getAllData(logfile) +def run(logfile, use_gnss): + (t, v_body, a_body) = getAllData(logfile, use_gnss) rho = 1.15 # air densitiy rho15 = 1.225 # air density at 15 degC @@ -197,8 +203,10 @@ def run(logfile): # Provide parameter file path and name parser.add_argument('logfile', help='Full ulog file path, name and extension', type=str) + parser.add_argument('--gnss', help='Use GNSS velocity instead of local velocity estimate', + action='store_true') args = parser.parse_args() logfile = os.path.abspath(args.logfile) # Convert to absolute path - run(logfile) + run(logfile, args.gnss) From 6d8273483cd0644f4a5ad614aae9c95c19a1cbb2 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 13 Mar 2024 17:06:21 +0100 Subject: [PATCH 002/652] Commander: set vehicle_status.failsafe flag only if action for failed check is more than warning Signed-off-by: Silvan Fuhrer --- src/modules/commander/failsafe/framework.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/failsafe/framework.h b/src/modules/commander/failsafe/framework.h index 07d46cbabfd6..9f989582f7ce 100644 --- a/src/modules/commander/failsafe/framework.h +++ b/src/modules/commander/failsafe/framework.h @@ -147,7 +147,7 @@ class FailsafeBase: public ModuleParams bool rc_sticks_takeover_request, const failsafe_flags_s &status_flags); - bool inFailsafe() const { return _selected_action != Action::None; } + bool inFailsafe() const { return (_selected_action != Action::None && _selected_action != Action::Warn); } Action selectedAction() const { return _selected_action; } From d330d4749565bacdfa3bbaa3b166ebfdf56761b4 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 14 Mar 2024 09:48:59 +0100 Subject: [PATCH 003/652] EstimatorCheck: GNSS data fusion stopped as INFO if local position is already invalid Helps to reduce spamming of less important warnings. Signed-off-by: Silvan Fuhrer --- .../commander/HealthAndArmingChecks/checks/estimatorCheck.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 9bb33f2bd24f..1cdd097b12aa 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -293,7 +293,9 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor mavlink_log_warning(reporter.mavlink_log_pub(), "GNSS data fusion stopped\t"); } - events::send(events::ID("check_estimator_gnss_fusion_stopped"), {events::Log::Error, events::LogInternal::Info}, + // only report this failure as critical if not already in a local position invalid state + events::Log log_level = reporter.failsafeFlags().local_position_invalid ? events::Log::Info : events::Log::Error; + events::send(events::ID("check_estimator_gnss_fusion_stopped"), {log_level, events::LogInternal::Info}, "GNSS data fusion stopped"); } else if (!_gps_was_fused && ekf_gps_fusion) { From 6e15dd5328f183f3202f68f50409a33bfb33a3c7 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 14 Mar 2024 10:35:45 +0100 Subject: [PATCH 004/652] Commander: trigger warning when arming denied due to check failure Signed-off-by: Silvan Fuhrer --- src/modules/commander/Commander.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index bca8ef3f68d3..444f5b0c8dba 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -598,6 +598,9 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_ if (!_health_and_arming_checks.canArm(_vehicle_status.nav_state)) { tune_negative(true); + mavlink_log_critical(&_mavlink_log_pub, "Arming denied: Resolve system health failures first\t"); + events::send(events::ID("commander_arm_denied_resolve_failures"), {events::Log::Critical, events::LogInternal::Info}, + "Arming denied: Resolve system health failures first"); return TRANSITION_DENIED; } } From 4ae2fbd17160c777ffe862de149524179f562a3e Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 14 Mar 2024 10:50:00 +0100 Subject: [PATCH 005/652] Commander enums: capitalize flight mode names Signed-off-by: Silvan Fuhrer --- src/lib/events/enums.json | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index 1b23bcfab4c5..f8ebe3b1a728 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -402,19 +402,19 @@ }, "2": { "name": "fallback_posctrl", - "description": "fallback to position control" + "description": "fallback to Position mode" }, "3": { "name": "fallback_altctrl", - "description": "fallback to altitude control" + "description": "fallback to Altitude mode" }, "4": { "name": "fallback_stabilized", - "description": "fallback to stabilized" + "description": "fallback to Stabilized mode" }, "5": { "name": "hold", - "description": "hold" + "description": "Hold" }, "6": { "name": "rtl", @@ -422,11 +422,11 @@ }, "7": { "name": "land", - "description": "land" + "description": "Land" }, "8": { "name": "descend", - "description": "descend" + "description": "Descend" }, "9": { "name": "disarm", From f6430a27d67a0f19e12bc666bda9a6544c3d71fd Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 14 Mar 2024 11:04:02 +0100 Subject: [PATCH 006/652] Commander enums: capitalize battery level key words Signed-off-by: Silvan Fuhrer --- src/lib/events/enums.json | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index f8ebe3b1a728..97bfd70c8fb9 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -372,15 +372,15 @@ }, "3": { "name": "low_battery_level", - "description": "low battery level" + "description": "Low battery level" }, "4": { "name": "critical_battery_level", - "description": "critical battery level" + "description": "Critical battery level" }, "5": { "name": "emergency_battery_level", - "description": "emergency battery level" + "description": "Emergency battery level" }, "6": { "name": "low_remaining_flight_time", From da39d075acec070f8f7fe3677b79363192fa10ac Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 14 Mar 2024 11:33:11 +0100 Subject: [PATCH 007/652] Commander enums: shorten failsafe event messages Such that the focus is on the important keywords. Signed-off-by: Silvan Fuhrer --- src/lib/events/enums.json | 10 +++++----- src/modules/commander/failsafe/framework.cpp | 8 ++++---- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index 97bfd70c8fb9..8e86170951bf 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -364,7 +364,7 @@ }, "1": { "name": "manual_control_loss", - "description": "manual control loss" + "description": "Manual control loss" }, "2": { "name": "gcs_connection_loss", @@ -384,7 +384,7 @@ }, "6": { "name": "low_remaining_flight_time", - "description": "low remaining flight time" + "description": "Remaining flight time low" } } }, @@ -402,15 +402,15 @@ }, "2": { "name": "fallback_posctrl", - "description": "fallback to Position mode" + "description": "Position mode" }, "3": { "name": "fallback_altctrl", - "description": "fallback to Altitude mode" + "description": "Altitude mode" }, "4": { "name": "fallback_stabilized", - "description": "fallback to Stabilized mode" + "description": "Stabilized mode" }, "5": { "name": "hold", diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 4c85ee5c7214..cdd72de0f71d 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -195,7 +195,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_generic_hold"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe activated, triggering {2} in {3} seconds", mavlink_mode, failsafe_action, + "Failsafe, triggering {2} in {3} seconds", mavlink_mode, failsafe_action, (uint16_t) delay_s); } else { @@ -204,7 +204,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_hold"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe activated due to {4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action, + "{4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action, (uint16_t) delay_s, failsafe_cause); } @@ -231,7 +231,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_generic"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe activated, triggering {2}", mavlink_mode, failsafe_action); + "Failsafe, triggering {2}", mavlink_mode, failsafe_action); } } else { @@ -272,7 +272,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe activated due to {3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause); + "{3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause); } } From 70346a5b2f34eef5119848658dbb97f3d7c1ca56 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 15 Mar 2024 10:06:58 +0100 Subject: [PATCH 008/652] failsafe: set cause to generic when fallback mode is activated Previously when triggering low battery RTL and then losing GPS, the fallback to Descend would still have low battery as cause. --- src/modules/commander/failsafe/framework.cpp | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index cdd72de0f71d..16a3678d81b5 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -517,6 +517,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s break; } + returned_state.cause = Cause::Generic; + // fallthrough case Action::FallbackAltCtrl: if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_ALTCTL)) { @@ -524,6 +526,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s break; } + returned_state.cause = Cause::Generic; + // fallthrough case Action::FallbackStab: if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_STAB)) { @@ -531,6 +535,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s break; } // else: fall through here as well. If stabilized isn't available, we most certainly end up in Terminate + returned_state.cause = Cause::Generic; + // fallthrough case Action::Hold: if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER)) { @@ -538,6 +544,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s break; } + returned_state.cause = Cause::Generic; + // fallthrough case Action::RTL: if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_RTL)) { @@ -545,6 +553,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s break; } + returned_state.cause = Cause::Generic; + // fallthrough case Action::Land: if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LAND)) { @@ -552,6 +562,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s break; } + returned_state.cause = Cause::Generic; + // fallthrough case Action::Descend: if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_DESCEND)) { @@ -559,6 +571,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s break; } + returned_state.cause = Cause::Generic; + // fallthrough case Action::Terminate: selected_action = Action::Terminate; From 32aa3263a60d48a960eb8a2ccc50073815250889 Mon Sep 17 00:00:00 2001 From: muramura Date: Sun, 17 Mar 2024 22:04:32 +0900 Subject: [PATCH 009/652] EKF: Change a typo --- src/modules/ekf2/EKF/gps_control.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/gps_control.cpp index cf2f9eb7b454..03cf0a326f28 100644 --- a/src/modules/ekf2/EKF/gps_control.cpp +++ b/src/modules/ekf2/EKF/gps_control.cpp @@ -246,7 +246,7 @@ bool Ekf::tryYawEmergencyReset() bool success = false; /* A rapid reset to the yaw emergency estimate is performed if horizontal velocity innovation checks continuously - * fails while the difference between the yaw emergency estimator and the yas estimate is large. + * fails while the difference between the yaw emergency estimator and the yaw estimate is large. * This enables recovery from a bad yaw estimate. A reset is not performed if the fault condition was * present before flight to prevent triggering due to GPS glitches or other sensor errors. */ From 2e6dd243af393afb64e326a0357a052045e2a492 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 26 Jan 2024 16:53:21 +0100 Subject: [PATCH 010/652] mpc: add possibility to generate tilt using full 3D accel Using full 3D acceleration provides better horizontal acceleration tracking but also creates a sometimes unwanted behavior because the tilt is directly coupled with the vertical acceleration setpoint. --- .../MulticopterPositionControl.cpp | 1 + .../MulticopterPositionControl.hpp | 1 + .../PositionControl/PositionControl.cpp | 17 ++++++++++++----- .../PositionControl/PositionControl.hpp | 6 ++++++ ...multicopter_position_control_limits_params.c | 10 ++++++++++ 5 files changed, 30 insertions(+), 5 deletions(-) diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.cpp b/src/modules/mc_pos_control/MulticopterPositionControl.cpp index ca8360c80452..90928921835d 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.cpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.cpp @@ -167,6 +167,7 @@ void MulticopterPositionControl::parameters_update(bool force) Vector3f(_param_mpc_xy_vel_i_acc.get(), _param_mpc_xy_vel_i_acc.get(), _param_mpc_z_vel_i_acc.get()), Vector3f(_param_mpc_xy_vel_d_acc.get(), _param_mpc_xy_vel_d_acc.get(), _param_mpc_z_vel_d_acc.get())); _control.setHorizontalThrustMargin(_param_mpc_thr_xy_marg.get()); + _control.decoupleHorizontalAndVecticalAcceleration(_param_mpc_acc_decouple.get()); _goto_control.setParamMpcAccHor(_param_mpc_acc_hor.get()); _goto_control.setParamMpcAccDownMax(_param_mpc_acc_down_max.get()); _goto_control.setParamMpcAccUpMax(_param_mpc_acc_up_max.get()); diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.hpp b/src/modules/mc_pos_control/MulticopterPositionControl.hpp index b1f88fde57d3..3dac59bc1b89 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.hpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.hpp @@ -146,6 +146,7 @@ class MulticopterPositionControl : public ModuleBase (ParamFloat) _param_mpc_tiltmax_air, (ParamFloat) _param_mpc_thr_hover, (ParamBool) _param_mpc_use_hte, + (ParamBool) _param_mpc_acc_decouple, // Takeoff / Land (ParamFloat) _param_com_spoolup_time, /**< time to let motors spool up after arming */ diff --git a/src/modules/mc_pos_control/PositionControl/PositionControl.cpp b/src/modules/mc_pos_control/PositionControl/PositionControl.cpp index 955f3f4b44a7..0cf632c04359 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControl.cpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControl.cpp @@ -204,13 +204,20 @@ void PositionControl::_velocityControl(const float dt) void PositionControl::_accelerationControl() { // Assume standard acceleration due to gravity in vertical direction for attitude generation - Vector3f body_z = Vector3f(-_acc_sp(0), -_acc_sp(1), CONSTANTS_ONE_G).normalized(); + float z_specific_force = -CONSTANTS_ONE_G; + + if (!_decouple_horizontal_and_vertical_acceleration) { + // Include vertical acceleration setpoint for better horizontal acceleration tracking + z_specific_force += _acc_sp(2); + } + + Vector3f body_z = Vector3f(-_acc_sp(0), -_acc_sp(1), -z_specific_force).normalized(); ControlMath::limitTilt(body_z, Vector3f(0, 0, 1), _lim_tilt); - // Scale thrust assuming hover thrust produces standard gravity - float collective_thrust = _acc_sp(2) * (_hover_thrust / CONSTANTS_ONE_G) - _hover_thrust; + // Convert to thrust assuming hover thrust produces standard gravity + const float thrust_ned_z = _acc_sp(2) * (_hover_thrust / CONSTANTS_ONE_G) - _hover_thrust; // Project thrust to planned body attitude - collective_thrust /= (Vector3f(0, 0, 1).dot(body_z)); - collective_thrust = math::min(collective_thrust, -_lim_thr_min); + const float cos_ned_body = (Vector3f(0, 0, 1).dot(body_z)); + const float collective_thrust = math::min(thrust_ned_z / cos_ned_body, -_lim_thr_min); _thr_sp = body_z * collective_thrust; } diff --git a/src/modules/mc_pos_control/PositionControl/PositionControl.hpp b/src/modules/mc_pos_control/PositionControl/PositionControl.hpp index 4eb909e1fa3e..7575409bbc78 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControl.hpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControl.hpp @@ -163,6 +163,11 @@ class PositionControl */ void resetIntegral() { _vel_int.setZero(); } + /** + * If set, the tilt setpoint is computed by assuming no vertical acceleration + */ + void decoupleHorizontalAndVecticalAcceleration(bool val) { _decouple_horizontal_and_vertical_acceleration = val; } + /** * Get the controllers output local position setpoint * These setpoints are the ones which were executed on including PID output and feed-forward. @@ -211,6 +216,7 @@ class PositionControl float _lim_tilt{}; ///< Maximum tilt from level the output attitude is allowed to have float _hover_thrust{}; ///< Thrust [HOVER_THRUST_MIN, HOVER_THRUST_MAX] with which the vehicle hovers not accelerating down or up with level orientation + bool _decouple_horizontal_and_vertical_acceleration{false}; ///< Ignore vertical acceleration setpoint to remove its effect on the tilt setpoint // States matrix::Vector3f _pos; /**< current position */ diff --git a/src/modules/mc_pos_control/multicopter_position_control_limits_params.c b/src/modules/mc_pos_control/multicopter_position_control_limits_params.c index a60732cfa8c2..91039f04ea6d 100644 --- a/src/modules/mc_pos_control/multicopter_position_control_limits_params.c +++ b/src/modules/mc_pos_control/multicopter_position_control_limits_params.c @@ -138,3 +138,13 @@ PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.12f); * @group Multicopter Position Control */ PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.f); + +/** + * Acceleration to tilt coupling + * + * Set to decouple tilt from vertical acceleration. + * + * @boolean + * @group Multicopter Position Control + */ +PARAM_DEFINE_INT32(MPC_ACC_DECOUPLE, 1); From 95627ea098f3e6107805ba4f389c54ecfe1c0c42 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 20 Mar 2024 09:33:37 +1100 Subject: [PATCH 011/652] SMART_BATTERY_INFO to BATTERY_INFO (#22875) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Update submodule mavlink to latest Wed Mar 13 01:02:16 UTC 2024 - mavlink in PX4/Firmware (497327e916103ef05ff8f08f47d33b9a19bc28d7): https://github.com/mavlink/mavlink/commit/c4a5c497379ca873f73abe691a033641a6a5a817 - mavlink current upstream: https://github.com/mavlink/mavlink/commit/a3558d6b335d930fc01816fd168d16b3f38ed434 - Changes: https://github.com/mavlink/mavlink/compare/c4a5c497379ca873f73abe691a033641a6a5a817...a3558d6b335d930fc01816fd168d16b3f38ed434 a3558d6b 2024-03-07 Hamish Willee - common - DO_FENCE_ENABLE/PARACHUTE fix (#2090) b9730e0f 2024-03-06 olliw42 - update RADIO_RC_CHANNELS to latest, remove all mlrs from storm32.xml (#1919) 7fed0268 2024-03-06 Patrick José Pereira - common: MAV_CMD_DO_SET_SYS_CMP_ID: Add first version (#2082) 2909b481 2024-03-06 Hamish Willee - Update Pymavlink (#2089) e9b532a9 2024-03-05 Randy Mackay - common: add set-camera-source command (#2079) bcdbeb7f 2024-03-01 auturgy - Allow individual fences to be enabled and disabled (#2085) 2f8403d1 2024-02-29 Hamish Willee - MAV_CMD_ODID_SET_EMERGENCY - (#2086) daa59c02 2024-02-22 Peter Barker - common.xml: add a command to deal with safety switch (#2081) 977332e2 2024-02-14 Hamish Willee - COMPONENT_INFORMATION_BASIC - add manufacturer date (#2078) 4fef7de2 2024-02-07 Randy Mackay - Common: rename SMART_BATTERY_INFO to BATTERY_INFO and add SOH (#2070) 3865b311 2024-02-01 Hamish Willee - FLIGHT_INFORMATION - description to match PX4 (#2067) f80e6818 2024-01-31 KonradRudin - development.xml: merge both MAV_CMD enums together (#2074) * SMART_BATTERY_INFO to BATTERY_INFO on new mavlink module * Update src/modules/mavlink/streams/BATTERY_INFO.hpp * fix trivial whitespace --------- Co-authored-by: PX4 BuildBot Co-authored-by: Daniel Agar --- src/modules/mavlink/mavlink | 2 +- src/modules/mavlink/mavlink_messages.cpp | 8 +-- ...MART_BATTERY_INFO.hpp => BATTERY_INFO.hpp} | 58 ++++++++++++------- 3 files changed, 41 insertions(+), 27 deletions(-) rename src/modules/mavlink/streams/{SMART_BATTERY_INFO.hpp => BATTERY_INFO.hpp} (67%) diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index c4a5c497379c..a3558d6b335d 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit c4a5c497379ca873f73abe691a033641a6a5a817 +Subproject commit a3558d6b335d930fc01816fd168d16b3f38ed434 diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index d9a9dc213910..bcd532861814 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -132,6 +132,7 @@ #if !defined(CONSTRAINED_FLASH) # include "streams/ADSB_VEHICLE.hpp" # include "streams/AUTOPILOT_STATE_FOR_GIMBAL_DEVICE.hpp" +# include "streams/BATTERY_INFO.hpp" # include "streams/DEBUG.hpp" # include "streams/DEBUG_FLOAT_ARRAY.hpp" # include "streams/DEBUG_VECT.hpp" @@ -147,7 +148,6 @@ # include "streams/ODOMETRY.hpp" # include "streams/SCALED_PRESSURE2.hpp" # include "streams/SCALED_PRESSURE3.hpp" -# include "streams/SMART_BATTERY_INFO.hpp" # include "streams/UAVIONIX_ADSB_OUT_CFG.hpp" # include "streams/UAVIONIX_ADSB_OUT_DYNAMIC.hpp" # include "streams/UTM_GLOBAL_POSITION.hpp" @@ -259,9 +259,9 @@ static const StreamListItem streams_list[] = { create_stream_list_item(), #endif // SYS_STATUS_HPP create_stream_list_item(), -#if defined(SMART_BATTERY_INFO_HPP) - create_stream_list_item(), -#endif // SMART_BATTERY_INFO_HPP +#if defined(BATTERY_INFO_HPP) + create_stream_list_item(), +#endif // BATTERY_INFO_HPP #if defined(HIGHRES_IMU_HPP) create_stream_list_item(), #endif // HIGHRES_IMU_HPP diff --git a/src/modules/mavlink/streams/SMART_BATTERY_INFO.hpp b/src/modules/mavlink/streams/BATTERY_INFO.hpp similarity index 67% rename from src/modules/mavlink/streams/SMART_BATTERY_INFO.hpp rename to src/modules/mavlink/streams/BATTERY_INFO.hpp index 3476db3a02b2..fd72acce45ed 100644 --- a/src/modules/mavlink/streams/SMART_BATTERY_INFO.hpp +++ b/src/modules/mavlink/streams/BATTERY_INFO.hpp @@ -31,30 +31,30 @@ * ****************************************************************************/ -#ifndef SMART_BATTERY_INFO_HPP -#define SMART_BATTERY_INFO_HPP +#ifndef BATTERY_INFO_HPP +#define BATTERY_INFO_HPP #include -class MavlinkStreamSmartBatteryInfo : public MavlinkStream +class MavlinkStreamBatteryInfo : public MavlinkStream { public: - static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamSmartBatteryInfo(mavlink); } + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamBatteryInfo(mavlink); } - static constexpr const char *get_name_static() { return "SMART_BATTERY_INFO"; } - static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SMART_BATTERY_INFO; } + static constexpr const char *get_name_static() { return "BATTERY_INFO"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_BATTERY_INFO; } const char *get_name() const override { return get_name_static(); } uint16_t get_id() override { return get_id_static(); } unsigned get_size() override { - static constexpr unsigned size_per_battery = MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + static constexpr unsigned size_per_battery = MAVLINK_MSG_ID_BATTERY_INFO_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; return size_per_battery * _battery_status_subs.advertised_count(); } private: - explicit MavlinkStreamSmartBatteryInfo(Mavlink *mavlink) : MavlinkStream(mavlink) {} + explicit MavlinkStreamBatteryInfo(Mavlink *mavlink) : MavlinkStream(mavlink) {} uORB::SubscriptionMultiArray _battery_status_subs{ORB_ID::battery_status}; @@ -67,36 +67,50 @@ class MavlinkStreamSmartBatteryInfo : public MavlinkStream if (battery_sub.update(&battery_status)) { if (battery_status.serial_number == 0) { - // This is not smart battery + // Required to emit continue; } - mavlink_smart_battery_info_t msg{}; + mavlink_battery_info_t msg{}; msg.id = battery_status.id - 1; - msg.capacity_full_specification = battery_status.capacity; - msg.capacity_full = (int32_t)((float)(battery_status.state_of_health * battery_status.capacity) / 100.f); + msg.design_capacity = (float)(battery_status.capacity * 1000); + msg.full_charge_capacity = (float)(battery_status.state_of_health * battery_status.capacity * 1000.f) / 100.f; msg.cycle_count = battery_status.cycle_count; if (battery_status.manufacture_date) { uint16_t day = battery_status.manufacture_date % 32; uint16_t month = (battery_status.manufacture_date >> 5) % 16; - uint16_t year = (80 + (battery_status.manufacture_date >> 9)) % 100; + uint16_t year = (80 + (battery_status.manufacture_date >> 9)); + uint16_t year2dig = year % 100; + //Formatted as 'ddmmyyyy' (maxed 9 chars) + snprintf(msg.manufacture_date, sizeof(msg.manufacture_date), "%d%d%d", day, month, year); //Formatted as 'dd/mm/yy-123456' (maxed 15 + 1 chars) - snprintf(msg.serial_number, sizeof(msg.serial_number), "%d/%d/%d-%d", day, month, year, battery_status.serial_number); + snprintf(msg.serial_number, sizeof(msg.serial_number), "%d/%d/%d-%d", day, month, year2dig, + battery_status.serial_number); } else { + snprintf(msg.serial_number, sizeof(msg.serial_number), "%d", battery_status.serial_number); } - //msg.device_name = ?? - msg.weight = -1; - msg.discharge_minimum_voltage = -1; - msg.charging_minimum_voltage = -1; - msg.resting_minimum_voltage = -1; - - mavlink_msg_smart_battery_info_send_struct(_mavlink->get_channel(), &msg); + // Not supported by PX4 (not in battery_status uorb topic) + /* + msg.name = 0; // char[50] + msg.weight = 0; + msg.discharge_minimum_voltage = 0; + msg.charging_minimum_voltage = 0; + msg.resting_minimum_voltage = 0; + msg.charging_maximum_voltage = 0; + msg.charging_maximum_current = 0; + msg.discharge_maximum_current = 0; + msg.discharge_maximum_burst_current = 0; + msg.cells_in_series = 0; + msg.nominal_voltage = 0; + */ + + mavlink_msg_battery_info_send_struct(_mavlink->get_channel(), &msg); updated = true; } } @@ -105,4 +119,4 @@ class MavlinkStreamSmartBatteryInfo : public MavlinkStream } }; -#endif // SMART_BATTERY_INFO_HPP +#endif // BATTERY_INFO_HPP From 63850873eb6a0ecb7fc5ccda0b294dc3e60a674e Mon Sep 17 00:00:00 2001 From: muramura Date: Sun, 10 Mar 2024 01:20:35 +0900 Subject: [PATCH 012/652] sd_bench: Display maximum time for maximum write time --- src/systemcmds/sd_bench/sd_bench.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/systemcmds/sd_bench/sd_bench.cpp b/src/systemcmds/sd_bench/sd_bench.cpp index 990932432162..edfaff4f5062 100644 --- a/src/systemcmds/sd_bench/sd_bench.cpp +++ b/src/systemcmds/sd_bench/sd_bench.cpp @@ -50,6 +50,8 @@ #include +#define MAX(a,b) ((a) > (b) ? (a) : (b)) + typedef struct sdb_config { int num_runs; ///< number of runs int run_duration; ///< duration of a single run [ms] @@ -202,6 +204,7 @@ void write_test(int fd, sdb_config_t *cfg, uint8_t *block, int block_size) unsigned int total_blocks = 0; cfg->total_blocks_written = 0; unsigned int *blocknumber = (unsigned int *)(void *)&block[0]; + unsigned int max_max_write_time = 0; for (int run = 0; run < cfg->num_runs; ++run) { hrt_abstime start = hrt_absolute_time(); @@ -245,10 +248,12 @@ void write_test(int fd, sdb_config_t *cfg, uint8_t *block, int block_size) total_elapsed += elapsed; total_blocks += num_blocks; + max_max_write_time = MAX(max_max_write_time, max_write_time); } cfg->total_blocks_written = total_blocks; PX4_INFO(" Avg : %8.2lf KB/s", (double)block_size * total_blocks / total_elapsed / 1024.); + PX4_INFO(" Overall max write time: %i ms", max_max_write_time); } int read_test(int fd, sdb_config_t *cfg, uint8_t *block, int block_size) From 37caddedbb8e8fd871ebbe942f03c257ae6a0012 Mon Sep 17 00:00:00 2001 From: Drone-Lab <2334088143@qq.com> Date: Wed, 20 Mar 2024 15:37:19 +0800 Subject: [PATCH 013/652] navigator: update mission after changing home position (#22834) --- src/modules/navigator/mission_base.cpp | 27 ++++++++++++++++++++++++++ src/modules/navigator/mission_base.h | 8 ++++++++ 2 files changed, 35 insertions(+) diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index 4a376995a098..026cefaba2c5 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -253,6 +253,7 @@ MissionBase::on_active() updateMavlinkMission(); updateDatamanCache(); + updateMissionAltAfterHomeChanged(); /* Check the mission */ if (!_mission_checked && canRunMissionFeasibility()) { @@ -1375,3 +1376,29 @@ bool MissionBase::canRunMissionFeasibility() (_geofence_status_sub.get().geofence_id == _mission.geofence_id) && (_geofence_status_sub.get().status == geofence_status_s::GF_STATUS_READY); } + +void MissionBase::updateMissionAltAfterHomeChanged() +{ + if (_navigator->get_home_position()->update_count > _home_update_counter) { + float new_alt = get_absolute_altitude_for_item(_mission_item); + float altitude_diff = new_alt - _navigator->get_position_setpoint_triplet()->current.alt; + + if (_navigator->get_position_setpoint_triplet()->previous.valid + && PX4_ISFINITE(_navigator->get_position_setpoint_triplet()->previous.alt)) { + _navigator->get_position_setpoint_triplet()->previous.alt = _navigator->get_position_setpoint_triplet()->previous.alt + + altitude_diff; + } + + _navigator->get_position_setpoint_triplet()->current.alt = _navigator->get_position_setpoint_triplet()->current.alt + + altitude_diff; + + if (_navigator->get_position_setpoint_triplet()->next.valid + && PX4_ISFINITE(_navigator->get_position_setpoint_triplet()->next.alt)) { + _navigator->get_position_setpoint_triplet()->next.alt = _navigator->get_position_setpoint_triplet()->next.alt + + altitude_diff; + } + + _navigator->set_position_setpoint_triplet_updated(); + _home_update_counter = _navigator->get_home_position()->update_count; + } +} diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index 7f234bb7d277..1b788106f4a3 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -448,8 +448,16 @@ class MissionBase : public MissionBlock, public ModuleParams */ bool checkMissionDataChanged(mission_s new_mission); + /** + * @brief update current mission altitude after the home position has changed. + */ + + void updateMissionAltAfterHomeChanged(); + bool canRunMissionFeasibility(); + uint32_t _home_update_counter = 0; /**< Variable to store the previous value for home change detection.*/ + bool _align_heading_necessary{false}; // if true, heading of vehicle needs to be aligned with heading of next waypoint. Used to create new mission items for heading alignment. mission_item_s _last_gimbal_configure_item {}; From c9221b91ad85c7eae114fd1a0ffe3bf1750676ea Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 19 Mar 2024 13:55:51 +0100 Subject: [PATCH 014/652] ekf2: fix gnss yaw unit test --- src/modules/ekf2/test/test_EKF_gps_yaw.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp index 42737306eae3..2c3afc655ac4 100644 --- a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp +++ b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp @@ -81,9 +81,10 @@ class EkfGpsHeadingTest : public ::testing::Test void EkfGpsHeadingTest::runConvergenceScenario(float yaw_offset_rad, float antenna_offset_rad) { // GIVEN: an initial GPS yaw, not aligned with the current one - float gps_heading = matrix::wrap_pi(_ekf_wrapper.getYawAngle() + yaw_offset_rad); + // The yaw antenna offset has already been corrected in the driver + float gps_heading = matrix::wrap_pi(_ekf_wrapper.getYawAngle()); - _sensor_simulator._gps.setYaw(gps_heading); + _sensor_simulator._gps.setYaw(gps_heading); // used to remove the correction to fuse the real measurement _sensor_simulator._gps.setYawOffset(antenna_offset_rad); // WHEN: the GPS yaw fusion is activated @@ -91,7 +92,7 @@ void EkfGpsHeadingTest::runConvergenceScenario(float yaw_offset_rad, float anten _sensor_simulator.runSeconds(5); // THEN: the estimate is reset and stays close to the measurement - checkConvergence(gps_heading, 0.05f); + checkConvergence(gps_heading, 0.01f); } void EkfGpsHeadingTest::checkConvergence(float truth, float tolerance_deg) From cb2bb2e0980e21a9cb4029aa036d2535d37c94b8 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 20 Mar 2024 12:12:27 +0100 Subject: [PATCH 015/652] ekf2: add no gyro bias estimate test case This makes the ekf unstable and creates NANs during initialization --- .../test/sensor_simulator/ekf_wrapper.cpp | 10 +++++++ .../ekf2/test/sensor_simulator/ekf_wrapper.h | 3 +++ .../ekf2/test/test_EKF_initialization.cpp | 26 +++++++++++++++++++ 3 files changed, 39 insertions(+) diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp index 513e6d057b3d..fe2c3a88ff7c 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp @@ -314,3 +314,13 @@ float EkfWrapper::getMagHeadingNoise() const { return _ekf_params->mag_heading_noise; } + +void EkfWrapper::enableGyroBiasEstimation() +{ + _ekf_params->imu_ctrl |= static_cast(ImuCtrl::GyroBias); +} + +void EkfWrapper::disableGyroBiasEstimation() +{ + _ekf_params->imu_ctrl &= ~static_cast(ImuCtrl::GyroBias); +} diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h index 43753e9bc548..e1d35f093408 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h @@ -128,6 +128,9 @@ class EkfWrapper float getMagHeadingNoise() const; + void enableGyroBiasEstimation(); + void disableGyroBiasEstimation(); + private: std::shared_ptr _ekf; diff --git a/src/modules/ekf2/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp index 6e2dae1b9eba..eed210864176 100644 --- a/src/modules/ekf2/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -191,6 +191,32 @@ TEST_F(EkfInitializationTest, initializeWithZeroTiltNotAtRest) learningCorrectAccelBias(); } +TEST_F(EkfInitializationTest, initializeWithTiltNoGyroBiasEstimate) +{ + const float pitch = math::radians(30.0f); + const float roll = math::radians(-20.0f); + const Eulerf euler_angles_sim(roll, pitch, 0.0f); + const Quatf quat_sim(euler_angles_sim); + + _ekf_wrapper.disableGyroBiasEstimation(); + _sensor_simulator.simulateOrientation(quat_sim); + + _sensor_simulator.runSeconds(_init_tilt_period); + + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); + + initializedOrienationIsMatchingGroundTruth(quat_sim); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); // Fake position fusion obs var when at rest sq(0.5f) + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); + + _sensor_simulator.runSeconds(1.f); + learningCorrectAccelBias(); +} + TEST_F(EkfInitializationTest, gyroBias) { // GIVEN: a healthy filter From 6d819343aad926d2a156b6e028c93dc79d5cba96 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 20 Mar 2024 11:02:08 +0100 Subject: [PATCH 016/652] ekf2: fix direct state measurement update for suboptimal K case The duration of a unit test had to be increased because the incorrect covariance matrix update, was making the unit test passing faster (over-optimistic variance). --- src/modules/ekf2/EKF/ekf.h | 9 +++++++-- src/modules/ekf2/EKF/ekf_helper.cpp | 10 ++++++++-- src/modules/ekf2/test/test_EKF_initialization.cpp | 2 +- 3 files changed, 16 insertions(+), 5 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index edffd17974d0..bc087558e9eb 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -485,9 +485,14 @@ class Ekf final : public EstimatorInterface #else // Efficient implementation of the Joseph stabilized covariance update // Based on "G. J. Bierman. Factorization Methods for Discrete Sequential Estimation. Academic Press, Dover Publications, New York, 1977, 2006" + // P = (I - K * H) * P * (I - K * H).T + K * R * K.T + // = P_temp * (I - H.T * K.T) + K * R * K.T + // = P_temp - P_temp * H.T * K.T + K * R * K.T // Step 1: conventional update - VectorState PH = P * H; + // Compute P_temp and store it in P to avoid allocating more memory + // P is symmetric, so PH == H.T * P.T == H.T * P. Taking the row is faster as matrices are row-major + VectorState PH = P * H; // H is stored as a column vector. H is in fact H.T for (unsigned i = 0; i < State::size; i++) { for (unsigned j = 0; j < State::size; j++) { @@ -496,7 +501,7 @@ class Ekf final : public EstimatorInterface } // Step 2: stabilized update - PH = P * H; + PH = P * H; // H is stored as a column vector. H is in fact H.T for (unsigned i = 0; i < State::size; i++) { for (unsigned j = 0; j <= i; j++) { diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 032d35fb31a6..bb9e901f5760 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -865,18 +865,24 @@ bool Ekf::fuseDirectStateMeasurement(const float innov, const float innov_var, c #else // Efficient implementation of the Joseph stabilized covariance update // Based on "G. J. Bierman. Factorization Methods for Discrete Sequential Estimation. Academic Press, Dover Publications, New York, 1977, 2006" + // P = (I - K * H) * P * (I - K * H).T + K * R * K.T + // = P_temp * (I - H.T * K.T) + K * R * K.T + // = P_temp - P_temp * H.T * K.T + K * R * K.T // Step 1: conventional update + // Compute P_temp and store it in P to avoid allocating more memory + // P is symmetric, so PH == H.T * P.T == H.T * P. Taking the row is faster as matrices are row-major VectorState PH = P.row(state_index); for (unsigned i = 0; i < State::size; i++) { for (unsigned j = 0; j < State::size; j++) { - P(i, j) -= K(i) * PH(j); // P is now not symmetrical if K is not optimal (e.g.: some gains have been zeroed) + P(i, j) -= K(i) * PH(j); // P is now not symmetric if K is not optimal (e.g.: some gains have been zeroed) } } // Step 2: stabilized update - PH = P.row(state_index); + // P (or "P_temp") is not symmetric so we must take the column + PH = P.col(state_index); for (unsigned i = 0; i < State::size; i++) { for (unsigned j = 0; j <= i; j++) { diff --git a/src/modules/ekf2/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp index eed210864176..142a4ea3ef73 100644 --- a/src/modules/ekf2/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -346,7 +346,7 @@ TEST_F(EkfInitializationTest, initializeWithTiltNotAtRest) _ekf->set_vehicle_at_rest(false); _sensor_simulator.simulateOrientation(quat_sim); //_sensor_simulator.runSeconds(_init_tilt_period); - _sensor_simulator.runSeconds(7); + _sensor_simulator.runSeconds(10); EXPECT_TRUE(_ekf->control_status_flags().tilt_align); From 638e17d5518ead549aa667a9db18960d35177378 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 20 Mar 2024 11:13:42 +0100 Subject: [PATCH 017/652] ekf: update change indicator --- .../test/change_indication/ekf_gsf_reset.csv | 754 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 666 ++++++++-------- 2 files changed, 710 insertions(+), 710 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 93742373c006..17437ae7216c 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -12,380 +12,380 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00055,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00088,-0.064,8.4e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.005,0.0013,-0.078,8.4e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00048,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0037,0.00083,-0.093,0.00014,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.95,0.95,2,0.14,0.14,2.1,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0064,0.0012,-0.11,0.00014,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,2,0.21,0.21,2.6,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1690000,1,-0.011,-0.014,0.00012,0.028,-0.0001,-0.19,0.0045,0.00062,-0.13,0.0002,-0.00087,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,2,0.14,0.14,3,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.002,-0.2,0.0075,0.00054,-0.15,0.0002,-0.00087,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00038,1.3,1.3,2,0.21,0.21,3.5,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00087,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,2,0.31,0.31,4.1,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0081,-0.00027,-0.19,0.00021,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00034,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00021,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2190000,1,-0.011,-0.014,5.8e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.021,0.00031,1.2,1.2,2.1,0.2,0.2,6,0.0056,0.0056,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,2.1,0.3,0.3,6.7,0.0056,0.0056,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0086,-0.29,0.0074,-0.0015,-0.3,8.9e-05,-0.0025,-5.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,8.9e-05,-0.0025,-5.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2590000,1,-0.011,-0.013,5.8e-05,0.027,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.5e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.88,0.88,2.1,0.18,0.18,9.1,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2690000,1,-0.011,-0.013,5.4e-05,0.031,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.5e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2790000,1,-0.011,-0.013,4.8e-05,0.024,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.012,0.012,0.00024,0.76,0.76,2.2,0.16,0.16,11,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2890000,1,-0.011,-0.013,-1.9e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.94,0.94,2.2,0.23,0.23,12,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.01,0.01,0.00022,0.66,0.66,2.2,0.15,0.15,13,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3090000,1,-0.011,-0.013,4.8e-05,0.025,-0.011,-0.38,0.0081,-0.0031,-0.53,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.81,0.81,2.2,0.22,0.22,14,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3190000,1,-0.011,-0.013,-8.9e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0089,0.0089,0.00021,0.58,0.58,2.3,0.14,0.14,15,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3290000,1,-0.011,-0.013,3.1e-05,0.023,-0.01,-0.4,0.0074,-0.0031,-0.61,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0097,0.0097,0.00022,0.72,0.72,2.3,0.2,0.2,16,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3390000,1,-0.011,-0.012,2.6e-06,0.018,-0.0091,-0.42,0.005,-0.0021,-0.65,-0.00045,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0079,0.0079,0.00019,0.52,0.52,2.3,0.14,0.14,18,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3490000,1,-0.011,-0.013,-4.9e-06,0.022,-0.012,-0.43,0.007,-0.0031,-0.69,-0.00045,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.64,0.64,2.3,0.19,0.19,19,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3590000,1,-0.011,-0.012,1.8e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.48,0.48,2.4,0.13,0.13,20,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3690000,1,-0.011,-0.012,0.00014,0.02,-0.014,-0.46,0.0066,-0.0035,-0.78,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.58,0.58,2.4,0.17,0.17,22,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.44,0.44,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.0061,-0.004,-0.87,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.54,0.54,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0074,0.0074,0.00019,0.65,0.65,2.5,0.22,0.22,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0057,-0.0041,-0.97,-0.0008,-0.0048,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00017,0.5,0.5,2.5,0.16,0.16,28,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.0008,-0.0048,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00018,0.6,0.6,2.5,0.21,0.21,29,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4290000,1,-0.01,-0.012,8.2e-05,0.016,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00093,-0.0049,-7.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00016,0.46,0.46,2.6,0.15,0.15,31,0.00094,0.00095,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00093,-0.0049,-7.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00017,0.55,0.55,2.6,0.2,0.2,33,0.00094,0.00095,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.0051,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.43,0.43,2.6,0.14,0.14,34,0.00077,0.00077,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0066,-0.0047,-1.2,-0.001,-0.0051,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.51,0.51,2.7,0.19,0.19,36,0.00077,0.00077,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4690000,1,-0.01,-0.012,0.0002,0.013,-0.0094,-0.6,0.0047,-0.0033,-1.3,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.004,0.004,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00062,0.00062,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4790000,1,-0.01,-0.012,0.00019,0.015,-0.011,-0.61,0.0061,-0.0043,-1.4,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0043,0.0043,0.00016,0.47,0.47,2.7,0.18,0.18,40,0.00062,0.00062,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4890000,1,-0.01,-0.011,0.00017,0.012,-0.0095,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0035,0.0035,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00049,0.00049,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4990000,1,-0.01,-0.011,0.00015,0.014,-0.01,-0.64,0.0057,-0.0041,-1.5,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00015,0.43,0.43,2.8,0.17,0.17,44,0.00049,0.00049,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5090000,1,-0.01,-0.011,0.0002,0.011,-0.0078,-0.66,0.004,-0.0029,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00014,0.34,0.34,2.8,0.12,0.12,47,0.00039,0.00039,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5190000,1,-0.01,-0.011,0.00022,0.012,-0.0091,-0.67,0.0052,-0.0038,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00039,0.00039,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5290000,1,-0.0099,-0.011,0.00021,0.0079,-0.0066,-0.68,0.0036,-0.0027,-1.7,-0.0013,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00031,0.00031,9.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5390000,1,-0.0099,-0.011,0.00027,0.0073,-0.0074,-0.7,0.0043,-0.0034,-1.8,-0.0013,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00014,0.36,0.36,3,0.15,0.15,54,0.00031,0.00031,9.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5490000,1,-0.0097,-0.011,0.00028,0.0047,-0.0055,-0.71,0.0029,-0.0024,-1.8,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00013,0.28,0.28,3,0.11,0.11,56,0.00024,0.00024,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5590000,1,-0.0097,-0.011,0.00026,0.0053,-0.0058,-0.73,0.0034,-0.0029,-1.9,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.33,0.33,3,0.15,0.15,59,0.00024,0.00024,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5690000,1,-0.0096,-0.011,0.00034,0.0034,-0.0032,-0.74,0.0023,-0.002,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00019,0.00019,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5790000,1,-0.0095,-0.011,0.00033,0.0036,-0.0021,-0.75,0.0026,-0.0023,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.002,0.002,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00019,0.00019,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5890000,1,-0.0094,-0.011,0.00031,0.003,-0.0004,0.0028,0.0017,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.24,0.24,9.8,0.1,0.1,0.52,0.00015,0.00015,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5990000,1,-0.0094,-0.011,0.00033,0.0032,0.0011,0.015,0.002,-0.0014,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00012,0.28,0.28,8.8,0.13,0.13,0.33,0.00015,0.00015,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6090000,1,-0.0094,-0.011,0.00032,0.0042,0.0023,-0.011,0.0024,-0.0012,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00013,0.32,0.32,7,0.17,0.17,0.33,0.00015,0.00015,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6190000,1,-0.0094,-0.011,0.00024,0.003,0.0046,-0.005,0.0017,-0.00032,-3.7e+02,-0.0015,-0.0057,-7.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00012,0.00012,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6290000,1,-0.0094,-0.011,0.00022,0.0042,0.0047,-0.012,0.0021,0.00013,-3.7e+02,-0.0015,-0.0057,-7.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.29,0.29,3.2,0.16,0.16,0.3,0.00012,0.00012,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6390000,0.77,-0.024,0.0046,-0.63,-0.012,-0.0013,-0.05,0.0011,-0.001,-3.7e+02,-0.0014,-0.0057,-8.1e-05,0,0,-0.0001,-0.097,-0.021,0.51,-0.00012,-0.08,-0.061,0,0,0.0012,0.0012,0.065,0.21,0.21,2.3,0.12,0.12,0.29,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0014,0.00038,0.0014,0.001,0.0014,0.0014,1,1 -6490000,0.78,-0.024,0.005,-0.63,-0.038,-0.012,-0.052,-0.0019,-0.0044,-3.7e+02,-0.0013,-0.0057,-8.5e-05,0,0,-0.00015,-0.1,-0.022,0.51,-0.00039,-0.084,-0.064,0,0,0.0012,0.0012,0.056,0.21,0.21,1.5,0.15,0.15,0.26,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00022,0.0013,0.00092,0.0014,0.0013,1,1 -6590000,0.78,-0.024,0.0052,-0.63,-0.064,-0.021,-0.098,-0.0077,-0.0087,-3.7e+02,-0.0012,-0.0057,-8.8e-05,-3.6e-05,0.00025,2.5e-05,-0.1,-0.023,0.51,-0.00086,-0.085,-0.066,0,0,0.0012,0.0012,0.053,0.22,0.22,1.1,0.18,0.18,0.23,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00017,0.0013,0.00088,0.0013,0.0013,1,1 -6690000,0.78,-0.024,0.0053,-0.63,-0.091,-0.035,-0.075,-0.017,-0.017,-3.7e+02,-0.001,-0.0057,-9.4e-05,9.3e-05,0.00099,-0.0003,-0.1,-0.023,0.5,-0.001,-0.086,-0.067,0,0,0.0012,0.0012,0.051,0.23,0.23,0.78,0.22,0.22,0.21,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00087,0.0013,0.0013,1,1 -6790000,0.78,-0.024,0.0054,-0.63,-0.12,-0.045,-0.11,-0.026,-0.026,-3.7e+02,-0.00089,-0.0057,-9.7e-05,-1.3e-05,0.0015,-6.5e-05,-0.1,-0.023,0.5,-0.00099,-0.086,-0.068,0,0,0.0012,0.0012,0.051,0.25,0.25,0.6,0.26,0.26,0.2,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00086,0.0013,0.0013,1,1 -6890000,0.78,-0.024,0.0054,-0.63,-0.14,-0.053,-0.12,-0.039,-0.033,-3.7e+02,-0.00083,-0.0057,-9.8e-05,-7.5e-05,0.0017,-0.00011,-0.1,-0.023,0.5,-0.001,-0.086,-0.068,0,0,0.0012,0.0012,0.05,0.26,0.26,0.46,0.31,0.31,0.18,9.7e-05,9.7e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00086,0.0013,0.0013,1,1 -6990000,0.78,-0.024,0.0054,-0.63,-0.17,-0.065,-0.12,-0.059,-0.045,-3.7e+02,-0.0007,-0.0058,-0.00011,0.00036,0.0023,-0.00042,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0012,0.0012,0.05,0.28,0.28,0.36,0.36,0.36,0.16,9.6e-05,9.6e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00011,0.0013,0.00085,0.0013,0.0013,1,1 -7090000,0.78,-0.024,0.0056,-0.63,-0.2,-0.077,-0.12,-0.084,-0.062,-3.7e+02,-0.0005,-0.0059,-0.00011,0.00085,0.0031,-0.00078,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0012,0.0013,0.049,0.31,0.31,0.29,0.42,0.42,0.16,9.5e-05,9.6e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.0001,0.0013,0.00085,0.0013,0.0013,1,1 -7190000,0.78,-0.024,0.0057,-0.63,-0.23,-0.085,-0.14,-0.11,-0.073,-3.7e+02,-0.00044,-0.006,-0.00012,0.001,0.0033,-0.00056,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.34,0.33,0.24,0.49,0.48,0.15,9.4e-05,9.5e-05,5.8e-06,0.04,0.04,0.04,0.0013,9.9e-05,0.0013,0.00085,0.0013,0.0013,1,1 -7290000,0.78,-0.024,0.0056,-0.63,-0.25,-0.081,-0.14,-0.13,-0.068,-3.7e+02,-0.00066,-0.006,-0.00011,0.00095,0.0024,-0.0012,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.37,0.36,0.2,0.56,0.55,0.14,9.2e-05,9.3e-05,5.8e-06,0.04,0.04,0.04,0.0013,9.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 -7390000,0.78,-0.024,0.0056,-0.63,-0.28,-0.086,-0.16,-0.16,-0.075,-3.7e+02,-0.0007,-0.0059,-0.00011,0.00082,0.0023,-0.0014,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.18,0.63,0.63,0.13,9.1e-05,9.2e-05,5.8e-06,0.04,0.04,0.039,0.0013,9.2e-05,0.0013,0.00084,0.0013,0.0013,1,1 -7490000,0.78,-0.024,0.0057,-0.63,-0.3,-0.1,-0.16,-0.19,-0.096,-3.7e+02,-0.00051,-0.0059,-0.00011,0.00079,0.0031,-0.0021,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.44,0.43,0.15,0.72,0.71,0.12,8.9e-05,9e-05,5.8e-06,0.04,0.04,0.039,0.0013,9e-05,0.0013,0.00084,0.0013,0.0013,1,1 -7590000,0.78,-0.024,0.0056,-0.63,-0.32,-0.1,-0.16,-0.21,-0.1,-3.7e+02,-0.0006,-0.0058,-0.00011,0.00035,0.0028,-0.003,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0013,0.048,0.47,0.47,0.14,0.81,0.8,0.12,8.6e-05,8.7e-05,5.8e-06,0.04,0.04,0.039,0.0013,8.7e-05,0.0013,0.00084,0.0013,0.0013,1,1 -7690000,0.78,-0.024,0.0056,-0.63,-0.35,-0.12,-0.16,-0.24,-0.12,-3.7e+02,-0.00048,-0.0058,-0.00011,0.00031,0.0033,-0.005,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0014,0.048,0.52,0.51,0.13,0.91,0.9,0.11,8.4e-05,8.5e-05,5.8e-06,0.04,0.04,0.039,0.0013,8.6e-05,0.0013,0.00084,0.0013,0.0013,1,1 -7790000,0.78,-0.024,0.0058,-0.63,-0.39,-0.12,-0.16,-0.3,-0.14,-3.7e+02,-0.00043,-0.006,-0.00012,0.00098,0.0036,-0.007,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0014,0.0014,0.048,0.56,0.55,0.12,1,1,0.11,8.1e-05,8.2e-05,5.8e-06,0.04,0.04,0.038,0.0013,8.4e-05,0.0013,0.00084,0.0013,0.0013,1,1 -7890000,0.78,-0.025,0.0058,-0.63,-0.41,-0.13,-0.15,-0.33,-0.15,-3.7e+02,-0.00039,-0.0059,-0.00012,0.00061,0.0039,-0.0095,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0014,0.0014,0.048,0.61,0.6,0.11,1.1,1.1,0.1,7.8e-05,8e-05,5.8e-06,0.04,0.04,0.038,0.0013,8.3e-05,0.0013,0.00084,0.0013,0.0013,1,1 -7990000,0.78,-0.025,0.0057,-0.63,-0.43,-0.14,-0.16,-0.36,-0.16,-3.7e+02,-0.00041,-0.0058,-0.00011,0.00024,0.0038,-0.011,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.66,0.65,0.1,1.3,1.2,0.099,7.5e-05,7.6e-05,5.8e-06,0.04,0.04,0.038,0.0013,8.1e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8090000,0.78,-0.025,0.0057,-0.63,-0.45,-0.15,-0.17,-0.4,-0.18,-3.7e+02,-0.00037,-0.0057,-0.00011,-0.00031,0.004,-0.011,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.72,0.71,0.1,1.4,1.4,0.097,7.2e-05,7.4e-05,5.8e-06,0.04,0.04,0.037,0.0013,8e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8190000,0.78,-0.025,0.0058,-0.63,-0.48,-0.15,-0.17,-0.46,-0.19,-3.7e+02,-0.0004,-0.0058,-0.00011,0.00015,0.004,-0.013,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.78,0.76,0.099,1.6,1.5,0.094,6.8e-05,7e-05,5.7e-06,0.04,0.04,0.037,0.0013,7.9e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8290000,0.78,-0.025,0.006,-0.63,-0.022,-0.005,-0.17,-0.47,-0.2,-3.7e+02,-0.00028,-0.0059,-0.00012,0.00023,0.0041,-0.017,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.092,6.5e-05,6.7e-05,5.7e-06,0.04,0.04,0.036,0.0013,7.8e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8390000,0.78,-0.025,0.0059,-0.63,-0.048,-0.012,-0.17,-0.47,-0.2,-3.7e+02,-0.00026,-0.0058,-0.00012,0.00023,0.0041,-0.021,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.2e-05,6.4e-05,5.7e-06,0.04,0.04,0.035,0.0013,7.8e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8490000,0.78,-0.025,0.006,-0.63,-0.075,-0.019,-0.17,-0.48,-0.2,-3.7e+02,-0.00026,-0.0058,-0.00012,0.00023,0.0041,-0.025,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,5.8e-05,6.1e-05,5.7e-06,0.04,0.04,0.034,0.0013,7.7e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8590000,0.78,-0.025,0.0059,-0.63,-0.099,-0.026,-0.16,-0.48,-0.2,-3.7e+02,-0.0005,-0.006,-0.00012,0.00023,0.0041,-0.029,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.5e-05,5.7e-05,5.7e-06,0.04,0.04,0.034,0.0013,7.6e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8690000,0.78,-0.025,0.0058,-0.63,-0.12,-0.034,-0.16,-0.49,-0.21,-3.7e+02,-0.00048,-0.0058,-0.00011,0.00023,0.0041,-0.034,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,35,35,0.088,5.2e-05,5.5e-05,5.7e-06,0.04,0.04,0.033,0.0013,7.6e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8790000,0.78,-0.025,0.006,-0.63,-0.15,-0.041,-0.15,-0.5,-0.21,-3.7e+02,-0.00044,-0.0058,-0.00011,0.00023,0.0041,-0.04,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,4.9e-05,5.1e-05,5.7e-06,0.04,0.04,0.032,0.0013,7.5e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8890000,0.78,-0.025,0.0061,-0.63,-0.17,-0.046,-0.15,-0.51,-0.21,-3.7e+02,-0.00044,-0.0059,-0.00012,0.00023,0.0041,-0.044,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.095,28,28,0.086,4.6e-05,4.8e-05,5.7e-06,0.04,0.04,0.03,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1 -8990000,0.78,-0.025,0.0062,-0.63,-0.2,-0.05,-0.14,-0.53,-0.21,-3.7e+02,-0.00036,-0.006,-0.00012,0.00023,0.0041,-0.05,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,30,30,0.087,4.4e-05,4.6e-05,5.7e-06,0.04,0.04,0.029,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1 -9090000,0.78,-0.025,0.0062,-0.63,-0.22,-0.053,-0.14,-0.53,-0.22,-3.7e+02,-0.00043,-0.0061,-0.00012,0.00023,0.0041,-0.052,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.1e-05,4.3e-05,5.7e-06,0.04,0.04,0.028,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1 -9190000,0.78,-0.025,0.006,-0.63,-0.25,-0.066,-0.14,-0.55,-0.22,-3.7e+02,-0.00041,-0.0058,-0.00011,0.00023,0.0041,-0.055,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,3.8e-05,4e-05,5.7e-06,0.04,0.04,0.027,0.0013,7.3e-05,0.0013,0.00084,0.0013,0.0013,1,1 -9290000,0.78,-0.025,0.0061,-0.63,-0.27,-0.071,-0.13,-0.56,-0.22,-3.7e+02,-0.00036,-0.0058,-0.00011,0.00023,0.0041,-0.06,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,3.6e-05,3.8e-05,5.7e-06,0.04,0.04,0.025,0.0013,7.3e-05,0.0013,0.00084,0.0013,0.0013,1,1 -9390000,0.78,-0.025,0.0062,-0.63,-0.3,-0.08,-0.13,-0.59,-0.23,-3.7e+02,-0.00032,-0.0058,-0.00012,0.00023,0.0041,-0.063,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,26,26,0.086,3.4e-05,3.6e-05,5.7e-06,0.04,0.04,0.024,0.0013,7.2e-05,0.0013,0.00084,0.0013,0.0013,1,1 -9490000,0.78,-0.026,0.0061,-0.63,-0.31,-0.087,-0.13,-0.59,-0.23,-3.7e+02,-0.00027,-0.0056,-0.00011,0.00023,0.0041,-0.067,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,19,19,0.091,22,22,0.085,3.2e-05,3.4e-05,5.7e-06,0.04,0.04,0.023,0.0013,7.2e-05,0.0013,0.00083,0.0013,0.0013,1,1 -9590000,0.78,-0.025,0.0059,-0.63,-0.33,-0.095,-0.12,-0.62,-0.24,-3.7e+02,-0.0004,-0.0056,-0.00011,0.00023,0.0041,-0.07,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,19,19,0.09,25,25,0.085,3e-05,3.2e-05,5.7e-06,0.04,0.04,0.022,0.0013,7.2e-05,0.0013,0.00083,0.0013,0.0013,1,1 -9690000,0.78,-0.025,0.006,-0.63,-0.33,-0.092,-0.12,-0.61,-0.24,-3.7e+02,-0.00046,-0.0058,-0.00011,0.00023,0.0041,-0.075,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,17,17,0.089,22,22,0.086,2.8e-05,3e-05,5.7e-06,0.04,0.04,0.02,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1 -9790000,0.78,-0.025,0.006,-0.63,-0.36,-0.1,-0.11,-0.65,-0.25,-3.7e+02,-0.00044,-0.0057,-0.00011,0.00023,0.0041,-0.08,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,17,17,0.087,25,25,0.085,2.6e-05,2.8e-05,5.7e-06,0.04,0.04,0.019,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1 -9890000,0.78,-0.025,0.0059,-0.63,-0.36,-0.1,-0.1,-0.64,-0.25,-3.7e+02,-0.0005,-0.0057,-0.00011,0.00023,0.0041,-0.083,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.084,22,22,0.085,2.5e-05,2.6e-05,5.7e-06,0.04,0.04,0.018,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1 -9990000,0.78,-0.025,0.006,-0.63,-0.39,-0.11,-0.097,-0.67,-0.26,-3.7e+02,-0.00052,-0.0057,-0.00011,0.00023,0.0041,-0.086,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.083,25,25,0.086,2.3e-05,2.5e-05,5.7e-06,0.04,0.04,0.017,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10090000,0.78,-0.025,0.0058,-0.63,-0.41,-0.11,-0.093,-0.71,-0.27,-3.7e+02,-0.0006,-0.0057,-0.00011,0.00023,0.0041,-0.089,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.081,28,28,0.085,2.2e-05,2.3e-05,5.7e-06,0.04,0.04,0.016,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10190000,0.78,-0.025,0.0061,-0.63,-0.41,-0.11,-0.093,-0.7,-0.26,-3.7e+02,-0.00061,-0.0059,-0.00011,0.00023,0.0041,-0.09,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,14,14,0.078,24,24,0.084,2.1e-05,2.2e-05,5.7e-06,0.04,0.04,0.015,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10290000,0.78,-0.025,0.0063,-0.63,-0.44,-0.11,-0.08,-0.74,-0.27,-3.7e+02,-0.00062,-0.006,-0.00011,0.00023,0.0041,-0.096,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,14,14,0.076,27,27,0.085,1.9e-05,2.1e-05,5.7e-06,0.04,0.04,0.014,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10390000,0.78,-0.025,0.0064,-0.63,-0.016,-0.026,0.0097,-0.00026,-0.0021,-3.7e+02,-0.00059,-0.006,-0.00011,0.00018,0.0044,-0.099,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,0.25,0.25,0.56,0.25,0.25,0.078,1.8e-05,2e-05,5.7e-06,0.04,0.039,0.013,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10490000,0.78,-0.025,0.0065,-0.63,-0.044,-0.032,0.023,-0.0033,-0.005,-3.7e+02,-0.0006,-0.006,-0.00012,0.00039,0.0046,-0.1,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,0.26,0.26,0.55,0.26,0.26,0.08,1.7e-05,1.9e-05,5.7e-06,0.04,0.039,0.012,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10590000,0.78,-0.025,0.0062,-0.63,-0.042,-0.022,0.026,0.0012,-0.001,-3.7e+02,-0.00075,-0.006,-0.00011,0.00062,0.0031,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.13,0.13,0.27,0.13,0.13,0.073,1.6e-05,1.7e-05,5.7e-06,0.039,0.039,0.012,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10690000,0.78,-0.025,0.0062,-0.63,-0.069,-0.026,0.03,-0.0044,-0.0034,-3.7e+02,-0.00074,-0.006,-0.00011,0.00064,0.0031,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.5e-05,1.7e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10790000,0.78,-0.024,0.006,-0.63,-0.065,-0.021,0.024,5e-05,-0.0014,-3.7e+02,-0.00079,-0.006,-0.00011,0.00084,0.00042,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.4e-05,1.6e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10890000,0.78,-0.024,0.006,-0.63,-0.092,-0.027,0.02,-0.0078,-0.0038,-3.7e+02,-0.00079,-0.006,-0.00011,0.0008,0.00041,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.4e-05,1.5e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.8e-05,0.0013,0.00083,0.0013,0.0013,1,1 -10990000,0.78,-0.024,0.0055,-0.63,-0.08,-0.021,0.014,-0.0033,-0.0021,-3.7e+02,-0.00082,-0.0059,-0.0001,0.0011,-0.0047,-0.11,-0.1,-0.023,0.5,-0.001,-0.087,-0.069,0,0,0.0013,0.0014,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.3e-05,1.4e-05,5.7e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 -11090000,0.78,-0.024,0.0053,-0.63,-0.1,-0.029,0.019,-0.012,-0.0048,-3.7e+02,-0.00085,-0.0058,-9.9e-05,0.00083,-0.0047,-0.11,-0.1,-0.023,0.5,-0.00098,-0.087,-0.069,0,0,0.0013,0.0014,0.048,0.099,0.1,0.11,0.11,0.11,0.074,1.2e-05,1.3e-05,5.7e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 -11190000,0.78,-0.023,0.0047,-0.63,-0.09,-0.022,0.0078,-0.0044,-0.0017,-3.7e+02,-0.00094,-0.0059,-9.5e-05,0.0015,-0.012,-0.11,-0.11,-0.023,0.5,-0.00093,-0.087,-0.069,0,0,0.0012,0.0013,0.048,0.083,0.083,0.084,0.11,0.11,0.069,1.1e-05,1.2e-05,5.7e-06,0.037,0.037,0.011,0.0013,6.8e-05,0.0013,0.00081,0.0013,0.0013,1,1 -11290000,0.78,-0.023,0.0048,-0.63,-0.11,-0.025,0.0076,-0.015,-0.0038,-3.7e+02,-0.00089,-0.0059,-9.9e-05,0.0016,-0.011,-0.11,-0.11,-0.023,0.5,-0.00097,-0.087,-0.069,0,0,0.0012,0.0012,0.047,0.098,0.098,0.078,0.12,0.12,0.072,1.1e-05,1.2e-05,5.7e-06,0.037,0.037,0.01,0.0013,6.7e-05,0.0013,0.00081,0.0013,0.0013,1,1 -11390000,0.78,-0.022,0.0042,-0.63,-0.098,-0.02,0.002,-0.0023,-0.00077,-3.7e+02,-0.00099,-0.006,-9.6e-05,0.0016,-0.018,-0.11,-0.11,-0.023,0.5,-0.001,-0.088,-0.069,0,0,0.0011,0.0011,0.047,0.079,0.079,0.063,0.082,0.082,0.068,1e-05,1.1e-05,5.7e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.0008,0.0013,0.0013,1,1 -11490000,0.78,-0.022,0.0044,-0.63,-0.12,-0.022,0.0029,-0.013,-0.0025,-3.7e+02,-0.00095,-0.0061,-0.0001,0.0016,-0.018,-0.11,-0.11,-0.023,0.5,-0.0011,-0.088,-0.069,0,0,0.0011,0.0011,0.047,0.094,0.094,0.058,0.089,0.089,0.069,9.6e-06,1e-05,5.7e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 -11590000,0.78,-0.021,0.0038,-0.63,-0.097,-0.019,-0.003,-0.0042,-0.00076,-3.7e+02,-0.001,-0.0061,-9.9e-05,0.0014,-0.025,-0.11,-0.11,-0.023,0.5,-0.0011,-0.088,-0.069,0,0,0.00095,0.00099,0.047,0.078,0.078,0.049,0.068,0.068,0.066,9.1e-06,9.8e-06,5.7e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00078,0.0013,0.0013,1,1 -11690000,0.78,-0.021,0.0039,-0.63,-0.11,-0.022,-0.0074,-0.015,-0.0027,-3.7e+02,-0.00094,-0.0061,-0.0001,0.0014,-0.025,-0.11,-0.11,-0.023,0.5,-0.0012,-0.088,-0.069,0,0,0.00095,0.00099,0.047,0.092,0.092,0.046,0.075,0.075,0.066,8.6e-06,9.4e-06,5.7e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00078,0.0013,0.0013,1,1 -11790000,0.78,-0.02,0.0034,-0.63,-0.096,-0.014,-0.0092,-0.008,0.0004,-3.7e+02,-0.00097,-0.0061,-9.8e-05,0.0019,-0.031,-0.11,-0.11,-0.023,0.5,-0.0011,-0.089,-0.069,0,0,0.00084,0.00087,0.047,0.076,0.076,0.039,0.06,0.06,0.063,8.1e-06,8.8e-06,5.7e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 -11890000,0.78,-0.02,0.0035,-0.63,-0.11,-0.015,-0.01,-0.019,-0.00091,-3.7e+02,-0.00095,-0.0062,-0.0001,0.0018,-0.031,-0.11,-0.11,-0.023,0.5,-0.0012,-0.089,-0.069,0,0,0.00084,0.00087,0.047,0.089,0.089,0.037,0.067,0.067,0.063,7.8e-06,8.4e-06,5.7e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 -11990000,0.78,-0.019,0.0028,-0.63,-0.092,-0.0097,-0.015,-0.011,0.0014,-3.7e+02,-0.0011,-0.0061,-9.4e-05,0.002,-0.036,-0.11,-0.11,-0.023,0.5,-0.0011,-0.089,-0.069,0,0,0.00075,0.00077,0.047,0.074,0.073,0.033,0.055,0.055,0.061,7.4e-06,8e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00075,0.0013,0.0013,1,1 -12090000,0.78,-0.019,0.0027,-0.63,-0.1,-0.013,-0.021,-0.02,4.4e-05,-3.7e+02,-0.0011,-0.0061,-9.1e-05,0.0022,-0.036,-0.11,-0.11,-0.023,0.5,-0.001,-0.089,-0.069,0,0,0.00075,0.00077,0.047,0.086,0.086,0.031,0.063,0.063,0.061,7e-06,7.6e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00075,0.0013,0.0013,1,1 -12190000,0.78,-0.019,0.0021,-0.63,-0.081,-0.013,-0.016,-0.01,0.00049,-3.7e+02,-0.0011,-0.0061,-9e-05,0.0018,-0.041,-0.11,-0.11,-0.024,0.5,-0.001,-0.09,-0.069,0,0,0.00067,0.00069,0.046,0.07,0.07,0.028,0.052,0.052,0.059,6.7e-06,7.2e-06,5.7e-06,0.032,0.033,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 -12290000,0.78,-0.019,0.0022,-0.63,-0.089,-0.015,-0.015,-0.019,-0.001,-3.7e+02,-0.0011,-0.006,-9e-05,0.0018,-0.042,-0.11,-0.11,-0.024,0.5,-0.001,-0.09,-0.069,0,0,0.00067,0.00069,0.046,0.081,0.081,0.028,0.06,0.06,0.059,6.4e-06,7e-06,5.7e-06,0.032,0.033,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 -12390000,0.78,-0.018,0.0017,-0.63,-0.07,-0.012,-0.013,-0.0093,8.2e-05,-3.7e+02,-0.0011,-0.0061,-8.9e-05,0.0013,-0.046,-0.11,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.0006,0.00062,0.046,0.066,0.066,0.026,0.05,0.05,0.057,6.1e-06,6.6e-06,5.7e-06,0.032,0.032,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 -12490000,0.78,-0.018,0.0019,-0.63,-0.078,-0.013,-0.016,-0.017,-0.00097,-3.7e+02,-0.0011,-0.0061,-9.2e-05,0.001,-0.046,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.0006,0.00062,0.046,0.076,0.076,0.026,0.058,0.058,0.057,5.9e-06,6.4e-06,5.7e-06,0.032,0.032,0.01,0.0012,6.4e-05,0.0012,0.00073,0.0013,0.0012,1,1 -12590000,0.78,-0.018,0.0016,-0.63,-0.071,-0.012,-0.022,-0.014,-0.00011,-3.7e+02,-0.0012,-0.0061,-9e-05,0.0011,-0.048,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00055,0.00057,0.046,0.062,0.062,0.025,0.049,0.049,0.055,5.6e-06,6.1e-06,5.7e-06,0.031,0.032,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1 -12690000,0.78,-0.018,0.0016,-0.63,-0.076,-0.013,-0.025,-0.021,-0.0011,-3.7e+02,-0.0012,-0.0061,-8.9e-05,0.0009,-0.047,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00056,0.00057,0.046,0.071,0.071,0.025,0.057,0.057,0.055,5.4e-06,5.9e-06,5.7e-06,0.031,0.032,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1 -12790000,0.78,-0.018,0.0014,-0.63,-0.07,-0.011,-0.028,-0.018,-0.00038,-3.7e+02,-0.0012,-0.0061,-8.9e-05,0.001,-0.049,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00052,0.00053,0.046,0.058,0.058,0.024,0.048,0.048,0.053,5.1e-06,5.6e-06,5.7e-06,0.031,0.031,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 -12890000,0.78,-0.018,0.0015,-0.63,-0.077,-0.011,-0.027,-0.026,-0.0015,-3.7e+02,-0.0011,-0.0061,-9e-05,0.0011,-0.05,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00052,0.00053,0.046,0.066,0.066,0.025,0.056,0.056,0.054,5e-06,5.5e-06,5.7e-06,0.031,0.031,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 -12990000,0.78,-0.018,0.0011,-0.63,-0.062,-0.0099,-0.028,-0.019,-0.0012,-3.7e+02,-0.0012,-0.0061,-8.7e-05,0.0011,-0.052,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00049,0.0005,0.046,0.058,0.058,0.025,0.058,0.058,0.052,4.8e-06,5.3e-06,5.7e-06,0.031,0.031,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 -13090000,0.78,-0.018,0.0012,-0.63,-0.068,-0.0096,-0.028,-0.026,-0.0019,-3.7e+02,-0.0011,-0.0061,-9e-05,0.0007,-0.053,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00049,0.0005,0.046,0.065,0.065,0.025,0.066,0.066,0.052,4.6e-06,5.1e-06,5.7e-06,0.031,0.031,0.0094,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1 -13190000,0.78,-0.017,0.00095,-0.63,-0.054,-0.0091,-0.025,-0.017,-0.0013,-3.7e+02,-0.0012,-0.0061,-9e-05,0.0004,-0.055,-0.11,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00047,0.00048,0.046,0.057,0.057,0.025,0.067,0.067,0.051,4.4e-06,4.9e-06,5.7e-06,0.031,0.031,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1 -13290000,0.78,-0.017,0.00097,-0.63,-0.059,-0.011,-0.021,-0.023,-0.0026,-3.7e+02,-0.0011,-0.0061,-9e-05,0.00068,-0.055,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00047,0.00048,0.046,0.064,0.064,0.027,0.077,0.077,0.051,4.3e-06,4.7e-06,5.7e-06,0.03,0.031,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1 -13390000,0.78,-0.017,0.00082,-0.63,-0.048,-0.01,-0.017,-0.016,-0.0018,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00081,-0.057,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00045,0.00046,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.1e-06,4.6e-06,5.7e-06,0.03,0.031,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13490000,0.78,-0.017,0.00079,-0.63,-0.051,-0.011,-0.016,-0.021,-0.0031,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00098,-0.057,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00045,0.00046,0.046,0.062,0.062,0.028,0.088,0.088,0.05,3.9e-06,4.4e-06,5.7e-06,0.03,0.03,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13590000,0.78,-0.017,0.00066,-0.63,-0.041,-0.01,-0.018,-0.014,-0.0018,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00069,-0.058,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00043,0.00044,0.046,0.054,0.054,0.028,0.087,0.087,0.05,3.8e-06,4.3e-06,5.7e-06,0.03,0.03,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13690000,0.78,-0.017,0.00066,-0.63,-0.044,-0.013,-0.022,-0.019,-0.0032,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.001,-0.058,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00043,0.00044,0.046,0.059,0.059,0.029,0.098,0.098,0.05,3.7e-06,4.1e-06,5.7e-06,0.03,0.03,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13790000,0.78,-0.017,0.00048,-0.63,-0.032,-0.012,-0.024,-0.0065,-0.0029,-3.7e+02,-0.0012,-0.0061,-8.6e-05,0.00076,-0.059,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.045,0.045,0.029,0.072,0.072,0.049,3.5e-06,4e-06,5.7e-06,0.03,0.03,0.0079,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 -13890000,0.78,-0.017,0.00054,-0.63,-0.036,-0.013,-0.028,-0.01,-0.0043,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.00094,-0.059,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.049,0.049,0.03,0.081,0.081,0.05,3.4e-06,3.9e-06,5.7e-06,0.03,0.03,0.0078,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 -13990000,0.78,-0.017,0.00039,-0.63,-0.027,-0.013,-0.027,-0.0033,-0.004,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.00081,-0.06,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.3e-06,3.8e-06,5.7e-06,0.03,0.03,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 -14090000,0.78,-0.017,0.00034,-0.63,-0.029,-0.014,-0.028,-0.006,-0.0055,-3.7e+02,-0.0012,-0.006,-8.4e-05,0.0011,-0.06,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.043,0.043,0.031,0.07,0.07,0.05,3.2e-06,3.7e-06,5.7e-06,0.03,0.03,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 -14190000,0.78,-0.017,0.00027,-0.63,-0.023,-0.012,-0.03,-0.00016,-0.0036,-3.7e+02,-0.0012,-0.006,-8.2e-05,0.0014,-0.061,-0.12,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,5.6e-06,0.03,0.03,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 -14290000,0.78,-0.017,0.00024,-0.63,-0.024,-0.014,-0.029,-0.0024,-0.0049,-3.7e+02,-0.0012,-0.006,-8.2e-05,0.0014,-0.06,-0.12,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3e-06,3.4e-06,5.7e-06,0.03,0.03,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 -14390000,0.78,-0.017,0.0002,-0.63,-0.019,-0.014,-0.031,0.0017,-0.0036,-3.7e+02,-0.0012,-0.006,-8e-05,0.0019,-0.061,-0.12,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.034,0.034,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,5.6e-06,0.03,0.03,0.0063,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14490000,0.78,-0.017,0.00026,-0.63,-0.021,-0.016,-0.034,-0.00062,-0.0052,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0019,-0.062,-0.12,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.037,0.037,0.032,0.06,0.06,0.051,2.8e-06,3.2e-06,5.6e-06,0.03,0.03,0.0062,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14590000,0.78,-0.016,0.00034,-0.63,-0.021,-0.017,-0.034,-0.0013,-0.0051,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0019,-0.062,-0.12,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.031,0.051,0.051,0.051,2.7e-06,3.2e-06,5.6e-06,0.03,0.03,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14690000,0.78,-0.017,0.00036,-0.63,-0.025,-0.015,-0.031,-0.0037,-0.0068,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0021,-0.062,-0.12,-0.11,-0.024,0.5,-0.0009,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.035,0.035,0.032,0.056,0.056,0.051,2.6e-06,3.1e-06,5.6e-06,0.03,0.03,0.0056,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14790000,0.78,-0.016,0.00037,-0.63,-0.024,-0.015,-0.027,-0.0037,-0.0065,-3.7e+02,-0.0011,-0.006,-8e-05,0.0021,-0.063,-0.12,-0.11,-0.024,0.5,-0.00089,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.03,0.03,0.031,0.049,0.049,0.051,2.6e-06,3e-06,5.6e-06,0.03,0.03,0.0053,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14890000,0.78,-0.016,0.00038,-0.63,-0.027,-0.018,-0.03,-0.0063,-0.0082,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0022,-0.063,-0.12,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,5.6e-06,0.03,0.03,0.0051,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14990000,0.78,-0.016,0.00042,-0.63,-0.025,-0.015,-0.026,-0.0047,-0.0063,-3.7e+02,-0.0011,-0.006,-8e-05,0.0022,-0.063,-0.12,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,5.6e-06,0.029,0.03,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15090000,0.78,-0.016,0.00051,-0.63,-0.026,-0.016,-0.029,-0.0074,-0.0078,-3.7e+02,-0.001,-0.006,-8e-05,0.0021,-0.063,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.3e-06,2.8e-06,5.6e-06,0.029,0.03,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15190000,0.78,-0.016,0.00054,-0.63,-0.025,-0.015,-0.026,-0.0058,-0.0062,-3.7e+02,-0.001,-0.006,-8e-05,0.0021,-0.064,-0.12,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.3e-06,2.7e-06,5.6e-06,0.029,0.03,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15290000,0.78,-0.016,0.00054,-0.63,-0.026,-0.016,-0.024,-0.0083,-0.0078,-3.7e+02,-0.001,-0.006,-7.9e-05,0.0022,-0.063,-0.12,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,5.6e-06,0.029,0.03,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15390000,0.78,-0.016,0.0005,-0.63,-0.025,-0.017,-0.022,-0.0079,-0.008,-3.7e+02,-0.0011,-0.0059,-7.5e-05,0.0026,-0.063,-0.12,-0.11,-0.024,0.5,-0.00082,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.028,0.029,0.029,0.054,0.054,0.051,2.1e-06,2.5e-06,5.6e-06,0.029,0.03,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15490000,0.78,-0.016,0.00052,-0.63,-0.028,-0.017,-0.022,-0.011,-0.0093,-3.7e+02,-0.0011,-0.006,-7.7e-05,0.0023,-0.063,-0.12,-0.11,-0.024,0.5,-0.00083,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.5e-06,5.6e-06,0.029,0.03,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15590000,0.78,-0.016,0.00055,-0.63,-0.026,-0.015,-0.021,-0.0099,-0.0087,-3.7e+02,-0.0011,-0.006,-7.7e-05,0.0021,-0.064,-0.12,-0.11,-0.024,0.5,-0.00082,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2e-06,2.4e-06,5.6e-06,0.029,0.03,0.0035,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -15690000,0.78,-0.016,0.00053,-0.63,-0.027,-0.016,-0.021,-0.012,-0.01,-3.7e+02,-0.0011,-0.006,-7.7e-05,0.0021,-0.063,-0.12,-0.11,-0.024,0.5,-0.00082,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.4e-06,5.6e-06,0.029,0.03,0.0033,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -15790000,0.78,-0.016,0.00052,-0.63,-0.025,-0.015,-0.024,-0.0087,-0.0087,-3.7e+02,-0.0011,-0.006,-7.7e-05,0.0021,-0.064,-0.12,-0.11,-0.024,0.5,-0.00081,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.026,0.027,0.027,0.056,0.057,0.051,1.9e-06,2.3e-06,5.6e-06,0.029,0.03,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -15890000,0.78,-0.016,0.00054,-0.63,-0.026,-0.015,-0.022,-0.011,-0.01,-3.7e+02,-0.0011,-0.006,-7.7e-05,0.0021,-0.064,-0.12,-0.11,-0.024,0.5,-0.00082,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.028,0.029,0.027,0.063,0.063,0.052,1.9e-06,2.3e-06,5.6e-06,0.029,0.03,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -15990000,0.78,-0.016,0.00052,-0.63,-0.024,-0.015,-0.017,-0.0081,-0.0092,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.0023,-0.064,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.024,0.025,0.026,0.052,0.053,0.051,1.8e-06,2.2e-06,5.6e-06,0.029,0.03,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16090000,0.78,-0.016,0.00045,-0.63,-0.026,-0.017,-0.014,-0.01,-0.011,-3.7e+02,-0.0011,-0.006,-7.2e-05,0.0026,-0.064,-0.13,-0.11,-0.024,0.5,-0.00077,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,5.6e-06,0.029,0.03,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16190000,0.78,-0.016,0.00044,-0.63,-0.024,-0.016,-0.013,-0.0077,-0.0086,-3.7e+02,-0.0011,-0.006,-7e-05,0.0027,-0.064,-0.13,-0.11,-0.024,0.5,-0.00075,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.7e-06,2.1e-06,5.6e-06,0.029,0.03,0.0025,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16290000,0.78,-0.016,0.00037,-0.63,-0.026,-0.017,-0.014,-0.01,-0.011,-3.7e+02,-0.0011,-0.0059,-6.7e-05,0.003,-0.064,-0.13,-0.11,-0.024,0.5,-0.00073,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,5.6e-06,0.029,0.03,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16390000,0.78,-0.016,0.0004,-0.63,-0.023,-0.014,-0.013,-0.0078,-0.0083,-3.7e+02,-0.0012,-0.006,-6.6e-05,0.0029,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.021,0.022,0.023,0.047,0.047,0.051,1.6e-06,2e-06,5.6e-06,0.029,0.03,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16490000,0.78,-0.016,0.00035,-0.63,-0.022,-0.015,-0.016,-0.0098,-0.0097,-3.7e+02,-0.0012,-0.006,-6.5e-05,0.0029,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,2e-06,5.6e-06,0.029,0.03,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16590000,0.78,-0.016,0.00032,-0.63,-0.022,-0.011,-0.017,-0.01,-0.0058,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00067,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.022,0.046,0.046,0.051,1.5e-06,1.9e-06,5.6e-06,0.029,0.03,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16690000,0.78,-0.016,0.00036,-0.63,-0.024,-0.012,-0.013,-0.013,-0.0068,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.0028,-0.063,-0.13,-0.11,-0.024,0.5,-0.00067,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.022,0.022,0.022,0.05,0.051,0.051,1.5e-06,1.9e-06,5.6e-06,0.029,0.03,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16790000,0.78,-0.016,0.0004,-0.63,-0.023,-0.0088,-0.012,-0.012,-0.0036,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0029,-0.063,-0.13,-0.11,-0.024,0.5,-0.00062,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,5.6e-06,0.029,0.03,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16890000,0.78,-0.016,0.00039,-0.63,-0.024,-0.0098,-0.0097,-0.015,-0.0044,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0028,-0.063,-0.13,-0.11,-0.024,0.5,-0.00063,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.4e-06,1.8e-06,5.6e-06,0.029,0.03,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16990000,0.78,-0.016,0.00043,-0.63,-0.023,-0.0096,-0.0092,-0.013,-0.0044,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,5.6e-06,0.029,0.029,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17090000,0.78,-0.016,0.00043,-0.63,-0.024,-0.011,-0.0091,-0.015,-0.0054,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,5.6e-06,0.029,0.029,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17190000,0.78,-0.016,0.00037,-0.63,-0.023,-0.014,-0.01,-0.014,-0.0057,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00064,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.3e-06,1.7e-06,5.6e-06,0.029,0.029,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17290000,0.78,-0.016,0.0004,-0.63,-0.025,-0.015,-0.0055,-0.016,-0.0068,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0025,-0.063,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,5.6e-06,0.029,0.029,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17390000,0.78,-0.016,0.00033,-0.63,-0.023,-0.017,-0.0036,-0.014,-0.0071,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.6e-06,5.6e-06,0.029,0.029,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17490000,0.78,-0.016,0.00035,-0.63,-0.025,-0.017,-0.0019,-0.016,-0.0089,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.2e-06,1.6e-06,5.6e-06,0.029,0.029,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17590000,0.78,-0.016,0.00036,-0.63,-0.023,-0.018,0.0035,-0.014,-0.0086,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00063,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17690000,0.78,-0.016,0.00039,-0.63,-0.025,-0.02,0.0029,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.0028,-0.063,-0.13,-0.11,-0.024,0.5,-0.00063,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.018,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17790000,0.78,-0.016,0.00034,-0.63,-0.023,-0.02,0.0016,-0.014,-0.011,-3.7e+02,-0.0013,-0.006,-4.7e-05,0.0031,-0.063,-0.13,-0.11,-0.024,0.5,-0.00059,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.5e-06,5.5e-06,0.029,0.029,0.0011,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1 -17890000,0.78,-0.016,0.00032,-0.63,-0.026,-0.022,0.0017,-0.017,-0.014,-3.7e+02,-0.0012,-0.006,-4.5e-05,0.0033,-0.063,-0.13,-0.11,-0.024,0.5,-0.00059,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.019,0.02,0.016,0.052,0.053,0.048,1.1e-06,1.5e-06,5.5e-06,0.029,0.029,0.0011,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1 -17990000,0.78,-0.016,0.00035,-0.63,-0.025,-0.019,0.0029,-0.015,-0.014,-3.7e+02,-0.0013,-0.006,-4.4e-05,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.00057,-0.091,-0.069,0,0,0.00036,0.00037,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,5.5e-06,0.029,0.029,0.001,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18090000,0.78,-0.016,0.00039,-0.63,-0.026,-0.019,0.0052,-0.018,-0.015,-3.7e+02,-0.0013,-0.006,-4.8e-05,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00059,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.4e-06,5.5e-06,0.029,0.029,0.00098,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18190000,0.78,-0.016,0.0004,-0.63,-0.023,-0.019,0.0065,-0.013,-0.012,-3.7e+02,-0.0013,-0.006,-4.1e-05,0.0031,-0.063,-0.13,-0.11,-0.024,0.5,-0.00055,-0.091,-0.069,0,0,0.00035,0.00037,0.046,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,5.5e-06,0.029,0.029,0.00092,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18290000,0.78,-0.016,0.00049,-0.63,-0.024,-0.019,0.0077,-0.016,-0.014,-3.7e+02,-0.0013,-0.006,-4.3e-05,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00056,-0.091,-0.069,0,0,0.00035,0.00037,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1e-06,1.3e-06,5.5e-06,0.029,0.029,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18390000,0.78,-0.016,0.00045,-0.63,-0.023,-0.02,0.0089,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.0032,-0.064,-0.13,-0.11,-0.024,0.5,-0.00052,-0.091,-0.069,0,0,0.00035,0.00037,0.046,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.3e-06,5.5e-06,0.029,0.029,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18490000,0.78,-0.016,0.00041,-0.63,-0.023,-0.021,0.0085,-0.014,-0.014,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.00052,-0.091,-0.069,0,0,0.00035,0.00037,0.046,0.018,0.019,0.014,0.052,0.053,0.046,9.9e-07,1.3e-06,5.5e-06,0.029,0.029,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18590000,0.78,-0.016,0.0004,-0.63,-0.022,-0.021,0.0066,-0.011,-0.012,-3.7e+02,-0.0013,-0.006,-2.5e-05,0.0034,-0.063,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.014,0.046,0.046,0.045,9.6e-07,1.3e-06,5.5e-06,0.029,0.029,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18690000,0.78,-0.016,0.00046,-0.63,-0.023,-0.021,0.0047,-0.014,-0.014,-3.7e+02,-0.0013,-0.006,-2.7e-05,0.0034,-0.064,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.017,0.018,0.013,0.05,0.05,0.045,9.5e-07,1.2e-06,5.5e-06,0.029,0.029,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18790000,0.78,-0.016,0.00048,-0.63,-0.022,-0.02,0.0044,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-2.3e-05,0.0033,-0.064,-0.13,-0.11,-0.024,0.5,-0.00046,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.013,0.044,0.044,0.045,9.2e-07,1.2e-06,5.4e-06,0.029,0.029,0.00072,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18890000,0.78,-0.016,0.00039,-0.63,-0.022,-0.022,0.005,-0.014,-0.014,-3.7e+02,-0.0013,-0.006,-1.9e-05,0.0035,-0.063,-0.13,-0.11,-0.024,0.5,-0.00045,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.1e-07,1.2e-06,5.4e-06,0.029,0.029,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18990000,0.78,-0.016,0.00033,-0.63,-0.018,-0.022,0.0036,-0.0095,-0.012,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0036,-0.063,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.012,0.042,0.043,0.044,8.8e-07,1.2e-06,5.4e-06,0.029,0.029,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19090000,0.78,-0.016,0.00033,-0.63,-0.018,-0.024,0.0066,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0036,-0.063,-0.13,-0.11,-0.024,0.5,-0.00042,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.012,0.046,0.047,0.044,8.7e-07,1.1e-06,5.4e-06,0.029,0.029,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19190000,0.78,-0.015,0.00028,-0.63,-0.015,-0.023,0.0066,-0.0074,-0.013,-3.7e+02,-0.0013,-0.006,-3.5e-06,0.0036,-0.063,-0.13,-0.11,-0.024,0.5,-0.00038,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.012,0.041,0.042,0.044,8.5e-07,1.1e-06,5.4e-06,0.029,0.029,0.00062,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19290000,0.78,-0.015,0.00028,-0.63,-0.016,-0.023,0.0094,-0.0091,-0.015,-3.7e+02,-0.0013,-0.006,-6.1e-06,0.0035,-0.063,-0.13,-0.11,-0.024,0.5,-0.0004,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.012,0.045,0.046,0.044,8.4e-07,1.1e-06,5.4e-06,0.029,0.029,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19390000,0.78,-0.015,0.00032,-0.63,-0.015,-0.021,0.013,-0.0082,-0.013,-3.7e+02,-0.0013,-0.006,3e-06,0.0036,-0.063,-0.13,-0.11,-0.024,0.5,-0.00036,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.2e-07,1.1e-06,5.4e-06,0.029,0.029,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19490000,0.78,-0.015,0.00027,-0.63,-0.014,-0.022,0.0095,-0.0097,-0.016,-3.7e+02,-0.0013,-0.006,7.4e-06,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,-0.00034,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.1e-07,1.1e-06,5.4e-06,0.029,0.029,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19590000,0.78,-0.015,0.00022,-0.63,-0.013,-0.021,0.0088,-0.0082,-0.014,-3.7e+02,-0.0013,-0.006,2.1e-05,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.0003,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.011,0.04,0.04,0.042,7.8e-07,1e-06,5.3e-06,0.029,0.029,0.00054,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19690000,0.78,-0.015,0.00021,-0.63,-0.013,-0.019,0.01,-0.009,-0.016,-3.7e+02,-0.0013,-0.006,1.8e-05,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,-0.00031,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.043,0.044,0.042,7.7e-07,1e-06,5.3e-06,0.029,0.029,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19790000,0.78,-0.015,0.00017,-0.63,-0.011,-0.017,0.011,-0.0077,-0.014,-3.7e+02,-0.0014,-0.006,2.5e-05,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,-0.00028,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.011,0.039,0.039,0.042,7.6e-07,1e-06,5.3e-06,0.029,0.029,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19890000,0.78,-0.015,0.0002,-0.63,-0.011,-0.019,0.012,-0.0093,-0.017,-3.7e+02,-0.0013,-0.006,3.2e-05,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00026,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.043,0.043,0.042,7.5e-07,9.9e-07,5.3e-06,0.029,0.029,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19990000,0.78,-0.015,0.00021,-0.63,-0.0091,-0.018,0.015,-0.0081,-0.015,-3.7e+02,-0.0013,-0.0059,4.9e-05,0.0043,-0.063,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.01,0.038,0.039,0.041,7.3e-07,9.7e-07,5.3e-06,0.029,0.029,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20090000,0.78,-0.015,0.00016,-0.63,-0.0091,-0.019,0.015,-0.0088,-0.018,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.01,0.042,0.043,0.042,7.2e-07,9.6e-07,5.3e-06,0.029,0.029,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20190000,0.78,-0.015,0.00012,-0.63,-0.0096,-0.017,0.017,-0.009,-0.016,-3.7e+02,-0.0013,-0.0059,7e-05,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,-0.00016,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.01,0.038,0.039,0.041,7e-07,9.3e-07,5.2e-06,0.029,0.029,0.00045,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20290000,0.78,-0.015,0.00013,-0.63,-0.0084,-0.017,0.015,-0.0094,-0.018,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,-0.00016,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,6.9e-07,9.3e-07,5.2e-06,0.029,0.029,0.00044,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20390000,0.78,-0.015,0.00017,-0.63,-0.008,-0.015,0.017,-0.0092,-0.016,-3.7e+02,-0.0013,-0.0059,8.1e-05,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,9e-07,5.2e-06,0.029,0.029,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20490000,0.78,-0.015,0.00013,-0.63,-0.0082,-0.015,0.017,-0.01,-0.017,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,6.7e-07,9e-07,5.2e-06,0.029,0.029,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20590000,0.78,-0.015,0.00013,-0.63,-0.0077,-0.012,0.014,-0.0087,-0.015,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.0045,-0.063,-0.13,-0.11,-0.024,0.5,-0.00011,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0093,0.037,0.038,0.04,6.5e-07,8.7e-07,5.2e-06,0.029,0.029,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20690000,0.78,-0.016,8.6e-05,-0.63,-0.0084,-0.013,0.015,-0.0095,-0.016,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,-0.00011,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.4e-07,8.6e-07,5.2e-06,0.029,0.029,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20790000,0.78,-0.015,6.4e-05,-0.63,-0.0061,-0.012,0.016,-0.008,-0.014,-3.7e+02,-0.0014,-0.0059,9.4e-05,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,-9e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.3e-07,8.4e-07,5.1e-06,0.029,0.029,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20890000,0.78,-0.016,4.6e-05,-0.63,-0.0064,-0.012,0.015,-0.0085,-0.016,-3.7e+02,-0.0013,-0.0059,0.0001,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,-8.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.2e-07,8.4e-07,5.1e-06,0.029,0.029,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20990000,0.78,-0.016,3.1e-05,-0.63,-0.0048,-0.0096,0.015,-0.0082,-0.016,-3.7e+02,-0.0014,-0.0059,0.0001,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,-7.6e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.1e-07,8.2e-07,5.1e-06,0.029,0.029,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21090000,0.78,-0.016,2.5e-05,-0.63,-0.0059,-0.0093,0.016,-0.0091,-0.018,-3.7e+02,-0.0014,-0.0059,0.00011,0.0048,-0.063,-0.13,-0.11,-0.024,0.5,-6.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6e-07,8.1e-07,5.1e-06,0.029,0.029,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21190000,0.78,-0.016,1.9e-05,-0.63,-0.006,-0.009,0.015,-0.0096,-0.018,-3.7e+02,-0.0013,-0.0059,0.00011,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,-5.6e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,5.9e-07,7.9e-07,5e-06,0.029,0.029,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21290000,0.78,-0.016,-6.8e-05,-0.63,-0.0055,-0.0093,0.017,-0.0096,-0.02,-3.7e+02,-0.0014,-0.0059,0.00012,0.0049,-0.063,-0.13,-0.11,-0.024,0.5,-5.1e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.0085,0.053,0.055,0.039,5.9e-07,7.9e-07,5e-06,0.029,0.029,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21390000,0.78,-0.015,-2.1e-05,-0.63,-0.0049,-0.0049,0.016,-0.0084,-0.015,-3.7e+02,-0.0014,-0.0059,0.00013,0.0048,-0.063,-0.13,-0.11,-0.024,0.5,-2.2e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0084,0.046,0.047,0.039,5.7e-07,7.6e-07,5e-06,0.029,0.029,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21490000,0.78,-0.015,-3e-05,-0.63,-0.0055,-0.0057,0.016,-0.0095,-0.016,-3.7e+02,-0.0013,-0.0059,0.00013,0.0049,-0.063,-0.13,-0.11,-0.024,0.5,-1.9e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.017,0.0083,0.05,0.052,0.038,5.7e-07,7.6e-07,5e-06,0.029,0.029,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21590000,0.78,-0.015,7.3e-06,-0.63,-0.0042,-0.0041,0.016,-0.0079,-0.012,-3.7e+02,-0.0013,-0.0059,0.00014,0.0048,-0.063,-0.13,-0.11,-0.024,0.5,4.4e-06,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.0081,0.044,0.045,0.038,5.5e-07,7.4e-07,4.9e-06,0.029,0.029,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21690000,0.78,-0.015,4.5e-07,-0.63,-0.0058,-0.005,0.017,-0.0092,-0.013,-3.7e+02,-0.0013,-0.0059,0.00014,0.0049,-0.064,-0.13,-0.11,-0.024,0.5,1.1e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.5e-07,7.3e-07,4.9e-06,0.029,0.029,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21790000,0.78,-0.015,9.5e-05,-0.63,-0.0049,-0.0028,0.016,-0.0081,-0.0081,-3.7e+02,-0.0013,-0.0059,0.00015,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,4.7e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.3e-07,7.1e-07,4.9e-06,0.029,0.029,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21890000,0.78,-0.015,9.7e-05,-0.63,-0.0055,-0.0036,0.016,-0.0088,-0.0085,-3.7e+02,-0.0013,-0.0059,0.00015,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,5e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,7.1e-07,4.9e-06,0.029,0.029,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21990000,0.78,-0.015,0.00013,-0.63,-0.0054,-0.00082,0.017,-0.0082,-0.0047,-3.7e+02,-0.0013,-0.0059,0.00016,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,8.3e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.2e-07,6.9e-07,4.8e-06,0.029,0.029,0.00029,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -22090000,0.78,-0.015,0.00011,-0.63,-0.0051,-0.0023,0.015,-0.0086,-0.0048,-3.7e+02,-0.0013,-0.0059,0.00016,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,8.3e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.0078,0.044,0.046,0.037,5.1e-07,6.8e-07,4.8e-06,0.029,0.029,0.00029,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -22190000,0.78,-0.015,0.00013,-0.63,-0.0038,-0.003,0.016,-0.0072,-0.0044,-3.7e+02,-0.0014,-0.0059,0.00017,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,9.3e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.046,0.012,0.014,0.0076,0.04,0.041,0.037,5e-07,6.6e-07,4.8e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22290000,0.78,-0.015,9.5e-05,-0.63,-0.0034,-0.0025,0.016,-0.0078,-0.0045,-3.7e+02,-0.0014,-0.0059,0.00017,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,9.2e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.0076,0.043,0.045,0.037,5e-07,6.6e-07,4.8e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22390000,0.78,-0.015,8.7e-05,-0.63,-0.00089,-0.0026,0.017,-0.006,-0.004,-3.7e+02,-0.0014,-0.0059,0.00017,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,9.3e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.012,0.014,0.0075,0.039,0.04,0.037,4.9e-07,6.4e-07,4.7e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22490000,0.78,-0.015,6.5e-05,-0.63,0.00026,-0.0031,0.018,-0.0055,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00017,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,9.2e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.013,0.015,0.0074,0.042,0.044,0.037,4.8e-07,6.4e-07,4.7e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22590000,0.78,-0.015,6.3e-05,-0.63,0.0021,-0.002,0.018,-0.0037,-0.0035,-3.7e+02,-0.0014,-0.0059,0.00018,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,9.8e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.013,0.015,0.0073,0.045,0.046,0.036,4.8e-07,6.3e-07,4.7e-06,0.029,0.029,0.00026,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22690000,0.78,-0.015,1.9e-07,-0.63,0.0036,-0.0032,0.019,-0.0031,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00019,0.0048,-0.063,-0.13,-0.11,-0.024,0.5,9.8e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.014,0.016,0.0073,0.048,0.05,0.036,4.7e-07,6.3e-07,4.7e-06,0.029,0.029,0.00026,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22790000,0.78,-0.015,4.2e-05,-0.63,0.0047,-0.0026,0.02,-0.0025,-0.0029,-3.7e+02,-0.0014,-0.006,0.00017,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,9e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.014,0.016,0.0072,0.051,0.053,0.036,4.6e-07,6.2e-07,4.6e-06,0.029,0.029,0.00025,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22890000,0.78,-0.015,4.8e-05,-0.63,0.0053,-0.0034,0.021,-0.0027,-0.0033,-3.7e+02,-0.0014,-0.006,0.00017,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,9.6e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.015,0.017,0.0072,0.055,0.057,0.036,4.6e-07,6.2e-07,4.6e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22990000,0.78,-0.015,5.5e-05,-0.63,0.005,-0.0035,0.022,-0.0028,-0.004,-3.7e+02,-0.0014,-0.0059,0.00018,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,0.0001,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.015,0.017,0.0071,0.057,0.06,0.036,4.5e-07,6e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23090000,0.78,-0.015,0.00012,-0.63,0.0053,-0.0031,0.023,-0.0025,-0.0035,-3.7e+02,-0.0014,-0.006,0.00017,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,0.00011,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.018,0.007,0.062,0.065,0.036,4.5e-07,6e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23190000,0.78,-0.015,0.0001,-0.63,0.0029,-0.002,0.024,-0.0053,-0.0034,-3.7e+02,-0.0014,-0.006,0.00018,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,0.00013,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.015,0.018,0.0069,0.064,0.067,0.035,4.4e-07,5.9e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23290000,0.78,-0.015,0.00017,-0.63,0.0025,-0.0016,0.025,-0.0056,-0.0039,-3.7e+02,-0.0014,-0.006,0.00018,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,0.00013,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.019,0.0069,0.07,0.073,0.036,4.4e-07,5.9e-07,4.5e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23390000,0.78,-0.015,0.00014,-0.63,-0.00084,-0.0013,0.022,-0.0097,-0.0041,-3.7e+02,-0.0014,-0.006,0.00018,0.0046,-0.063,-0.13,-0.11,-0.024,0.5,0.00015,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.018,0.0068,0.072,0.075,0.035,4.3e-07,5.8e-07,4.5e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23490000,0.78,-0.013,-0.002,-0.63,0.0046,-0.00053,-0.011,-0.01,-0.0051,-3.7e+02,-0.0014,-0.006,0.00019,0.0047,-0.063,-0.13,-0.11,-0.024,0.5,0.00014,-0.091,-0.068,0,0,0.00034,0.00035,0.047,0.017,0.02,0.0068,0.078,0.082,0.035,4.3e-07,5.7e-07,4.5e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23590000,0.78,-0.0041,-0.0063,-0.63,0.015,0.0031,-0.043,-0.0096,-0.0024,-3.7e+02,-0.0013,-0.006,0.00019,0.0046,-0.064,-0.13,-0.11,-0.024,0.5,0.00015,-0.091,-0.068,0,0,0.00034,0.00033,0.047,0.014,0.016,0.0067,0.062,0.064,0.035,4.2e-07,5.5e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23690000,0.78,0.0015,-0.0053,-0.63,0.042,0.017,-0.093,-0.0073,-0.0018,-3.7e+02,-0.0013,-0.006,0.0002,0.0048,-0.064,-0.13,-0.11,-0.024,0.5,8.3e-05,-0.091,-0.068,0,0,0.00033,0.00033,0.047,0.015,0.017,0.0067,0.066,0.069,0.035,4.2e-07,5.5e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23790000,0.78,-0.0021,-0.0027,-0.63,0.063,0.034,-0.15,-0.0072,-0.00047,-3.7e+02,-0.0013,-0.006,0.00021,0.005,-0.064,-0.13,-0.11,-0.024,0.5,-1.3e-05,-0.09,-0.067,0,0,0.00033,0.00033,0.047,0.013,0.015,0.0066,0.055,0.057,0.035,4.1e-07,5.3e-07,4.3e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23890000,0.78,-0.0084,-0.00076,-0.63,0.077,0.046,-0.2,0.0003,0.0036,-3.7e+02,-0.0013,-0.006,0.00021,0.0051,-0.065,-0.13,-0.11,-0.024,0.5,-6.5e-05,-0.09,-0.067,0,0,0.00033,0.00034,0.047,0.014,0.016,0.0066,0.059,0.061,0.035,4.1e-07,5.3e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23990000,0.78,-0.013,0.00014,-0.63,0.072,0.046,-0.25,-0.0051,0.0022,-3.7e+02,-0.0013,-0.0059,0.0002,0.0053,-0.065,-0.13,-0.11,-0.024,0.5,-3.2e-05,-0.09,-0.067,0,0,0.00034,0.00036,0.047,0.014,0.016,0.0066,0.061,0.064,0.035,4e-07,5.2e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -24090000,0.78,-0.012,-0.00099,-0.63,0.072,0.046,-0.3,0.0012,0.0061,-3.7e+02,-0.0013,-0.0059,0.00021,0.0054,-0.065,-0.13,-0.11,-0.024,0.5,-8.2e-05,-0.09,-0.067,0,0,0.00034,0.00035,0.047,0.015,0.017,0.0065,0.066,0.069,0.035,4e-07,5.2e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -24190000,0.78,-0.0096,-0.0018,-0.63,0.07,0.045,-0.35,-0.0059,0.0038,-3.7e+02,-0.0013,-0.0059,0.0002,0.0057,-0.066,-0.13,-0.11,-0.024,0.5,-6.4e-05,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0065,0.068,0.071,0.034,3.9e-07,5.1e-07,4.3e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -24290000,0.78,-0.0087,-0.0022,-0.63,0.077,0.05,-0.4,0.00046,0.0086,-3.7e+02,-0.0013,-0.0059,0.0002,0.0057,-0.066,-0.13,-0.11,-0.024,0.5,-7.7e-05,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.016,0.019,0.0065,0.074,0.077,0.034,3.9e-07,5.1e-07,4.3e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -24390000,0.78,-0.0092,-0.0023,-0.63,0.075,0.048,-0.46,-0.012,0.0019,-3.7e+02,-0.0013,-0.0059,0.00016,0.0063,-0.067,-0.13,-0.11,-0.024,0.5,-6.1e-05,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,3.9e-07,5e-07,4.2e-06,0.029,0.029,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24490000,0.78,-0.0049,-0.0027,-0.63,0.086,0.055,-0.51,-0.0038,0.0071,-3.7e+02,-0.0013,-0.0059,0.00016,0.0063,-0.067,-0.13,-0.11,-0.024,0.5,-8.7e-05,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.017,0.02,0.0064,0.082,0.085,0.034,3.8e-07,5e-07,4.2e-06,0.029,0.029,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24590000,0.78,-0.0015,-0.0028,-0.63,0.09,0.059,-0.56,-0.017,-0.0021,-3.7e+02,-0.0012,-0.0059,0.00015,0.0069,-0.069,-0.13,-0.11,-0.024,0.5,-0.00014,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.8e-07,4.9e-07,4.2e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24690000,0.78,-0.0006,-0.0027,-0.63,0.11,0.075,-0.64,-0.0078,0.0034,-3.7e+02,-0.0012,-0.0059,0.00016,0.0071,-0.069,-0.13,-0.11,-0.024,0.5,-0.00031,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.018,0.021,0.0063,0.09,0.094,0.034,3.8e-07,4.9e-07,4.2e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24790000,0.78,-0.0022,-0.0025,-0.63,0.11,0.084,-0.73,-0.027,-0.0015,-3.7e+02,-0.0012,-0.0059,0.00014,0.0079,-0.071,-0.13,-0.11,-0.025,0.5,-0.00014,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.018,0.021,0.0062,0.092,0.097,0.034,3.7e-07,4.8e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -24890000,0.78,-0.00032,-0.004,-0.63,0.13,0.098,-0.75,-0.016,0.0076,-3.7e+02,-0.0012,-0.0059,0.00013,0.0081,-0.071,-0.13,-0.11,-0.025,0.5,-0.00022,-0.088,-0.068,0,0,0.00033,0.00033,0.046,0.019,0.022,0.0062,0.099,0.1,0.034,3.7e-07,4.8e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -24990000,0.78,0.0014,-0.0056,-0.62,0.13,0.11,-0.81,-0.037,0.00092,-3.7e+02,-0.0012,-0.0059,9.7e-05,0.0091,-0.074,-0.13,-0.11,-0.025,0.5,-2.7e-05,-0.088,-0.068,0,0,0.00033,0.00033,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.7e-07,4.7e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -25090000,0.78,0.00078,-0.006,-0.62,0.16,0.12,-0.86,-0.023,0.013,-3.7e+02,-0.0012,-0.0059,9e-05,0.0093,-0.074,-0.13,-0.11,-0.025,0.5,-3.2e-05,-0.087,-0.068,0,0,0.00033,0.00033,0.045,0.02,0.023,0.0062,0.11,0.11,0.034,3.7e-07,4.7e-07,4.1e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -25190000,0.78,-0.0013,-0.0055,-0.62,0.15,0.11,-0.91,-0.067,-0.01,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.011,-0.078,-0.13,-0.11,-0.025,0.5,-8.3e-06,-0.086,-0.069,0,0,0.00033,0.00032,0.044,0.019,0.023,0.0061,0.11,0.11,0.033,3.6e-07,4.6e-07,4e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1 -25290000,0.78,0.0056,-0.0067,-0.62,0.18,0.13,-0.96,-0.05,0.0014,-3.7e+02,-0.0011,-0.0059,4.9e-05,0.011,-0.078,-0.13,-0.11,-0.025,0.5,-0.00012,-0.086,-0.069,0,0,0.00032,0.00033,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.6e-07,4e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1 -25390000,0.78,0.012,-0.0071,-0.62,0.18,0.13,-1,-0.098,-0.023,-3.7e+02,-0.001,-0.0058,3.9e-06,0.013,-0.083,-0.13,-0.11,-0.025,0.5,-0.00017,-0.085,-0.069,0,0,0.00032,0.00035,0.043,0.02,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1 -25490000,0.78,0.013,-0.0073,-0.63,0.22,0.16,-1.1,-0.079,-0.01,-3.7e+02,-0.001,-0.0058,2.1e-05,0.014,-0.083,-0.13,-0.11,-0.025,0.5,-0.00051,-0.084,-0.069,0,0,0.00032,0.00035,0.043,0.022,0.026,0.0061,0.13,0.13,0.033,3.5e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25590000,0.78,0.011,-0.0071,-0.63,0.25,0.19,-1.1,-0.056,0.0066,-3.7e+02,-0.001,-0.0058,3.1e-05,0.014,-0.084,-0.13,-0.12,-0.025,0.5,-0.00078,-0.084,-0.068,0,0,0.00032,0.00034,0.043,0.023,0.028,0.0061,0.14,0.14,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1 -25690000,0.78,0.018,-0.01,-0.63,0.29,0.21,-1.2,-0.029,0.025,-3.7e+02,-0.001,-0.0058,4.4e-05,0.014,-0.084,-0.13,-0.12,-0.026,0.5,-0.0011,-0.083,-0.067,0,0,0.00032,0.00038,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.2e-05,0.0011,0.00058,0.0011,0.0011,1,1 -25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,0.0032,0.046,-3.7e+02,-0.001,-0.0058,6.7e-05,0.015,-0.085,-0.13,-0.12,-0.026,0.5,-0.0016,-0.081,-0.067,0,0,0.00033,0.00042,0.041,0.027,0.033,0.0061,0.15,0.16,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1 -25890000,0.77,0.025,-0.012,-0.63,0.41,0.28,-1.3,0.042,0.069,-3.7e+02,-0.001,-0.0058,9.3e-05,0.015,-0.085,-0.13,-0.12,-0.026,0.5,-0.0023,-0.08,-0.066,0,0,0.00033,0.00043,0.041,0.029,0.037,0.0061,0.16,0.18,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.1e-05,0.0011,0.00056,0.0011,0.0011,1,1 -25990000,0.77,0.021,-0.012,-0.63,0.47,0.32,-1.3,0.086,0.097,-3.7e+02,-0.001,-0.0058,0.00011,0.015,-0.086,-0.13,-0.12,-0.027,0.5,-0.0027,-0.079,-0.065,0,0,0.00033,0.0004,0.04,0.031,0.04,0.0061,0.18,0.19,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1 -26090000,0.78,0.032,-0.016,-0.63,0.53,0.35,-1.3,0.13,0.13,-3.7e+02,-0.001,-0.0058,9.6e-05,0.016,-0.086,-0.13,-0.12,-0.027,0.5,-0.0026,-0.077,-0.064,0,0,0.00033,0.00049,0.039,0.033,0.043,0.0061,0.19,0.2,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00017,0.00097,4.9e-05,0.0011,0.00054,0.001,0.0011,1,1 -26190000,0.78,0.042,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.17,-3.7e+02,-0.00099,-0.0058,0.00011,0.017,-0.087,-0.13,-0.13,-0.028,0.5,-0.0032,-0.074,-0.062,0,0,0.00035,0.00057,0.038,0.036,0.047,0.0061,0.2,0.22,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00017,0.00094,4.7e-05,0.001,0.00053,0.00098,0.001,1,1 -26290000,0.78,0.044,-0.018,-0.63,0.68,0.45,-1.3,0.25,0.21,-3.7e+02,-0.00099,-0.0058,0.0001,0.018,-0.087,-0.13,-0.13,-0.028,0.49,-0.0035,-0.071,-0.061,0,0,0.00035,0.00059,0.036,0.039,0.052,0.0061,0.21,0.23,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00091,4.6e-05,0.001,0.00052,0.00095,0.001,1,1 -26390000,0.77,0.04,-0.018,-0.63,0.76,0.5,-1.3,0.32,0.25,-3.7e+02,-0.00098,-0.0058,0.00011,0.019,-0.088,-0.13,-0.13,-0.028,0.49,-0.0039,-0.07,-0.06,0,0,0.00035,0.00054,0.035,0.041,0.056,0.0061,0.23,0.25,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00098,1,1 -26490000,0.77,0.057,-0.024,-0.63,0.84,0.56,-1.3,0.4,0.3,-3.7e+02,-0.00098,-0.0058,0.00011,0.02,-0.088,-0.13,-0.13,-0.029,0.49,-0.0041,-0.068,-0.058,0,0,0.00037,0.00074,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1 -26590000,0.77,0.074,-0.029,-0.63,0.96,0.64,-1.3,0.49,0.37,-3.7e+02,-0.00097,-0.0058,8.4e-05,0.022,-0.089,-0.13,-0.13,-0.03,0.49,-0.0036,-0.064,-0.056,0,0,0.0004,0.00097,0.031,0.047,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1 -26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.43,-3.7e+02,-0.00097,-0.0058,9.8e-05,0.023,-0.09,-0.13,-0.14,-0.031,0.49,-0.0046,-0.059,-0.052,0,0,0.0004,0.00097,0.029,0.051,0.073,0.0061,0.28,0.31,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1 -26790000,0.77,0.07,-0.029,-0.64,1.2,0.79,-1.3,0.7,0.51,-3.7e+02,-0.00097,-0.0058,8.1e-05,0.025,-0.089,-0.13,-0.14,-0.032,0.48,-0.0044,-0.056,-0.049,0,0,0.00038,0.00083,0.026,0.054,0.079,0.0061,0.3,0.33,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1 -26890000,0.76,0.093,-0.036,-0.64,1.4,0.87,-1.3,0.84,0.59,-3.7e+02,-0.00096,-0.0058,8.6e-05,0.026,-0.089,-0.13,-0.15,-0.032,0.48,-0.0049,-0.052,-0.047,0,0,0.00043,0.0011,0.024,0.057,0.085,0.0061,0.31,0.35,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1 -26990000,0.76,0.12,-0.041,-0.64,1.5,0.98,-1.3,0.98,0.68,-3.7e+02,-0.00096,-0.0058,7.5e-05,0.028,-0.09,-0.13,-0.15,-0.034,0.48,-0.0052,-0.046,-0.043,0,0,0.00048,0.0014,0.021,0.061,0.091,0.0061,0.33,0.38,0.033,3.6e-07,4.6e-07,3.6e-06,0.029,0.029,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1 -27090000,0.76,0.12,-0.041,-0.64,1.7,1.1,-1.2,1.1,0.78,-3.7e+02,-0.00097,-0.0058,5.8e-05,0.03,-0.09,-0.13,-0.16,-0.035,0.47,-0.0052,-0.041,-0.038,0,0,0.00048,0.0013,0.019,0.064,0.098,0.0061,0.36,0.4,0.033,3.6e-07,4.6e-07,3.6e-06,0.029,0.029,0.00015,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1 -27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.91,-3.7e+02,-0.00097,-0.0058,4e-05,0.031,-0.089,-0.13,-0.16,-0.035,0.47,-0.0049,-0.038,-0.035,0,0,0.00044,0.0011,0.017,0.067,0.1,0.0062,0.38,0.43,0.034,3.6e-07,4.6e-07,3.6e-06,0.029,0.029,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1 -27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00097,-0.0058,3.4e-05,0.032,-0.087,-0.13,-0.16,-0.036,0.47,-0.005,-0.035,-0.033,0,0,0.0004,0.00082,0.015,0.069,0.11,0.0062,0.4,0.46,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1 -27390000,0.76,0.077,-0.03,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00097,-0.0058,2.9e-05,0.032,-0.085,-0.13,-0.17,-0.036,0.47,-0.005,-0.033,-0.032,0,0,0.00037,0.00064,0.014,0.071,0.11,0.0062,0.43,0.49,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1 -27490000,0.76,0.062,-0.026,-0.64,2.2,1.4,-1.2,1.9,1.3,-3.7e+02,-0.00097,-0.0058,2e-05,0.033,-0.083,-0.13,-0.17,-0.037,0.47,-0.0048,-0.032,-0.031,0,0,0.00035,0.00051,0.013,0.071,0.11,0.0062,0.45,0.52,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1 -27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00097,-0.0058,9.3e-06,0.033,-0.081,-0.13,-0.17,-0.037,0.47,-0.0044,-0.031,-0.031,0,0,0.00034,0.00044,0.012,0.072,0.11,0.0062,0.48,0.56,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00044,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1 -27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00097,-0.0058,-8.3e-07,0.033,-0.079,-0.13,-0.17,-0.037,0.47,-0.004,-0.031,-0.031,0,0,0.00034,0.00043,0.011,0.072,0.11,0.0063,0.51,0.59,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1 -27790000,0.77,0.049,-0.021,-0.64,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00097,-0.0058,-1.6e-05,0.034,-0.078,-0.13,-0.17,-0.037,0.47,-0.0035,-0.03,-0.03,0,0,0.00034,0.00043,0.0098,0.073,0.11,0.0063,0.54,0.63,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00015,0.00042,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1 -27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,2,-3.7e+02,-0.00097,-0.0058,-1.6e-05,0.034,-0.076,-0.13,-0.17,-0.037,0.47,-0.0035,-0.03,-0.03,0,0,0.00034,0.00042,0.0093,0.074,0.11,0.0063,0.57,0.67,0.034,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00041,2.2e-05,0.00048,0.00022,0.00043,0.00048,1,1 -27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00097,-0.0058,-1.9e-05,0.034,-0.075,-0.13,-0.17,-0.037,0.47,-0.0035,-0.03,-0.03,0,0,0.00034,0.0004,0.0087,0.075,0.11,0.0064,0.61,0.71,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1 -28090000,0.77,0.057,-0.025,-0.63,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00097,-0.0058,-3.2e-05,0.034,-0.073,-0.13,-0.17,-0.038,0.47,-0.0031,-0.029,-0.03,0,0,0.00034,0.00044,0.0081,0.076,0.11,0.0064,0.64,0.75,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.0004,2.1e-05,0.00048,0.0002,0.00042,0.00047,1,1 -28190000,0.77,0.071,-0.028,-0.63,2.5,1.7,-0.93,3.6,2.4,-3.7e+02,-0.00096,-0.0058,-3.4e-05,0.034,-0.071,-0.13,-0.17,-0.038,0.46,-0.0031,-0.029,-0.03,0,0,0.00035,0.00048,0.0077,0.077,0.11,0.0065,0.68,0.8,0.034,3.7e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1 -28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00096,-0.0058,-4.4e-05,0.034,-0.068,-0.13,-0.17,-0.038,0.46,-0.0028,-0.028,-0.029,0,0,0.00034,0.00042,0.0074,0.076,0.1,0.0065,0.72,0.84,0.034,3.7e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1 -28390000,0.77,0.02,-0.0095,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00097,-0.0058,-5.2e-05,0.034,-0.065,-0.13,-0.17,-0.038,0.46,-0.0027,-0.027,-0.029,0,0,0.00033,0.00036,0.0071,0.076,0.1,0.0066,0.75,0.89,0.033,3.6e-07,4.8e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 -28490000,0.77,0.0016,-0.0026,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00098,-0.0058,-5.9e-05,0.034,-0.063,-0.13,-0.17,-0.038,0.46,-0.0027,-0.027,-0.029,0,0,0.00033,0.00035,0.0068,0.076,0.1,0.0066,0.79,0.94,0.034,3.6e-07,4.8e-07,3.5e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.0004,0.00046,1,1 -28590000,0.77,-0.0021,-0.0012,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00097,-0.0058,-6e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0027,-0.027,-0.029,0,0,0.00033,0.00035,0.0065,0.077,0.1,0.0067,0.83,0.99,0.034,3.6e-07,4.8e-07,3.5e-06,0.028,0.028,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1 -28690000,0.77,-0.003,-0.00065,-0.63,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00098,-0.0058,-6.8e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0026,-0.027,-0.029,0,0,0.00033,0.00035,0.0063,0.077,0.1,0.0067,0.87,1,0.034,3.6e-07,4.8e-07,3.5e-06,0.028,0.028,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1 -28790000,0.77,-0.0033,-0.00044,-0.63,2.2,1.6,1,5,3.5,-3.7e+02,-0.00099,-0.0058,-7.7e-05,0.033,-0.059,-0.12,-0.17,-0.038,0.46,-0.0024,-0.027,-0.029,0,0,0.00033,0.00036,0.006,0.078,0.1,0.0067,0.91,1.1,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 -28890000,0.77,-0.003,-0.00045,-0.63,2.2,1.5,0.99,5.2,3.6,-3.7e+02,-0.001,-0.0058,-8.4e-05,0.033,-0.058,-0.12,-0.17,-0.038,0.46,-0.0024,-0.027,-0.028,0,0,0.00033,0.00036,0.0059,0.079,0.1,0.0068,0.96,1.2,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 -28990000,0.78,-0.0025,-0.00063,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-9.7e-05,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0022,-0.027,-0.028,0,0,0.00033,0.00036,0.0057,0.081,0.1,0.0068,1,1.2,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 -29090000,0.78,-0.002,-0.00079,-0.63,2.1,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.054,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00036,0.0055,0.082,0.11,0.0069,1,1.3,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1 -29190000,0.78,-0.0017,-0.00087,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-0.0001,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00036,0.0054,0.083,0.11,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1 -29290000,0.78,-0.00077,-0.0012,-0.63,1.9,1.4,1,6.1,4.2,-3.7e+02,-0.001,-0.0058,-0.00011,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.002,-0.027,-0.028,0,0,0.00032,0.00036,0.0053,0.085,0.11,0.0069,1.1,1.4,0.034,3.4e-07,4.8e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29390000,0.78,0.00066,-0.0015,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-0.00013,0.03,-0.049,-0.12,-0.17,-0.038,0.46,-0.0017,-0.027,-0.028,0,0,0.00032,0.00036,0.0051,0.086,0.11,0.007,1.2,1.5,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29490000,0.78,0.0019,-0.0019,-0.63,1.8,1.4,1,6.5,4.5,-3.7e+02,-0.001,-0.0058,-0.00013,0.029,-0.048,-0.12,-0.17,-0.038,0.46,-0.0017,-0.027,-0.028,0,0,0.00032,0.00036,0.005,0.088,0.12,0.007,1.3,1.5,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29590000,0.78,0.003,-0.0021,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-0.00013,0.028,-0.046,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00032,0.00036,0.0049,0.09,0.12,0.007,1.3,1.6,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29690000,0.78,0.0037,-0.0024,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-0.00014,0.027,-0.043,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00036,0.0048,0.092,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29790000,0.78,0.0043,-0.0026,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.0011,-0.0058,-0.00014,0.027,-0.04,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.027,0,0,0.00032,0.00036,0.0048,0.094,0.13,0.0071,1.4,1.8,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29890000,0.78,0.0046,-0.0027,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.0011,-0.0058,-0.00015,0.026,-0.036,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00037,0.0047,0.096,0.13,0.0071,1.5,1.9,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00044,1,1 -29990000,0.78,0.0048,-0.0028,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.0011,-0.0058,-0.00016,0.025,-0.033,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00032,0.00037,0.0046,0.098,0.14,0.0071,1.5,2,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00044,1,1 -30090000,0.78,0.0047,-0.0028,-0.63,1.6,1.3,0.94,7.5,5.4,-3.7e+02,-0.0011,-0.0058,-0.00016,0.024,-0.031,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00037,0.0045,0.1,0.14,0.0071,1.6,2,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 -30190000,0.78,0.0045,-0.0027,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.0011,-0.0058,-0.00016,0.023,-0.031,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.028,0,0,0.00031,0.00037,0.0045,0.1,0.15,0.0072,1.7,2.1,0.035,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 -30290000,0.78,0.0043,-0.0026,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.022,-0.029,-0.12,-0.17,-0.038,0.46,-0.001,-0.028,-0.028,0,0,0.00031,0.00037,0.0044,0.1,0.15,0.0072,1.8,2.2,0.035,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 -30390000,0.78,0.0042,-0.0027,-0.63,1.5,1.3,0.9,8,5.7,-3.7e+02,-0.0011,-0.0058,-0.00017,0.021,-0.027,-0.12,-0.17,-0.038,0.46,-0.00098,-0.028,-0.027,0,0,0.00031,0.00037,0.0044,0.11,0.16,0.0072,1.8,2.4,0.034,3.2e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30490000,0.78,0.004,-0.0026,-0.63,1.5,1.2,0.89,8.2,5.9,-3.7e+02,-0.0011,-0.0058,-0.00017,0.02,-0.025,-0.12,-0.17,-0.038,0.46,-0.00097,-0.028,-0.027,0,0,0.00031,0.00037,0.0043,0.11,0.16,0.0072,1.9,2.5,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30590000,0.78,0.0037,-0.0026,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.019,-0.021,-0.12,-0.17,-0.038,0.46,-0.00096,-0.028,-0.027,0,0,0.00031,0.00037,0.0043,0.11,0.17,0.0072,2,2.6,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30690000,0.78,0.0035,-0.0025,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00017,0.018,-0.018,-0.12,-0.17,-0.038,0.46,-0.0009,-0.028,-0.027,0,0,0.00031,0.00038,0.0042,0.11,0.18,0.0072,2.1,2.7,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30790000,0.78,0.0031,-0.0023,-0.63,1.4,1.2,0.83,8.6,6.2,-3.7e+02,-0.0011,-0.0058,-0.00018,0.017,-0.017,-0.12,-0.17,-0.038,0.46,-0.00081,-0.028,-0.027,0,0,0.00031,0.00038,0.0042,0.12,0.18,0.0072,2.1,2.8,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30890000,0.78,0.0028,-0.0023,-0.63,1.4,1.2,0.82,8.8,6.3,-3.7e+02,-0.0011,-0.0058,-0.00018,0.016,-0.015,-0.12,-0.17,-0.038,0.46,-0.00076,-0.028,-0.027,0,0,0.0003,0.00038,0.0042,0.12,0.19,0.0072,2.2,3,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30990000,0.78,0.0024,-0.0022,-0.63,1.3,1.2,0.81,8.9,6.5,-3.7e+02,-0.0011,-0.0058,-0.00019,0.015,-0.011,-0.12,-0.17,-0.038,0.46,-0.0007,-0.028,-0.027,0,0,0.0003,0.00038,0.0041,0.12,0.2,0.0071,2.3,3.1,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -31090000,0.78,0.0019,-0.0021,-0.63,1.3,1.2,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00019,0.014,-0.0084,-0.12,-0.17,-0.038,0.46,-0.0006,-0.028,-0.027,0,0,0.0003,0.00038,0.0041,0.12,0.2,0.0072,2.4,3.2,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -31190000,0.78,0.0017,-0.002,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00019,0.013,-0.0048,-0.12,-0.17,-0.038,0.46,-0.00052,-0.029,-0.027,0,0,0.0003,0.00038,0.0041,0.13,0.21,0.0071,2.5,3.4,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1 -31290000,0.78,0.0012,-0.0019,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00019,0.011,-0.002,-0.12,-0.17,-0.038,0.46,-0.00044,-0.029,-0.027,0,0,0.0003,0.00038,0.0041,0.13,0.22,0.0071,2.6,3.5,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.024,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1 -31390000,0.78,0.00064,-0.0017,-0.63,1.2,1.1,0.79,9.4,6.9,-3.7e+02,-0.0011,-0.0058,-0.00019,0.01,0.00086,-0.12,-0.17,-0.038,0.46,-0.00037,-0.029,-0.027,0,0,0.0003,0.00039,0.004,0.13,0.23,0.0071,2.7,3.7,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.024,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00042,1,1 -31490000,0.78,0.00013,-0.0016,-0.63,1.2,1.1,0.79,9.5,7,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0088,0.0035,-0.12,-0.17,-0.038,0.46,-0.00025,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.13,0.23,0.0071,2.8,3.9,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00042,1,1 -31590000,0.78,-0.00017,-0.0015,-0.63,1.1,1.1,0.78,9.7,7.1,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0075,0.0055,-0.11,-0.17,-0.038,0.46,-0.0002,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.14,0.24,0.007,2.9,4.1,0.035,3.1e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -31690000,0.78,-0.00078,-0.0013,-0.63,1.1,1.1,0.79,9.8,7.2,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0062,0.0082,-0.11,-0.17,-0.038,0.46,-0.00013,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.14,0.25,0.007,3,4.2,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -31790000,0.78,-0.0014,-0.0012,-0.63,1.1,1,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0049,0.011,-0.11,-0.17,-0.038,0.46,-6.7e-05,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.14,0.26,0.007,3.1,4.4,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -31890000,0.78,-0.002,-0.0011,-0.63,1.1,1,0.78,10,7.5,-3.7e+02,-0.0011,-0.0058,-0.00021,0.0036,0.014,-0.11,-0.17,-0.038,0.46,2.1e-05,-0.029,-0.027,0,0,0.00029,0.00039,0.0039,0.15,0.27,0.007,3.2,4.6,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -31990000,0.78,-0.0024,-0.00095,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0012,-0.0058,-0.00021,0.0021,0.018,-0.11,-0.18,-0.038,0.46,0.00013,-0.029,-0.027,0,0,0.00029,0.0004,0.0039,0.15,0.28,0.0069,3.3,4.8,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32090000,0.78,-0.003,-0.00075,-0.63,1,0.99,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00022,0.0006,0.02,-0.11,-0.18,-0.038,0.46,0.00024,-0.029,-0.026,0,0,0.00028,0.0004,0.0039,0.15,0.29,0.0069,3.4,5.1,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32190000,0.78,-0.0038,-0.00056,-0.63,0.97,0.98,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.001,0.024,-0.11,-0.18,-0.038,0.46,0.00038,-0.029,-0.026,0,0,0.00028,0.0004,0.0039,0.15,0.3,0.0069,3.6,5.3,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32290000,0.78,-0.0044,-0.00047,-0.63,0.94,0.96,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0027,0.028,-0.11,-0.18,-0.038,0.46,0.00048,-0.03,-0.026,0,0,0.00028,0.0004,0.0039,0.16,0.31,0.0068,3.7,5.5,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32390000,0.78,-0.0049,-0.00037,-0.63,0.91,0.94,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0036,0.029,-0.11,-0.18,-0.038,0.46,0.00053,-0.03,-0.026,0,0,0.00028,0.0004,0.0039,0.16,0.32,0.0068,3.8,5.8,0.035,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32490000,0.78,-0.0051,-0.00031,-0.63,0.88,0.93,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.005,0.032,-0.11,-0.18,-0.039,0.46,0.00062,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.16,0.33,0.0068,3.9,6,0.035,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 -32590000,0.78,-0.0053,-0.00026,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0058,0.033,-0.11,-0.18,-0.039,0.46,0.00068,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.5e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 -32690000,0.78,-0.0053,-0.00029,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0067,0.035,-0.11,-0.18,-0.039,0.46,0.00075,-0.03,-0.026,0,0,0.00027,0.00041,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -32790000,0.78,-0.0052,-0.00031,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0075,0.036,-0.11,-0.18,-0.039,0.46,0.0008,-0.03,-0.026,0,0,0.00027,0.00041,0.0038,0.13,0.13,0.27,0.26,0.26,0.048,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -32890000,0.78,-0.005,-0.00043,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00025,-0.0083,0.038,-0.11,-0.18,-0.039,0.46,0.0009,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -32990000,0.78,-0.005,-0.00055,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0091,0.039,-0.11,-0.18,-0.039,0.46,0.00092,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -33090000,0.78,-0.005,-0.00052,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0095,0.039,-0.11,-0.18,-0.038,0.46,0.00094,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -33190000,0.78,-0.0036,-0.0038,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0097,0.04,-0.11,-0.18,-0.038,0.46,0.00094,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,5.1e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -33290000,0.82,-0.0015,-0.016,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0094,0.04,-0.11,-0.18,-0.039,0.46,0.00091,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.8e-07,5.1e-07,3.5e-06,0.028,0.021,9.3e-05,0.00035,1.9e-05,0.00041,0.00015,0.00039,0.00041,1,1 -33390000,0.89,-0.0018,-0.013,-0.45,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.014,0.037,-0.11,-0.18,-0.039,0.46,0.0015,-0.028,-0.025,0,0,0.00028,0.00039,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1 -33490000,0.95,-0.00034,-0.0053,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.016,0.037,-0.11,-0.18,-0.04,0.46,0.002,-0.02,-0.025,0,0,0.00031,0.00035,0.0034,0.052,0.055,0.075,0.3,0.3,0.068,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1 -33590000,0.99,-0.0031,0.0014,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00021,-0.016,0.037,-0.11,-0.19,-0.042,0.46,0.0028,-0.013,-0.026,0,0,0.00034,0.00031,0.0029,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00017,9.9e-06,0.00041,9.4e-05,0.00016,0.0004,1,1 -33690000,1,-0.0066,0.0049,0.025,-1.6,-0.86,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.016,0.037,-0.11,-0.19,-0.043,0.46,0.002,-0.0093,-0.026,0,0,0.00037,0.00027,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5.1e-07,3.3e-06,0.027,0.021,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1 -33790000,0.98,-0.0075,0.0068,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.016,0.037,-0.11,-0.2,-0.043,0.46,0.0021,-0.0067,-0.027,0,0,0.00037,0.00025,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,5e-07,3.3e-06,0.027,0.021,9.3e-05,9.6e-05,6.3e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1 -33890000,0.93,-0.0078,0.0082,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.016,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,5e-07,3.3e-06,0.027,0.021,9.3e-05,8e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1 -33990000,0.87,-0.0098,0.0057,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.014,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00026,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.9e-07,3.3e-06,0.027,0.021,9.3e-05,7e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1 -34090000,0.81,-0.011,0.0045,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.0087,0.035,-0.11,-0.2,-0.044,0.46,0.0012,-0.0034,-0.027,0,0,0.00029,0.00028,0.002,0.047,0.056,0.033,0.33,0.33,0.063,2.8e-07,4.9e-07,3.2e-06,0.026,0.021,9.3e-05,6.5e-05,4.8e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1 -34190000,0.76,-0.0084,0.003,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.038,0.052,-0.11,-0.2,-0.044,0.46,0.0013,-0.0028,-0.027,0,0,0.00026,0.00027,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.8e-07,3.2e-06,0.025,0.02,9.2e-05,5.9e-05,4.5e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1 -34290000,0.72,-0.0055,0.0042,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.036,0.05,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00028,0.0018,0.053,0.063,0.027,0.34,0.34,0.06,2.8e-07,4.8e-07,3.2e-06,0.025,0.02,9.2e-05,5.6e-05,4.4e-06,0.0004,1.4e-05,1.6e-05,0.0004,1,1 -34390000,0.7,-0.0027,0.0056,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.00096,-0.0021,-0.027,0,0,0.00024,0.00029,0.0017,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3.2e-06,0.024,0.02,9.2e-05,5.4e-05,4.3e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1 -34490000,0.68,-0.0006,0.0067,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.034,0.049,-0.11,-0.2,-0.044,0.46,0.00084,-0.0021,-0.027,0,0,0.00024,0.00029,0.0017,0.072,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3.2e-06,0.024,0.02,9.3e-05,5.3e-05,4.2e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1 -34590000,0.68,0.00068,0.0076,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.049,-0.11,-0.2,-0.044,0.46,0.00068,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.084,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.8e-07,3.2e-06,0.024,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,1e-05,1.1e-05,0.0004,1,1 -34690000,0.67,0.0015,0.008,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.033,0.048,-0.11,-0.2,-0.044,0.46,0.00071,-0.0018,-0.027,0,0,0.00023,0.0003,0.0017,0.097,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5.1e-05,4.1e-06,0.0004,9.7e-06,1e-05,0.0004,1,1 -34790000,0.67,0.0021,0.0083,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5e-05,4.1e-06,0.0004,9e-06,9.2e-06,0.0004,1,1 -34890000,0.66,0.0022,0.0083,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.033,0.046,-0.11,-0.2,-0.044,0.46,0.00072,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1 -34990000,0.66,-0.0011,0.016,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00082,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.8e-05,4e-06,0.0004,8e-06,8e-06,0.0004,1,1 -35090000,0.66,-0.0012,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.6e-06,7.5e-06,0.0004,1,1 -35190000,0.66,-0.0013,0.016,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00084,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.2,0.27,0.014,0.52,0.55,0.054,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.7e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1 -35290000,0.66,-0.0014,0.016,0.75,-3.2,-2.4,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00087,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.22,0.3,0.013,0.56,0.6,0.052,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1 -35390000,0.66,-0.0014,0.016,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00094,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.25,0.33,0.013,0.61,0.66,0.052,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.7e-06,6.4e-06,0.0004,1,1 -35490000,0.66,-0.0014,0.016,0.75,-3.2,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.27,0.36,0.012,0.66,0.73,0.051,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.4e-06,6.1e-06,0.0004,1,1 -35590000,0.66,-0.0014,0.016,0.75,-3.2,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00095,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.3,0.4,0.011,0.72,0.8,0.05,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,6.2e-06,5.9e-06,0.0004,1,1 -35690000,0.66,-0.0014,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.33,0.43,0.011,0.78,0.89,0.049,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1 -35790000,0.66,-0.0014,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.36,0.47,0.01,0.86,0.99,0.048,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.5e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1 -35890000,0.66,-0.0015,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.033,0.044,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.39,0.51,0.0099,0.94,1.1,0.047,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.8e-06,5.3e-06,0.0004,1,1 -35990000,0.66,-0.0015,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.033,0.044,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.42,0.55,0.0096,1,1.2,0.047,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.7e-06,5.1e-06,0.0004,1,1 -36090000,0.66,-0.0015,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.044,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.46,0.59,0.0093,1.1,1.4,0.046,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.5e-06,5e-06,0.0004,1,1 -36190000,0.66,-0.0016,0.016,0.75,-3.4,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.033,0.043,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.49,0.63,0.009,1.3,1.5,0.045,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.4e-06,4.8e-06,0.0004,1,1 -36290000,0.66,-0.0015,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.53,0.68,0.0088,1.4,1.7,0.045,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.3e-05,3.8e-06,0.00039,5.4e-06,4.7e-06,0.0004,1,1 -36390000,0.66,-0.0016,0.016,0.75,-3.5,-2.9,-0.096,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.56,0.73,0.0085,1.5,1.9,0.044,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5.3e-06,4.6e-06,0.0004,1,1 -36490000,0.66,-0.0017,0.016,0.75,-3.5,-2.9,-0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.031,0.041,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.6,0.77,0.0083,1.7,2.1,0.043,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.3e-05,3.7e-06,0.00039,5.2e-06,4.5e-06,0.0004,1,1 -36590000,0.66,-0.0016,0.016,0.75,-3.6,-3,-0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.64,0.82,0.0082,1.9,2.4,0.042,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5.1e-06,4.3e-06,0.0004,1,1 -36690000,0.66,-0.0017,0.016,0.75,-3.6,-3,-0.072,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.03,0.04,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.68,0.87,0.008,2.1,2.6,0.042,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5.1e-06,4.3e-06,0.0004,1,1 -36790000,0.66,-0.0017,0.016,0.75,-3.7,-3.1,-0.062,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.72,0.93,0.0079,2.3,2.9,0.041,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5e-06,4.2e-06,0.0004,1,1 -36890000,0.66,-0.0017,0.016,0.75,-3.7,-3.1,-0.055,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.77,0.98,0.0078,2.5,3.2,0.041,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5e-06,4.1e-06,0.0004,1,1 -36990000,0.66,-0.0017,0.017,0.75,-3.7,-3.2,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.81,1,0.0077,2.8,3.5,0.04,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1 -37090000,0.66,-0.0017,0.017,0.75,-3.8,-3.2,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.86,1.1,0.0076,3.1,3.9,0.04,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.9e-06,3.9e-06,0.0004,1,1 -37190000,0.66,-0.0017,0.017,0.75,-3.8,-3.3,-0.032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.028,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.9,1.1,0.0075,3.4,4.3,0.039,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.8e-06,3.8e-06,0.0004,1,1 -37290000,0.66,-0.0018,0.017,0.75,-3.8,-3.4,-0.025,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.028,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.95,1.2,0.0075,3.7,4.7,0.039,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.6e-06,0.00039,4.8e-06,3.8e-06,0.0004,1,1 -37390000,0.66,-0.0017,0.017,0.75,-3.9,-3.4,-0.018,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.028,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.0002,0.00028,0.0017,1,1.3,0.0075,4,5.2,0.039,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.6e-06,0.00039,4.8e-06,3.7e-06,0.0004,1,1 -37490000,0.66,-0.0017,0.017,0.75,-3.9,-3.5,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.028,0.035,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1,1.3,0.0074,4.4,5.7,0.038,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 -37590000,0.66,-0.0017,0.017,0.75,-3.9,-3.5,-0.0024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.1,1.4,0.0074,4.8,6.2,0.038,3e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.6e-06,0.0004,1,1 -37690000,0.66,-0.0018,0.017,0.75,-4,-3.6,0.0069,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.026,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.1,1.5,0.0074,5.2,6.8,0.038,3.1e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.5e-06,0.0004,1,1 -37790000,0.66,-0.0018,0.017,0.75,-4,-3.6,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00031,-0.026,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.2,1.5,0.0074,5.7,7.4,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.5e-06,0.0004,1,1 -37890000,0.66,-0.0019,0.017,0.75,-4,-3.7,0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00031,-0.025,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.3,1.6,0.0074,6.2,8.1,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 -37990000,0.66,-0.0019,0.017,0.75,-4.1,-3.7,0.032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00031,-0.025,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.3,1.6,0.0074,6.7,8.8,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 -38090000,0.66,-0.0019,0.017,0.75,-4.1,-3.8,0.042,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00032,-0.024,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.7,0.0074,7.3,9.5,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 -38190000,0.66,-0.0019,0.017,0.75,-4.1,-3.8,0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00032,-0.024,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0074,7.9,10,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.3e-06,0.0004,1,1 -38290000,0.66,-0.0019,0.017,0.75,-4.2,-3.9,0.057,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00032,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.5,11,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.3e-06,0.0004,1,1 -38390000,0.66,-0.0019,0.017,0.75,-4.2,-3.9,0.064,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00032,-0.023,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,9.2,12,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.6e-06,3.2e-06,0.0004,1,1 -38490000,0.66,-0.0019,0.017,0.75,-4.3,-4,0.07,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00032,-0.023,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.6,2,0.0074,9.9,13,0.036,3.1e-07,4.8e-07,3.1e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 -38590000,0.66,-0.0018,0.017,0.75,-4.3,-4,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00032,-0.023,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.7,2.1,0.0075,11,14,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 -38690000,0.66,-0.0019,0.017,0.75,-4.3,-4.1,0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00033,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.00019,0.00026,0.0016,1.7,2.1,0.0075,11,15,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1 -38790000,0.66,-0.0018,0.017,0.75,-4.4,-4.1,0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00033,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.00019,0.00026,0.0016,1.8,2.2,0.0075,12,16,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.7e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1 -38890000,0.66,-0.0019,0.018,0.75,-4.4,-4.2,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00033,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.8,2.3,0.0075,13,17,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.7e-05,3.4e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1 +1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00048,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00038,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00034,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2190000,1,-0.011,-0.014,5.8e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2590000,1,-0.011,-0.013,5.8e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2790000,1,-0.011,-0.013,4.8e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2890000,1,-0.011,-0.013,-1.8e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3090000,1,-0.011,-0.013,4.8e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3190000,1,-0.011,-0.013,-8.9e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00021,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3290000,1,-0.011,-0.013,3.1e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3390000,1,-0.011,-0.012,2.5e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3490000,1,-0.011,-0.013,-5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3590000,1,-0.011,-0.012,1.8e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4290000,1,-0.01,-0.012,8.2e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00016,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00017,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4690000,1,-0.01,-0.012,0.0002,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4790000,1,-0.01,-0.012,0.00019,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5690000,1,-0.0096,-0.011,0.00034,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6090000,1,-0.0094,-0.011,0.00032,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6290000,1,-0.0094,-0.011,0.00022,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6390000,1,-0.0093,-0.011,0.00024,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6590000,1,-0.0094,-0.011,0.00017,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6690000,1,-0.0093,-0.011,9.6e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6790000,0.78,-0.024,0.0049,-0.63,-0.0056,0.0015,-0.11,0.0015,0.00055,-3.7e+02,-0.0014,-0.0057,-8.2e-05,0,0,-5.8e-05,-0.092,-0.02,0.51,-0.00081,-0.075,-0.061,0,0,0.0013,0.0013,0.072,0.18,0.18,0.6,0.11,0.11,0.2,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 +6890000,0.78,-0.025,0.0057,-0.63,-0.03,-0.0077,-0.12,-9e-05,-0.0018,-3.7e+02,-0.0013,-0.0057,-8.3e-05,0,0,-0.00011,-0.1,-0.022,0.51,-0.0011,-0.083,-0.067,0,0,0.0013,0.0013,0.057,0.18,0.18,0.46,0.14,0.14,0.18,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00094,0.0014,0.0013,1,1 +6990000,0.78,-0.025,0.0058,-0.63,-0.059,-0.018,-0.12,-0.0053,-0.0061,-3.7e+02,-0.0012,-0.0057,-8.7e-05,-2.7e-05,-6.9e-05,-0.00041,-0.1,-0.022,0.5,-0.0015,-0.084,-0.067,0,0,0.0013,0.0013,0.053,0.19,0.18,0.36,0.17,0.17,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.0009,0.0014,0.0013,1,1 +7090000,0.78,-0.025,0.0059,-0.63,-0.087,-0.028,-0.12,-0.014,-0.012,-3.7e+02,-0.0011,-0.0057,-9.1e-05,-8.3e-05,-0.00024,-0.00077,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.052,0.19,0.19,0.29,0.2,0.2,0.16,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00089,0.0013,0.0013,1,1 +7190000,0.78,-0.025,0.006,-0.63,-0.11,-0.037,-0.15,-0.024,-0.018,-3.7e+02,-0.001,-0.0057,-9.3e-05,-7.7e-05,-0.00036,-0.00056,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.051,0.21,0.21,0.24,0.23,0.23,0.15,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00088,0.0013,0.0013,1,1 +7290000,0.78,-0.025,0.0059,-0.63,-0.14,-0.04,-0.14,-0.035,-0.019,-3.7e+02,-0.0011,-0.0057,-9e-05,-4.6e-05,-0.00024,-0.0012,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.22,0.22,0.2,0.28,0.28,0.14,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00087,0.0013,0.0013,1,1 +7390000,0.78,-0.025,0.0059,-0.63,-0.16,-0.048,-0.16,-0.049,-0.025,-3.7e+02,-0.0011,-0.0057,-9e-05,8.1e-07,-0.00028,-0.0014,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.18,0.32,0.32,0.13,7.8e-05,7.9e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00087,0.0013,0.0013,1,1 +7490000,0.78,-0.025,0.0059,-0.63,-0.19,-0.061,-0.16,-0.066,-0.038,-3.7e+02,-0.00093,-0.0057,-9.3e-05,1.6e-05,-0.0005,-0.0022,-0.1,-0.023,0.5,-0.0017,-0.085,-0.069,0,0,0.0013,0.0013,0.049,0.27,0.26,0.15,0.37,0.37,0.12,7.8e-05,7.8e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 +7590000,0.78,-0.025,0.0059,-0.63,-0.21,-0.067,-0.16,-0.082,-0.044,-3.7e+02,-0.00093,-0.0056,-9e-05,0.00011,-0.00047,-0.003,-0.1,-0.023,0.5,-0.0016,-0.085,-0.068,0,0,0.0013,0.0013,0.049,0.29,0.29,0.14,0.43,0.43,0.12,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 +7690000,0.78,-0.025,0.0059,-0.63,-0.24,-0.079,-0.16,-0.1,-0.058,-3.7e+02,-0.00082,-0.0056,-9.3e-05,8.3e-05,-0.00057,-0.005,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.32,0.32,0.13,0.49,0.49,0.11,7.6e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 +7790000,0.78,-0.025,0.006,-0.63,-0.27,-0.088,-0.16,-0.14,-0.072,-3.7e+02,-0.00074,-0.0057,-9.9e-05,-0.00013,-0.00063,-0.007,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.35,0.35,0.12,0.56,0.55,0.11,7.5e-05,7.5e-05,4.9e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00086,0.0013,0.0013,1,1 +7890000,0.78,-0.025,0.006,-0.63,-0.29,-0.099,-0.15,-0.16,-0.086,-3.7e+02,-0.00067,-0.0056,-9.8e-05,-8.1e-05,-0.00064,-0.0095,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.39,0.38,0.11,0.63,0.63,0.1,7.4e-05,7.4e-05,4.9e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00086,0.0013,0.0013,1,1 +7990000,0.78,-0.025,0.006,-0.63,-0.32,-0.11,-0.16,-0.19,-0.098,-3.7e+02,-0.00064,-0.0056,-9.7e-05,2.6e-06,-0.00064,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.43,0.42,0.1,0.71,0.71,0.099,7.2e-05,7.3e-05,4.9e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00086,0.0013,0.0013,1,1 +8090000,0.78,-0.025,0.006,-0.63,-0.34,-0.12,-0.17,-0.21,-0.11,-3.7e+02,-0.00058,-0.0054,-9.5e-05,0.00017,-0.00074,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.47,0.46,0.1,0.8,0.8,0.097,7e-05,7.1e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 +8190000,0.78,-0.025,0.0061,-0.63,-0.37,-0.13,-0.17,-0.25,-0.13,-3.7e+02,-0.00056,-0.0055,-9.8e-05,-2.7e-05,-0.00068,-0.013,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.52,0.51,0.099,0.9,0.89,0.094,6.8e-05,6.9e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8290000,0.78,-0.025,0.0061,-0.63,-0.019,-0.0046,-0.17,-0.27,-0.13,-3.7e+02,-0.00042,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.017,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.6e-05,6.7e-05,4.9e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8390000,0.78,-0.025,0.0061,-0.63,-0.046,-0.012,-0.17,-0.27,-0.13,-3.7e+02,-0.00038,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.021,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,6.5e-05,4.9e-06,0.04,0.04,0.035,0.0013,8.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8490000,0.78,-0.026,0.0062,-0.63,-0.073,-0.02,-0.17,-0.27,-0.13,-3.7e+02,-0.00033,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.025,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,6.2e-05,6.3e-05,4.9e-06,0.04,0.04,0.034,0.0013,8.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8590000,0.78,-0.025,0.0062,-0.63,-0.099,-0.028,-0.16,-0.28,-0.14,-3.7e+02,-0.00051,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.029,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.9e-05,6.1e-05,4.9e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8690000,0.78,-0.025,0.0061,-0.63,-0.12,-0.036,-0.16,-0.28,-0.14,-3.7e+02,-0.00047,-0.0055,-9.9e-05,-6.1e-05,-0.00064,-0.034,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,35,35,0.088,5.7e-05,5.9e-05,4.9e-06,0.04,0.04,0.033,0.0013,7.9e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8790000,0.78,-0.026,0.0062,-0.63,-0.15,-0.044,-0.15,-0.3,-0.14,-3.7e+02,-0.0004,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.04,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,5.5e-05,5.6e-05,4.9e-06,0.04,0.04,0.032,0.0013,7.8e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8890000,0.78,-0.026,0.0063,-0.63,-0.18,-0.05,-0.15,-0.3,-0.14,-3.7e+02,-0.00037,-0.0056,-0.00011,-6.1e-05,-0.00064,-0.044,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.095,28,28,0.086,5.2e-05,5.4e-05,4.9e-06,0.04,0.04,0.03,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 +8990000,0.78,-0.026,0.0064,-0.63,-0.21,-0.056,-0.14,-0.32,-0.15,-3.7e+02,-0.00029,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.05,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.096,30,30,0.087,5e-05,5.1e-05,4.9e-06,0.04,0.04,0.029,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9090000,0.78,-0.026,0.0065,-0.63,-0.23,-0.06,-0.14,-0.33,-0.15,-3.7e+02,-0.00033,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.052,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.7e-05,4.9e-05,4.9e-06,0.04,0.04,0.028,0.0013,7.6e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9190000,0.78,-0.026,0.0063,-0.63,-0.25,-0.071,-0.14,-0.35,-0.16,-3.7e+02,-0.00029,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.056,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,4.5e-05,4.6e-05,4.9e-06,0.04,0.04,0.027,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9290000,0.78,-0.026,0.0063,-0.63,-0.27,-0.077,-0.13,-0.35,-0.16,-3.7e+02,-0.00023,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.06,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,4.2e-05,4.4e-05,4.9e-06,0.04,0.04,0.025,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9390000,0.78,-0.026,0.0065,-0.63,-0.3,-0.086,-0.13,-0.38,-0.17,-3.7e+02,-0.00018,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.063,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,21,21,0.093,25,25,0.086,4e-05,4.2e-05,4.9e-06,0.04,0.04,0.024,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9490000,0.78,-0.026,0.0064,-0.63,-0.31,-0.092,-0.13,-0.38,-0.17,-3.7e+02,-0.00011,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.067,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.091,22,22,0.085,3.8e-05,4e-05,4.9e-06,0.04,0.04,0.023,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9590000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.18,-3.7e+02,-0.00024,-0.0053,-0.0001,-6.1e-05,-0.00064,-0.07,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.09,25,25,0.085,3.6e-05,3.7e-05,4.9e-06,0.04,0.04,0.022,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9690000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.17,-3.7e+02,-0.0003,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.075,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.089,22,22,0.086,3.4e-05,3.6e-05,4.9e-06,0.04,0.04,0.02,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9790000,0.78,-0.026,0.0063,-0.63,-0.38,-0.11,-0.1,-0.45,-0.19,-3.7e+02,-0.00026,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.08,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.087,24,24,0.085,3.2e-05,3.4e-05,4.9e-06,0.04,0.04,0.019,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9890000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.1,-0.48,-0.2,-3.7e+02,-0.00033,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.083,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.084,28,28,0.085,3e-05,3.2e-05,4.9e-06,0.04,0.04,0.018,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 +9990000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.096,-0.47,-0.19,-3.7e+02,-0.00035,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.086,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.083,24,24,0.086,2.8e-05,3e-05,4.9e-06,0.04,0.04,0.017,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10090000,0.78,-0.026,0.0062,-0.63,-0.43,-0.12,-0.092,-0.51,-0.2,-3.7e+02,-0.00043,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.089,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.081,27,27,0.085,2.7e-05,2.8e-05,4.9e-06,0.04,0.04,0.016,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10190000,0.78,-0.026,0.0065,-0.63,-0.43,-0.12,-0.092,-0.5,-0.2,-3.7e+02,-0.00044,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.09,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,13,0.078,24,24,0.084,2.5e-05,2.7e-05,4.9e-06,0.04,0.04,0.015,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10290000,0.78,-0.026,0.0067,-0.63,-0.46,-0.12,-0.08,-0.55,-0.21,-3.7e+02,-0.00045,-0.0058,-0.00011,-6.1e-05,-0.00064,-0.096,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,14,0.076,27,27,0.085,2.4e-05,2.5e-05,4.9e-06,0.04,0.04,0.014,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10390000,0.78,-0.026,0.0068,-0.63,-0.017,-0.027,0.0097,-0.00031,-0.0021,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00013,-0.00061,-0.099,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,4.9e-06,0.04,0.04,0.013,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10490000,0.78,-0.026,0.0069,-0.63,-0.047,-0.034,0.023,-0.0035,-0.0051,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00035,-0.00043,-0.1,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.26,0.26,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,4.9e-06,0.04,0.04,0.012,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10590000,0.78,-0.026,0.0066,-0.63,-0.045,-0.023,0.026,0.0012,-0.0011,-3.7e+02,-0.00059,-0.0058,-0.00011,-3.5e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.1e-05,4.9e-06,0.04,0.04,0.012,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10690000,0.78,-0.026,0.0066,-0.63,-0.073,-0.029,0.03,-0.0048,-0.0037,-3.7e+02,-0.00059,-0.0059,-0.00011,-9.8e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.9e-05,2e-05,4.9e-06,0.04,0.04,0.011,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 +10790000,0.78,-0.025,0.0064,-0.63,-0.069,-0.024,0.024,-0.0001,-0.0015,-3.7e+02,-0.00063,-0.0058,-0.00011,0.00028,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.8e-05,1.9e-05,4.8e-06,0.04,0.039,0.011,0.0013,7e-05,0.0013,0.00084,0.0013,0.0013,1,1 +10890000,0.78,-0.025,0.0064,-0.63,-0.097,-0.03,0.02,-0.0084,-0.0042,-3.7e+02,-0.00063,-0.0058,-0.00011,0.0003,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00084,0.0013,0.0013,1,1 +10990000,0.78,-0.025,0.0059,-0.63,-0.085,-0.024,0.014,-0.0037,-0.0024,-3.7e+02,-0.00066,-0.0058,-0.0001,0.0011,-0.009,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.6e-05,1.7e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 +11090000,0.78,-0.025,0.0057,-0.63,-0.11,-0.032,0.019,-0.013,-0.0054,-3.7e+02,-0.00069,-0.0057,-9.6e-05,0.0013,-0.0089,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.1,0.1,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 +11190000,0.78,-0.024,0.0051,-0.63,-0.095,-0.025,0.0078,-0.0051,-0.0021,-3.7e+02,-0.00079,-0.0057,-9.3e-05,0.0019,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.084,0.084,0.084,0.11,0.11,0.069,1.4e-05,1.5e-05,4.8e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 +11290000,0.78,-0.024,0.0052,-0.63,-0.12,-0.029,0.0076,-0.016,-0.0046,-3.7e+02,-0.00074,-0.0058,-9.7e-05,0.0016,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.099,0.099,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,4.8e-06,0.038,0.038,0.01,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 +11390000,0.78,-0.022,0.0045,-0.63,-0.1,-0.024,0.002,-0.0027,-0.00099,-3.7e+02,-0.00084,-0.0059,-9.5e-05,0.0015,-0.022,-0.11,-0.11,-0.023,0.5,-0.0013,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.08,0.08,0.063,0.082,0.082,0.068,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 +11490000,0.78,-0.022,0.0047,-0.63,-0.12,-0.026,0.0029,-0.014,-0.0031,-3.7e+02,-0.0008,-0.006,-0.0001,0.0009,-0.022,-0.11,-0.11,-0.023,0.5,-0.0014,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.095,0.095,0.058,0.089,0.089,0.069,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 +11590000,0.78,-0.022,0.0041,-0.63,-0.1,-0.022,-0.003,-0.0044,-0.00098,-3.7e+02,-0.00085,-0.006,-9.8e-05,0.00079,-0.029,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.078,0.078,0.049,0.068,0.068,0.066,1.1e-05,1.2e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 +11690000,0.78,-0.022,0.0042,-0.63,-0.12,-0.026,-0.0074,-0.016,-0.0033,-3.7e+02,-0.00079,-0.006,-0.0001,0.00062,-0.03,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.093,0.093,0.046,0.075,0.075,0.066,1.1e-05,1.1e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 +11790000,0.78,-0.021,0.0037,-0.63,-0.1,-0.017,-0.0092,-0.0082,0.00018,-3.7e+02,-0.00082,-0.006,-9.7e-05,0.0012,-0.036,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.077,0.076,0.039,0.06,0.06,0.063,1e-05,1.1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 +11890000,0.78,-0.021,0.0038,-0.63,-0.12,-0.019,-0.01,-0.019,-0.0015,-3.7e+02,-0.0008,-0.0061,-9.9e-05,0.00091,-0.036,-0.11,-0.11,-0.023,0.5,-0.0015,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.09,0.09,0.037,0.067,0.067,0.063,9.5e-06,1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 +11990000,0.78,-0.02,0.003,-0.63,-0.095,-0.012,-0.015,-0.011,0.0012,-3.7e+02,-0.00095,-0.0061,-9.3e-05,0.0013,-0.04,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.074,0.074,0.033,0.055,0.055,0.061,9e-06,9.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 +12090000,0.78,-0.02,0.0029,-0.63,-0.11,-0.016,-0.021,-0.021,-0.00045,-3.7e+02,-0.00099,-0.006,-9e-05,0.0018,-0.04,-0.11,-0.11,-0.023,0.5,-0.0013,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.087,0.086,0.031,0.063,0.063,0.061,8.6e-06,9.2e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 +12190000,0.78,-0.019,0.0023,-0.63,-0.084,-0.015,-0.016,-0.01,0.00028,-3.7e+02,-0.00098,-0.006,-8.9e-05,0.0016,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.071,0.071,0.028,0.052,0.052,0.059,8.1e-06,8.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 +12290000,0.78,-0.019,0.0024,-0.63,-0.092,-0.017,-0.015,-0.019,-0.0014,-3.7e+02,-0.00094,-0.006,-8.9e-05,0.0017,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.082,0.082,0.028,0.06,0.06,0.059,7.8e-06,8.4e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 +12390000,0.78,-0.019,0.0019,-0.63,-0.073,-0.014,-0.013,-0.0094,-0.00012,-3.7e+02,-0.00099,-0.006,-8.8e-05,0.0011,-0.05,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.067,0.067,0.026,0.05,0.05,0.057,7.4e-06,8e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 +12490000,0.78,-0.019,0.0021,-0.63,-0.08,-0.016,-0.016,-0.017,-0.0014,-3.7e+02,-0.00096,-0.0061,-9.1e-05,0.00059,-0.05,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.077,0.076,0.026,0.058,0.058,0.057,7.1e-06,7.6e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 +12590000,0.78,-0.018,0.0018,-0.63,-0.073,-0.014,-0.022,-0.014,-0.00033,-3.7e+02,-0.001,-0.0061,-8.8e-05,0.00072,-0.052,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.063,0.063,0.025,0.049,0.049,0.055,6.8e-06,7.3e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.5e-05,0.0012,0.00072,0.0013,0.0012,1,1 +12690000,0.78,-0.018,0.0018,-0.63,-0.079,-0.015,-0.025,-0.021,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.8e-05,0.00038,-0.051,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.071,0.071,0.025,0.057,0.057,0.055,6.5e-06,7e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1 +12790000,0.78,-0.018,0.0016,-0.63,-0.072,-0.012,-0.028,-0.018,-0.0006,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00058,-0.053,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00054,0.00056,0.046,0.059,0.058,0.024,0.048,0.048,0.053,6.2e-06,6.7e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 +12890000,0.78,-0.018,0.0017,-0.63,-0.079,-0.013,-0.027,-0.026,-0.0019,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00062,-0.054,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00055,0.00056,0.046,0.066,0.066,0.025,0.056,0.056,0.054,6e-06,6.5e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 +12990000,0.78,-0.018,0.0013,-0.63,-0.064,-0.012,-0.028,-0.019,-0.0015,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.0009,-0.056,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.059,0.058,0.025,0.058,0.058,0.052,5.7e-06,6.2e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 +13090000,0.78,-0.018,0.0014,-0.63,-0.069,-0.011,-0.028,-0.026,-0.0023,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00025,-0.057,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.065,0.065,0.025,0.066,0.066,0.052,5.5e-06,6e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 +13190000,0.78,-0.018,0.0011,-0.63,-0.055,-0.011,-0.025,-0.017,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.7e-05,-1.3e-05,-0.058,-0.11,-0.11,-0.024,0.5,-0.0016,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.058,0.058,0.025,0.067,0.067,0.051,5.2e-06,5.7e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 +13290000,0.78,-0.018,0.0011,-0.63,-0.06,-0.013,-0.021,-0.024,-0.003,-3.7e+02,-0.001,-0.006,-8.8e-05,0.00039,-0.059,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.064,0.064,0.027,0.077,0.077,0.051,5.1e-06,5.5e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1 +13390000,0.78,-0.017,0.00099,-0.63,-0.049,-0.012,-0.017,-0.016,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00065,-0.06,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.9e-06,5.3e-06,4.8e-06,0.032,0.032,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 +13490000,0.78,-0.017,0.00096,-0.63,-0.053,-0.013,-0.016,-0.022,-0.0034,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00089,-0.061,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.062,0.062,0.028,0.088,0.088,0.05,4.7e-06,5.1e-06,4.8e-06,0.031,0.032,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 +13590000,0.78,-0.017,0.00083,-0.63,-0.043,-0.012,-0.018,-0.014,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00051,-0.062,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.054,0.054,0.028,0.087,0.087,0.05,4.5e-06,5e-06,4.8e-06,0.031,0.032,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 +13690000,0.78,-0.017,0.00081,-0.63,-0.046,-0.015,-0.022,-0.019,-0.0035,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00095,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.06,0.06,0.029,0.098,0.098,0.05,4.3e-06,4.8e-06,4.8e-06,0.031,0.032,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 +13790000,0.78,-0.017,0.00063,-0.63,-0.033,-0.013,-0.024,-0.0063,-0.003,-3.7e+02,-0.0011,-0.006,-8.3e-05,0.00068,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.045,0.045,0.029,0.072,0.072,0.049,4.2e-06,4.6e-06,4.8e-06,0.031,0.031,0.0079,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 +13890000,0.78,-0.017,0.00069,-0.63,-0.037,-0.015,-0.028,-0.01,-0.0045,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00091,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.049,0.049,0.03,0.081,0.081,0.05,4e-06,4.5e-06,4.8e-06,0.031,0.031,0.0078,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 +13990000,0.78,-0.017,0.00054,-0.63,-0.029,-0.014,-0.027,-0.0032,-0.004,-3.7e+02,-0.0011,-0.006,-8.4e-05,0.00078,-0.064,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.9e-06,4.3e-06,4.8e-06,0.031,0.031,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 +14090000,0.78,-0.017,0.00048,-0.63,-0.03,-0.015,-0.028,-0.006,-0.0056,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0012,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.044,0.044,0.031,0.07,0.07,0.05,3.8e-06,4.2e-06,4.8e-06,0.031,0.031,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 +14190000,0.78,-0.017,0.00041,-0.63,-0.024,-0.013,-0.03,-8.4e-05,-0.0036,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0015,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.6e-06,4.1e-06,4.8e-06,0.031,0.031,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 +14290000,0.78,-0.017,0.00037,-0.63,-0.025,-0.015,-0.029,-0.0025,-0.0051,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3.5e-06,3.9e-06,4.8e-06,0.031,0.031,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 +14390000,0.78,-0.017,0.00033,-0.63,-0.02,-0.015,-0.031,0.0017,-0.0037,-3.7e+02,-0.0011,-0.0059,-7.8e-05,0.0021,-0.065,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.034,0.034,0.031,0.053,0.053,0.05,3.4e-06,3.8e-06,4.8e-06,0.031,0.031,0.0063,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 +14490000,0.78,-0.017,0.0004,-0.63,-0.022,-0.018,-0.034,-0.00071,-0.0054,-3.7e+02,-0.001,-0.0059,-7.9e-05,0.0022,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.037,0.037,0.032,0.06,0.06,0.051,3.3e-06,3.7e-06,4.8e-06,0.031,0.031,0.0062,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 +14590000,0.78,-0.017,0.00048,-0.63,-0.023,-0.018,-0.034,-0.0013,-0.0052,-3.7e+02,-0.001,-0.0059,-8e-05,0.0021,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.032,0.032,0.031,0.051,0.051,0.051,3.2e-06,3.6e-06,4.8e-06,0.031,0.031,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 +14690000,0.78,-0.017,0.0005,-0.63,-0.026,-0.017,-0.031,-0.0038,-0.0071,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0024,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.035,0.035,0.032,0.056,0.056,0.051,3.1e-06,3.5e-06,4.8e-06,0.031,0.031,0.0057,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 +14790000,0.78,-0.017,0.00051,-0.63,-0.025,-0.016,-0.027,-0.0038,-0.0066,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0023,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.03,0.03,0.031,0.049,0.049,0.051,3e-06,3.3e-06,4.8e-06,0.031,0.031,0.0053,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 +14890000,0.78,-0.017,0.00052,-0.63,-0.028,-0.019,-0.03,-0.0065,-0.0085,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0025,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.9e-06,3.3e-06,4.8e-06,0.031,0.031,0.0051,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 +14990000,0.78,-0.017,0.00057,-0.63,-0.026,-0.016,-0.026,-0.0049,-0.0065,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.8e-06,3.2e-06,4.8e-06,0.031,0.031,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15090000,0.78,-0.017,0.00066,-0.63,-0.028,-0.017,-0.029,-0.0076,-0.0081,-3.7e+02,-0.00097,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.7e-06,3.1e-06,4.8e-06,0.031,0.031,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15190000,0.78,-0.017,0.00069,-0.63,-0.026,-0.016,-0.026,-0.006,-0.0064,-3.7e+02,-0.00096,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.00041,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.6e-06,3e-06,4.8e-06,0.031,0.031,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15290000,0.78,-0.017,0.00069,-0.63,-0.028,-0.018,-0.024,-0.0086,-0.0082,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0023,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.5e-06,2.9e-06,4.8e-06,0.031,0.031,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15390000,0.78,-0.017,0.00064,-0.63,-0.027,-0.018,-0.022,-0.0082,-0.0083,-3.7e+02,-0.00099,-0.0059,-7.4e-05,0.0028,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.029,0.029,0.029,0.054,0.054,0.051,2.4e-06,2.8e-06,4.8e-06,0.031,0.031,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15490000,0.78,-0.017,0.00066,-0.63,-0.03,-0.018,-0.022,-0.011,-0.0098,-3.7e+02,-0.00099,-0.0059,-7.6e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.4e-06,2.7e-06,4.8e-06,0.031,0.031,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15590000,0.78,-0.017,0.0007,-0.63,-0.028,-0.017,-0.021,-0.01,-0.0091,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0022,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2.3e-06,2.7e-06,4.8e-06,0.031,0.031,0.0035,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15690000,0.78,-0.017,0.00067,-0.63,-0.029,-0.017,-0.021,-0.013,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0021,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.028,0.069,0.069,0.052,2.2e-06,2.6e-06,4.8e-06,0.03,0.031,0.0033,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 +15790000,0.78,-0.017,0.00067,-0.63,-0.026,-0.016,-0.024,-0.009,-0.009,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.026,0.027,0.027,0.056,0.057,0.051,2.2e-06,2.5e-06,4.8e-06,0.03,0.031,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 +15890000,0.78,-0.017,0.00068,-0.63,-0.028,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.028,0.029,0.027,0.063,0.063,0.052,2.1e-06,2.5e-06,4.8e-06,0.03,0.031,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 +15990000,0.78,-0.017,0.00066,-0.63,-0.025,-0.017,-0.017,-0.0084,-0.0095,-3.7e+02,-0.001,-0.0059,-7.3e-05,0.0023,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.026,0.053,0.053,0.051,2e-06,2.4e-06,4.8e-06,0.03,0.031,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16090000,0.78,-0.017,0.00058,-0.63,-0.027,-0.019,-0.014,-0.011,-0.012,-3.7e+02,-0.0011,-0.0059,-7.1e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.026,0.026,0.025,0.058,0.058,0.052,2e-06,2.3e-06,4.8e-06,0.03,0.031,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16190000,0.78,-0.017,0.00056,-0.63,-0.025,-0.017,-0.013,-0.008,-0.009,-3.7e+02,-0.0011,-0.0059,-6.9e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.9e-06,2.3e-06,4.8e-06,0.03,0.031,0.0025,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16290000,0.78,-0.017,0.00049,-0.63,-0.028,-0.019,-0.014,-0.011,-0.011,-3.7e+02,-0.0011,-0.0059,-6.7e-05,0.0031,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.9e-06,2.2e-06,4.8e-06,0.03,0.031,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16390000,0.78,-0.017,0.00051,-0.63,-0.024,-0.015,-0.013,-0.0081,-0.0086,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.022,0.022,0.023,0.047,0.047,0.051,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16490000,0.78,-0.016,0.00047,-0.63,-0.024,-0.017,-0.016,-0.01,-0.01,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.024,0.023,0.052,0.052,0.052,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.013,-0.017,-0.01,-0.0062,-3.7e+02,-0.0011,-0.0059,-5.9e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.021,0.022,0.046,0.046,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16690000,0.78,-0.016,0.00048,-0.63,-0.025,-0.014,-0.013,-0.013,-0.0073,-3.7e+02,-0.0011,-0.0059,-6.1e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.00096,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.022,0.023,0.022,0.05,0.051,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16790000,0.78,-0.016,0.00052,-0.63,-0.024,-0.01,-0.012,-0.013,-0.004,-3.7e+02,-0.0011,-0.006,-5.6e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.0009,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.6e-06,2e-06,4.8e-06,0.03,0.031,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16890000,0.78,-0.016,0.00051,-0.63,-0.025,-0.011,-0.0096,-0.015,-0.0049,-3.7e+02,-0.0011,-0.006,-5.7e-05,0.0027,-0.066,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.6e-06,1.9e-06,4.8e-06,0.03,0.031,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +16990000,0.78,-0.016,0.00055,-0.63,-0.024,-0.011,-0.0091,-0.014,-0.0048,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.019,0.02,0.02,0.043,0.043,0.05,1.5e-06,1.9e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17090000,0.78,-0.016,0.00054,-0.63,-0.025,-0.013,-0.009,-0.016,-0.0059,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17190000,0.78,-0.016,0.00048,-0.63,-0.024,-0.015,-0.0099,-0.014,-0.0062,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17290000,0.78,-0.016,0.00051,-0.63,-0.027,-0.017,-0.0054,-0.017,-0.0074,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0024,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.019,0.047,0.047,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17390000,0.78,-0.016,0.00044,-0.63,-0.024,-0.018,-0.0035,-0.014,-0.0076,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17490000,0.78,-0.016,0.00046,-0.63,-0.026,-0.019,-0.0018,-0.017,-0.0095,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17590000,0.78,-0.016,0.00047,-0.63,-0.024,-0.019,0.0036,-0.014,-0.0091,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17690000,0.78,-0.016,0.00049,-0.63,-0.026,-0.021,0.003,-0.017,-0.011,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.0027,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.019,0.017,0.045,0.045,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17790000,0.78,-0.016,0.00043,-0.63,-0.024,-0.022,0.0016,-0.015,-0.012,-3.7e+02,-0.0012,-0.0059,-4.8e-05,0.0031,-0.065,-0.13,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.023,0.0017,-0.018,-0.015,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0033,-0.065,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.016,0.053,0.053,0.048,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 +17990000,0.78,-0.016,0.00045,-0.63,-0.026,-0.021,0.0029,-0.016,-0.015,-3.7e+02,-0.0012,-0.0059,-4.5e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.001,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 +18090000,0.78,-0.016,0.00049,-0.63,-0.027,-0.021,0.0053,-0.019,-0.016,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.021,0.021,0.016,0.06,0.061,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.00098,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 +18190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.02,0.0066,-0.014,-0.013,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00093,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18290000,0.78,-0.016,0.00059,-0.63,-0.025,-0.02,0.0078,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18390000,0.78,-0.016,0.00055,-0.63,-0.024,-0.021,0.009,-0.013,-0.012,-3.7e+02,-0.0012,-0.006,-3.8e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.014,0.048,0.048,0.046,1.1e-06,1.4e-06,4.7e-06,0.03,0.03,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18490000,0.78,-0.016,0.00051,-0.63,-0.024,-0.023,0.0086,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3.7e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.014,0.053,0.053,0.046,1.1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18590000,0.78,-0.016,0.00049,-0.63,-0.022,-0.022,0.0067,-0.012,-0.013,-3.7e+02,-0.0013,-0.0059,-2.8e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.016,0.017,0.014,0.046,0.046,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18690000,0.78,-0.016,0.00055,-0.63,-0.024,-0.023,0.0048,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3e-05,0.0033,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.013,0.05,0.05,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18790000,0.78,-0.016,0.00057,-0.63,-0.022,-0.021,0.0045,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.013,0.044,0.044,0.045,1e-06,1.2e-06,4.7e-06,0.03,0.03,0.00073,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18890000,0.78,-0.016,0.00048,-0.63,-0.022,-0.024,0.0051,-0.014,-0.015,-3.7e+02,-0.0013,-0.0059,-2.2e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.8e-07,1.2e-06,4.7e-06,0.03,0.03,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +18990000,0.78,-0.016,0.00042,-0.63,-0.019,-0.024,0.0037,-0.0098,-0.013,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.012,0.043,0.043,0.044,9.5e-07,1.2e-06,4.7e-06,0.03,0.03,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19090000,0.78,-0.016,0.00041,-0.63,-0.019,-0.025,0.0067,-0.011,-0.015,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.012,0.046,0.047,0.044,9.4e-07,1.2e-06,4.7e-06,0.03,0.03,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19190000,0.78,-0.016,0.00036,-0.63,-0.015,-0.024,0.0067,-0.0077,-0.013,-3.7e+02,-0.0013,-0.0059,-8.2e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.015,0.012,0.041,0.042,0.044,9.1e-07,1.2e-06,4.7e-06,0.03,0.03,0.00063,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19290000,0.78,-0.016,0.00037,-0.63,-0.016,-0.024,0.0094,-0.0095,-0.016,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0034,-0.065,-0.13,-0.11,-0.024,0.5,-0.00069,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.012,0.045,0.046,0.044,9e-07,1.1e-06,4.7e-06,0.03,0.03,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19390000,0.78,-0.016,0.0004,-0.63,-0.015,-0.022,0.013,-0.0084,-0.014,-3.7e+02,-0.0013,-0.006,-2.4e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.8e-07,1.1e-06,4.6e-06,0.03,0.03,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19490000,0.78,-0.016,0.00035,-0.63,-0.015,-0.024,0.0096,-0.01,-0.017,-3.7e+02,-0.0013,-0.0059,1.4e-06,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00064,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.6e-07,1.1e-06,4.6e-06,0.03,0.03,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.022,0.0088,-0.0085,-0.015,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.0039,-0.065,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.04,0.04,0.042,8.4e-07,1.1e-06,4.6e-06,0.03,0.03,0.00055,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19690000,0.78,-0.015,0.00028,-0.63,-0.014,-0.021,0.01,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00061,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.044,0.042,8.3e-07,1.1e-06,4.6e-06,0.03,0.03,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.018,0.011,-0.0079,-0.015,-3.7e+02,-0.0013,-0.006,1.8e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00058,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.039,0.039,0.042,8.1e-07,1e-06,4.6e-06,0.03,0.03,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.02,0.012,-0.0096,-0.017,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.004,-0.065,-0.13,-0.11,-0.024,0.5,-0.00056,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.043,0.042,8e-07,1e-06,4.6e-06,0.03,0.03,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +19990000,0.78,-0.016,0.00028,-0.63,-0.0096,-0.02,0.015,-0.0084,-0.016,-3.7e+02,-0.0013,-0.0059,3.9e-05,0.0043,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.039,0.039,0.041,7.7e-07,9.9e-07,4.6e-06,0.03,0.03,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20090000,0.78,-0.016,0.00023,-0.63,-0.0096,-0.02,0.015,-0.0091,-0.019,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.01,0.042,0.043,0.042,7.7e-07,9.8e-07,4.6e-06,0.03,0.03,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20190000,0.78,-0.016,0.00019,-0.63,-0.01,-0.019,0.017,-0.0092,-0.017,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00046,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.038,0.039,0.041,7.4e-07,9.5e-07,4.6e-06,0.03,0.03,0.00045,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20290000,0.78,-0.016,0.00019,-0.63,-0.0089,-0.019,0.015,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,7.4e-07,9.4e-07,4.6e-06,0.03,0.03,0.00044,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20390000,0.78,-0.016,0.00024,-0.63,-0.0085,-0.016,0.017,-0.0095,-0.017,-3.7e+02,-0.0013,-0.0059,6.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,7.2e-07,9.2e-07,4.5e-06,0.03,0.03,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20490000,0.78,-0.016,0.0002,-0.63,-0.0087,-0.016,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,6.5e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,7.1e-07,9.1e-07,4.5e-06,0.03,0.03,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20590000,0.78,-0.016,0.0002,-0.63,-0.0081,-0.014,0.014,-0.0089,-0.016,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0093,0.038,0.038,0.04,6.9e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20690000,0.78,-0.016,0.00015,-0.63,-0.0089,-0.014,0.015,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,7.2e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.8e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20790000,0.78,-0.016,0.00013,-0.63,-0.0065,-0.013,0.016,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.6e-07,8.5e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20890000,0.78,-0.016,0.00011,-0.63,-0.0067,-0.013,0.015,-0.0088,-0.017,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.6e-07,8.4e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +20990000,0.78,-0.016,9.5e-05,-0.63,-0.0051,-0.011,0.015,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,9e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00038,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.4e-07,8.3e-07,4.4e-06,0.03,0.03,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21090000,0.78,-0.016,8.8e-05,-0.63,-0.0062,-0.011,0.016,-0.0094,-0.019,-3.7e+02,-0.0013,-0.0059,9.3e-05,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6.4e-07,8.2e-07,4.4e-06,0.03,0.03,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21190000,0.78,-0.016,8.4e-05,-0.63,-0.0063,-0.011,0.015,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,9.4e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00036,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21290000,0.78,-0.016,-6.5e-06,-0.63,-0.0059,-0.011,0.017,-0.0099,-0.021,-3.7e+02,-0.0013,-0.0059,0.0001,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0085,0.054,0.055,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21390000,0.78,-0.016,4.3e-05,-0.63,-0.0052,-0.0064,0.016,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,0.00011,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0084,0.046,0.047,0.039,6e-07,7.7e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21490000,0.78,-0.016,3.3e-05,-0.63,-0.0059,-0.0073,0.016,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,0.00011,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0083,0.05,0.052,0.038,5.9e-07,7.6e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21590000,0.78,-0.016,7.2e-05,-0.63,-0.0045,-0.0056,0.016,-0.0082,-0.013,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00029,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0081,0.044,0.045,0.038,5.8e-07,7.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21690000,0.78,-0.016,6.5e-05,-0.63,-0.0061,-0.0065,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.7e-07,7.4e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21790000,0.78,-0.016,0.00016,-0.63,-0.0051,-0.0043,0.016,-0.0083,-0.0092,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.6e-07,7.1e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21890000,0.78,-0.015,0.00016,-0.63,-0.0058,-0.005,0.016,-0.009,-0.0097,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.5e-07,7.1e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +21990000,0.78,-0.015,0.00019,-0.63,-0.0057,-0.0022,0.017,-0.0084,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.4e-07,6.9e-07,4.3e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +22090000,0.78,-0.015,0.00018,-0.63,-0.0054,-0.0037,0.015,-0.0088,-0.006,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0078,0.045,0.046,0.037,5.4e-07,6.9e-07,4.2e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +22190000,0.78,-0.015,0.00019,-0.63,-0.004,-0.0043,0.016,-0.0073,-0.0054,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0076,0.04,0.041,0.037,5.2e-07,6.7e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +22290000,0.78,-0.015,0.00016,-0.63,-0.0036,-0.0039,0.016,-0.008,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0076,0.043,0.045,0.037,5.2e-07,6.6e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 +22390000,0.78,-0.015,0.00015,-0.63,-0.0011,-0.0039,0.017,-0.0062,-0.0051,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.012,0.014,0.0075,0.039,0.04,0.037,5.1e-07,6.5e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +22490000,0.78,-0.015,0.00013,-0.63,7e-05,-0.0045,0.018,-0.0056,-0.0054,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0074,0.042,0.044,0.037,5e-07,6.4e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +22590000,0.78,-0.015,0.00013,-0.63,0.0019,-0.0034,0.018,-0.0039,-0.0047,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0073,0.045,0.046,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +22690000,0.78,-0.015,6.1e-05,-0.63,0.0035,-0.0046,0.019,-0.0032,-0.0056,-3.7e+02,-0.0014,-0.0059,0.00016,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0073,0.048,0.05,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +22790000,0.78,-0.015,0.0001,-0.63,0.0045,-0.004,0.02,-0.0026,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0072,0.051,0.052,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +22890000,0.78,-0.015,0.00011,-0.63,0.0052,-0.0049,0.021,-0.0028,-0.0048,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0072,0.055,0.057,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +22990000,0.78,-0.015,0.00012,-0.63,0.0049,-0.0049,0.022,-0.0029,-0.0055,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0071,0.058,0.06,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23090000,0.78,-0.015,0.00018,-0.63,0.0051,-0.0046,0.023,-0.0027,-0.0052,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.007,0.062,0.065,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23190000,0.78,-0.015,0.00017,-0.63,0.0027,-0.0034,0.024,-0.0055,-0.005,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0069,0.065,0.067,0.035,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23290000,0.78,-0.015,0.00023,-0.63,0.0023,-0.0031,0.025,-0.0058,-0.0057,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.017,0.019,0.0069,0.07,0.073,0.036,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23390000,0.78,-0.015,0.00021,-0.63,-0.0011,-0.0028,0.022,-0.01,-0.0058,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.0068,0.072,0.075,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23490000,0.78,-0.013,-0.0019,-0.63,0.0044,-0.0021,-0.011,-0.011,-0.007,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00014,-0.091,-0.068,0,0,0.00036,0.00036,0.046,0.017,0.019,0.0068,0.078,0.081,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23590000,0.78,-0.0042,-0.0062,-0.63,0.015,0.0017,-0.043,-0.0099,-0.0038,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.066,-0.13,-0.11,-0.024,0.5,-0.00012,-0.091,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0067,0.062,0.064,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23690000,0.78,0.0014,-0.0052,-0.63,0.042,0.016,-0.093,-0.0075,-0.0033,-3.7e+02,-0.0013,-0.0059,0.00018,0.0046,-0.066,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0067,0.067,0.069,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23790000,0.78,-0.0022,-0.0027,-0.63,0.063,0.033,-0.15,-0.0074,-0.0017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.014,0.015,0.0066,0.055,0.056,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23890000,0.78,-0.0085,-0.0007,-0.63,0.077,0.045,-0.2,2.8e-05,0.0023,-3.7e+02,-0.0013,-0.0059,0.00019,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00034,0.00035,0.046,0.014,0.016,0.0066,0.059,0.061,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +23990000,0.78,-0.013,0.00021,-0.63,0.072,0.045,-0.25,-0.0055,0.00083,-3.7e+02,-0.0013,-0.0059,0.00018,0.0052,-0.067,-0.13,-0.11,-0.024,0.5,-0.00029,-0.09,-0.067,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0066,0.062,0.063,0.035,4.1e-07,5.2e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +24090000,0.78,-0.012,-0.00093,-0.63,0.072,0.044,-0.3,0.00081,0.0045,-3.7e+02,-0.0013,-0.0059,0.00019,0.0053,-0.067,-0.13,-0.11,-0.024,0.5,-0.00034,-0.09,-0.067,0,0,0.00035,0.00036,0.046,0.015,0.017,0.0065,0.066,0.069,0.035,4.1e-07,5.2e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +24190000,0.78,-0.0097,-0.0017,-0.63,0.069,0.043,-0.35,-0.0065,0.0022,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00031,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.015,0.017,0.0065,0.069,0.071,0.034,4.1e-07,5.1e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +24290000,0.78,-0.0089,-0.0021,-0.63,0.077,0.048,-0.4,-0.00011,0.0069,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0065,0.074,0.077,0.034,4e-07,5.1e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +24390000,0.78,-0.0093,-0.0022,-0.63,0.074,0.047,-0.46,-0.013,0.00027,-3.7e+02,-0.0012,-0.0059,0.00015,0.0062,-0.069,-0.13,-0.11,-0.024,0.5,-0.0003,-0.089,-0.068,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +24490000,0.78,-0.0051,-0.0026,-0.63,0.085,0.054,-0.51,-0.0046,0.0052,-3.7e+02,-0.0012,-0.0059,0.00015,0.0063,-0.069,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.02,0.0064,0.082,0.085,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +24590000,0.78,-0.0016,-0.0027,-0.63,0.089,0.057,-0.56,-0.018,-0.0039,-3.7e+02,-0.0012,-0.0059,0.00014,0.0069,-0.071,-0.13,-0.11,-0.024,0.5,-0.00037,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +24690000,0.78,-0.00074,-0.0027,-0.63,0.11,0.073,-0.64,-0.0089,0.0014,-3.7e+02,-0.0012,-0.0059,0.00015,0.0072,-0.071,-0.13,-0.11,-0.024,0.5,-0.00055,-0.089,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0063,0.09,0.094,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +24790000,0.78,-0.0023,-0.0024,-0.63,0.11,0.082,-0.73,-0.028,-0.0034,-3.7e+02,-0.0012,-0.0059,0.00013,0.0079,-0.073,-0.13,-0.11,-0.025,0.5,-0.00036,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0062,0.093,0.096,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +24890000,0.78,-0.00046,-0.004,-0.63,0.13,0.097,-0.75,-0.017,0.0055,-3.7e+02,-0.0012,-0.0059,0.00012,0.0081,-0.074,-0.13,-0.11,-0.025,0.5,-0.00045,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.099,0.1,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00062,0.0012,0.0012,1,1 +24990000,0.78,0.0012,-0.0055,-0.63,0.13,0.1,-0.81,-0.039,-0.001,-3.7e+02,-0.0011,-0.0059,9e-05,0.0092,-0.076,-0.13,-0.11,-0.025,0.5,-0.00024,-0.087,-0.069,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +25090000,0.78,0.00063,-0.0059,-0.63,0.16,0.12,-0.86,-0.025,0.011,-3.7e+02,-0.0011,-0.0059,8.4e-05,0.0094,-0.076,-0.13,-0.11,-0.025,0.5,-0.00025,-0.087,-0.068,0,0,0.00034,0.00034,0.044,0.02,0.023,0.0062,0.11,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0011,0.0012,1,1 +25190000,0.78,-0.0015,-0.0054,-0.62,0.15,0.11,-0.91,-0.069,-0.012,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00022,-0.086,-0.069,0,0,0.00034,0.00033,0.044,0.02,0.023,0.0061,0.11,0.11,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1 +25290000,0.78,0.0055,-0.0066,-0.62,0.17,0.13,-0.96,-0.053,-0.00075,-3.7e+02,-0.0011,-0.0059,4.8e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00034,-0.086,-0.069,0,0,0.00033,0.00034,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.0006,0.0011,0.0012,1,1 +25390000,0.78,0.011,-0.0071,-0.62,0.18,0.13,-1,-0.1,-0.025,-3.7e+02,-0.001,-0.0058,8.1e-06,0.014,-0.086,-0.13,-0.11,-0.025,0.5,-0.00037,-0.085,-0.069,0,0,0.00033,0.00036,0.043,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1 +25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.082,-0.012,-3.7e+02,-0.001,-0.0058,2.3e-05,0.014,-0.087,-0.13,-0.11,-0.025,0.5,-0.00072,-0.084,-0.069,0,0,0.00033,0.00036,0.042,0.022,0.026,0.0061,0.13,0.13,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25590000,0.78,0.011,-0.007,-0.63,0.25,0.19,-1.1,-0.059,0.0041,-3.7e+02,-0.001,-0.0058,3.2e-05,0.014,-0.087,-0.13,-0.12,-0.025,0.5,-0.00098,-0.084,-0.068,0,0,0.00033,0.00035,0.042,0.024,0.028,0.0061,0.14,0.14,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1 +25690000,0.78,0.018,-0.0099,-0.63,0.29,0.21,-1.2,-0.032,0.022,-3.7e+02,-0.001,-0.0058,4.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0013,-0.082,-0.068,0,0,0.00034,0.00039,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00017,0.001,5.2e-05,0.0011,0.00057,0.0011,0.0011,1,1 +25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,-0.00023,0.043,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00034,0.00043,0.041,0.027,0.033,0.0061,0.15,0.16,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1 +25890000,0.77,0.025,-0.012,-0.63,0.41,0.28,-1.3,0.039,0.066,-3.7e+02,-0.00099,-0.0058,8.6e-05,0.015,-0.089,-0.13,-0.12,-0.026,0.5,-0.0025,-0.079,-0.066,0,0,0.00034,0.00043,0.04,0.029,0.037,0.0061,0.17,0.17,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5e-05,0.0011,0.00056,0.0011,0.0011,1,1 +25990000,0.77,0.021,-0.012,-0.63,0.47,0.31,-1.3,0.083,0.093,-3.7e+02,-0.00099,-0.0058,9.9e-05,0.015,-0.089,-0.13,-0.12,-0.027,0.5,-0.0029,-0.078,-0.065,0,0,0.00034,0.00041,0.04,0.032,0.04,0.0061,0.18,0.19,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1 +26090000,0.78,0.032,-0.016,-0.63,0.52,0.35,-1.3,0.13,0.13,-3.7e+02,-0.00098,-0.0058,8.8e-05,0.016,-0.089,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00035,0.00049,0.039,0.034,0.043,0.0061,0.19,0.2,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00097,4.8e-05,0.0011,0.00054,0.001,0.0011,1,1 +26190000,0.78,0.041,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,9.6e-05,0.018,-0.09,-0.13,-0.13,-0.028,0.5,-0.0035,-0.074,-0.063,0,0,0.00036,0.00058,0.037,0.036,0.047,0.0061,0.2,0.22,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00093,4.7e-05,0.001,0.00053,0.00098,0.001,1,1 +26290000,0.78,0.044,-0.018,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,9.2e-05,0.019,-0.091,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00036,0.0006,0.036,0.039,0.052,0.0061,0.21,0.23,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00091,4.6e-05,0.001,0.00052,0.00094,0.001,1,1 +26390000,0.77,0.04,-0.018,-0.63,0.76,0.5,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,0.0001,0.02,-0.091,-0.13,-0.13,-0.028,0.49,-0.0042,-0.069,-0.06,0,0,0.00036,0.00055,0.034,0.042,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00097,1,1 +26490000,0.77,0.056,-0.024,-0.63,0.84,0.55,-1.3,0.4,0.3,-3.7e+02,-0.00096,-0.0058,0.0001,0.02,-0.092,-0.13,-0.13,-0.029,0.49,-0.0043,-0.067,-0.058,0,0,0.00038,0.00075,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1 +26590000,0.77,0.073,-0.029,-0.63,0.95,0.63,-1.3,0.48,0.36,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.023,-0.092,-0.13,-0.13,-0.03,0.49,-0.0039,-0.064,-0.057,0,0,0.00041,0.00098,0.031,0.048,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1 +26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.024,-0.093,-0.13,-0.14,-0.031,0.49,-0.0049,-0.059,-0.052,0,0,0.00041,0.00097,0.028,0.052,0.073,0.0061,0.28,0.31,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1 +26790000,0.77,0.07,-0.029,-0.64,1.2,0.79,-1.3,0.7,0.5,-3.7e+02,-0.00095,-0.0058,6.9e-05,0.025,-0.093,-0.13,-0.14,-0.032,0.48,-0.0047,-0.055,-0.049,0,0,0.00039,0.00084,0.026,0.055,0.079,0.0061,0.3,0.33,0.033,3.7e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1 +26890000,0.76,0.093,-0.036,-0.64,1.3,0.86,-1.3,0.83,0.58,-3.7e+02,-0.00095,-0.0058,7.2e-05,0.026,-0.093,-0.13,-0.15,-0.032,0.48,-0.0052,-0.052,-0.047,0,0,0.00044,0.0011,0.024,0.058,0.085,0.0061,0.32,0.35,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1 +26990000,0.76,0.12,-0.041,-0.64,1.5,0.97,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,6.1e-05,0.029,-0.094,-0.13,-0.15,-0.034,0.48,-0.0055,-0.046,-0.043,0,0,0.00049,0.0014,0.021,0.061,0.091,0.0061,0.34,0.37,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1 +27090000,0.76,0.12,-0.041,-0.64,1.7,1.1,-1.2,1.1,0.78,-3.7e+02,-0.00095,-0.0058,4.5e-05,0.03,-0.093,-0.13,-0.16,-0.035,0.47,-0.0055,-0.041,-0.038,0,0,0.00049,0.0013,0.018,0.065,0.098,0.0061,0.36,0.4,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1 +27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.9,-3.7e+02,-0.00096,-0.0058,2.8e-05,0.032,-0.092,-0.13,-0.16,-0.035,0.47,-0.0053,-0.038,-0.035,0,0,0.00045,0.0011,0.017,0.068,0.1,0.0062,0.38,0.43,0.034,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1 +27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,2.2e-05,0.032,-0.091,-0.13,-0.16,-0.036,0.47,-0.0054,-0.035,-0.033,0,0,0.00041,0.00083,0.015,0.07,0.11,0.0062,0.4,0.46,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1 +27390000,0.76,0.077,-0.03,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00095,-0.0058,1.7e-05,0.033,-0.089,-0.13,-0.17,-0.036,0.47,-0.0054,-0.033,-0.032,0,0,0.00038,0.00064,0.014,0.071,0.11,0.0062,0.43,0.49,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1 +27490000,0.76,0.061,-0.025,-0.64,2.2,1.4,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,9e-06,0.033,-0.087,-0.13,-0.17,-0.037,0.47,-0.0052,-0.032,-0.032,0,0,0.00036,0.00052,0.012,0.072,0.11,0.0062,0.46,0.52,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1 +27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,-8.8e-07,0.034,-0.084,-0.13,-0.17,-0.037,0.47,-0.0048,-0.031,-0.031,0,0,0.00035,0.00045,0.012,0.073,0.11,0.0062,0.48,0.55,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1 +27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,-9.9e-06,0.034,-0.083,-0.13,-0.17,-0.037,0.47,-0.0044,-0.031,-0.031,0,0,0.00035,0.00044,0.011,0.073,0.11,0.0063,0.51,0.59,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1 +27790000,0.77,0.049,-0.021,-0.64,2.3,1.5,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,-2.3e-05,0.035,-0.081,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.031,0,0,0.00035,0.00044,0.0098,0.074,0.1,0.0063,0.54,0.62,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00042,2.2e-05,0.00049,0.00022,0.00044,0.00048,1,1 +27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,-2.4e-05,0.034,-0.079,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00043,0.0093,0.075,0.1,0.0063,0.58,0.66,0.034,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00041,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1 +27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,-2.7e-05,0.034,-0.078,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00041,0.0087,0.076,0.1,0.0064,0.61,0.7,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1 +28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,-3.8e-05,0.035,-0.076,-0.13,-0.17,-0.038,0.47,-0.0035,-0.029,-0.03,0,0,0.00035,0.00045,0.0081,0.077,0.1,0.0064,0.65,0.74,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.0004,2.1e-05,0.00048,0.00021,0.00042,0.00048,1,1 +28190000,0.77,0.071,-0.028,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,-4e-05,0.035,-0.074,-0.13,-0.17,-0.038,0.46,-0.0035,-0.029,-0.03,0,0,0.00036,0.00049,0.0077,0.078,0.1,0.0065,0.68,0.79,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1 +28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00095,-0.0058,-4.9e-05,0.035,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.028,-0.029,0,0,0.00035,0.00043,0.0074,0.077,0.1,0.0066,0.72,0.83,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1 +28390000,0.77,0.02,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,-5.7e-05,0.035,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00035,0.00037,0.0071,0.076,0.1,0.0066,0.76,0.88,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 +28490000,0.77,0.0014,-0.0026,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,-6.3e-05,0.035,-0.065,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0068,0.077,0.099,0.0067,0.8,0.93,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 +28590000,0.77,-0.0022,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00096,-0.0058,-6.4e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0065,0.077,0.098,0.0067,0.84,0.98,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 +28690000,0.77,-0.0032,-0.00057,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00097,-0.0058,-7.1e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00034,0.00036,0.0063,0.078,0.098,0.0067,0.88,1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1 +28790000,0.77,-0.0034,-0.00035,-0.63,2.2,1.6,1,5,3.4,-3.7e+02,-0.00098,-0.0058,-7.9e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00034,0.00037,0.0061,0.079,0.098,0.0068,0.92,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 +28890000,0.77,-0.0032,-0.00036,-0.63,2.2,1.5,0.99,5.2,3.6,-3.7e+02,-0.00099,-0.0058,-8.6e-05,0.033,-0.06,-0.12,-0.17,-0.038,0.46,-0.0028,-0.027,-0.029,0,0,0.00034,0.00037,0.0059,0.08,0.1,0.0068,0.97,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 +28990000,0.77,-0.0027,-0.00054,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-9.8e-05,0.033,-0.058,-0.12,-0.17,-0.038,0.46,-0.0026,-0.027,-0.028,0,0,0.00034,0.00037,0.0057,0.081,0.1,0.0069,1,1.2,0.034,3.6e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 +29090000,0.78,-0.0022,-0.0007,-0.63,2.1,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.056,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00034,0.00037,0.0055,0.083,0.1,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 +29190000,0.77,-0.0019,-0.00078,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.028,0,0,0.00034,0.00037,0.0054,0.084,0.1,0.007,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1 +29290000,0.78,-0.00093,-0.0011,-0.63,1.9,1.4,1,6.1,4.2,-3.7e+02,-0.001,-0.0058,-0.00011,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.028,0,0,0.00033,0.00037,0.0053,0.086,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00044,1,1 +29390000,0.78,0.00051,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-0.00012,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.0051,0.087,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 +29490000,0.78,0.0017,-0.0018,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,-0.00013,0.03,-0.05,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.005,0.089,0.11,0.0071,1.3,1.5,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 +29590000,0.78,0.0028,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-0.00013,0.028,-0.048,-0.12,-0.17,-0.038,0.46,-0.002,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.091,0.12,0.0071,1.3,1.6,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 +29690000,0.78,0.0036,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-0.00014,0.028,-0.045,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.093,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 +29790000,0.78,0.0041,-0.0025,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0058,-0.00014,0.027,-0.042,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0048,0.095,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 +29890000,0.78,0.0045,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.001,-0.0058,-0.00015,0.026,-0.038,-0.12,-0.17,-0.038,0.46,-0.0017,-0.028,-0.028,0,0,0.00033,0.00038,0.0047,0.097,0.13,0.0072,1.5,1.8,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 +29990000,0.78,0.0046,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.001,-0.0058,-0.00015,0.025,-0.035,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00033,0.00038,0.0046,0.099,0.13,0.0072,1.6,1.9,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 +30090000,0.78,0.0046,-0.0027,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0058,-0.00016,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0046,0.1,0.14,0.0072,1.6,2,0.034,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 +30190000,0.78,0.0043,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.001,-0.0058,-0.00016,0.023,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0045,0.1,0.14,0.0072,1.7,2.1,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 +30290000,0.78,0.0042,-0.0026,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00016,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.2,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 +30390000,0.78,0.0041,-0.0026,-0.63,1.5,1.2,0.9,8,5.7,-3.7e+02,-0.0011,-0.0058,-0.00017,0.021,-0.028,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.3,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +30490000,0.78,0.0039,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.8,-3.7e+02,-0.0011,-0.0058,-0.00017,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.16,0.0072,1.9,2.4,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +30590000,0.78,0.0036,-0.0025,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.019,-0.022,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0043,0.11,0.16,0.0072,2,2.5,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +30690000,0.78,0.0034,-0.0024,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00017,0.018,-0.019,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00039,0.0043,0.11,0.17,0.0072,2.1,2.6,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +30790000,0.78,0.0031,-0.0023,-0.63,1.4,1.2,0.83,8.6,6.2,-3.7e+02,-0.0011,-0.0058,-0.00017,0.017,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.8,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +30890000,0.78,0.0027,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.3,-3.7e+02,-0.0011,-0.0058,-0.00018,0.016,-0.016,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.9,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +30990000,0.78,0.0023,-0.0022,-0.63,1.3,1.2,0.81,8.9,6.4,-3.7e+02,-0.0011,-0.0058,-0.00018,0.015,-0.012,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.19,0.0072,2.3,3,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +31090000,0.78,0.0019,-0.0021,-0.63,1.3,1.1,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00018,0.014,-0.0094,-0.12,-0.17,-0.038,0.46,-0.00097,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.12,0.2,0.0072,2.4,3.2,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +31190000,0.78,0.0016,-0.002,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00019,0.012,-0.0056,-0.12,-0.17,-0.038,0.46,-0.00088,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.2,0.0072,2.5,3.3,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +31290000,0.78,0.0012,-0.0018,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00019,0.011,-0.0028,-0.12,-0.17,-0.038,0.46,-0.00081,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.21,0.0071,2.6,3.5,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 +31390000,0.78,0.00059,-0.0016,-0.63,1.2,1.1,0.79,9.4,6.9,-3.7e+02,-0.0011,-0.0058,-0.00019,0.0099,0.0002,-0.12,-0.17,-0.038,0.46,-0.00074,-0.029,-0.027,0,0,0.0003,0.0004,0.0041,0.13,0.22,0.0071,2.7,3.6,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 +31490000,0.78,8.5e-05,-0.0015,-0.63,1.2,1.1,0.79,9.5,7,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0086,0.0029,-0.12,-0.17,-0.038,0.46,-0.00061,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.23,0.0071,2.8,3.8,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 +31590000,0.78,-0.00021,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.1,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0073,0.005,-0.11,-0.17,-0.038,0.46,-0.00056,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.0071,2.9,3.9,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 +31690000,0.78,-0.00082,-0.0013,-0.63,1.1,1.1,0.79,9.8,7.2,-3.7e+02,-0.0011,-0.0058,-0.0002,0.006,0.0077,-0.11,-0.17,-0.038,0.46,-0.00049,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.007,3,4.1,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +31790000,0.78,-0.0014,-0.0011,-0.63,1.1,1,0.79,9.9,7.3,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0047,0.011,-0.11,-0.17,-0.038,0.46,-0.00042,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.25,0.007,3.1,4.3,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +31890000,0.78,-0.002,-0.001,-0.63,1.1,1,0.78,10,7.4,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0033,0.014,-0.11,-0.17,-0.038,0.46,-0.00033,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.15,0.26,0.007,3.2,4.5,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +31990000,0.78,-0.0024,-0.0009,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0011,-0.0058,-0.00021,0.0018,0.017,-0.11,-0.17,-0.038,0.46,-0.00022,-0.029,-0.027,0,0,0.00029,0.00041,0.004,0.15,0.27,0.007,3.3,4.7,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +32090000,0.78,-0.003,-0.0007,-0.63,1,0.99,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00021,0.00019,0.02,-0.11,-0.17,-0.038,0.46,-0.00011,-0.029,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.28,0.007,3.5,4.9,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +32190000,0.78,-0.0038,-0.00051,-0.63,0.97,0.98,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0015,0.024,-0.11,-0.18,-0.038,0.46,3.2e-05,-0.03,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.29,0.0069,3.6,5.1,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +32290000,0.78,-0.0044,-0.00042,-0.63,0.94,0.96,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0032,0.028,-0.11,-0.18,-0.038,0.46,0.00014,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.3,0.0069,3.7,5.4,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +32390000,0.78,-0.0049,-0.00032,-0.63,0.91,0.94,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0041,0.03,-0.11,-0.18,-0.038,0.46,0.00019,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.31,0.0069,3.8,5.6,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 +32490000,0.78,-0.0051,-0.00027,-0.63,0.88,0.92,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0056,0.032,-0.11,-0.18,-0.038,0.46,0.00028,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.16,0.32,0.0068,4,5.8,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 +32590000,0.78,-0.0053,-0.00021,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0064,0.033,-0.11,-0.18,-0.038,0.46,0.00034,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,3e-07,5.1e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 +32690000,0.78,-0.0053,-0.00025,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0073,0.035,-0.11,-0.18,-0.038,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.2e-06,0.029,0.023,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 +32790000,0.78,-0.0052,-0.00026,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0081,0.036,-0.11,-0.18,-0.038,0.46,0.00047,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.27,0.26,0.26,0.049,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 +32890000,0.78,-0.005,-0.00039,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0089,0.038,-0.11,-0.18,-0.038,0.46,0.00057,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 +32990000,0.78,-0.0049,-0.0005,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0098,0.04,-0.11,-0.18,-0.038,0.46,0.00059,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 +33090000,0.78,-0.005,-0.00048,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00061,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 +33190000,0.78,-0.0036,-0.0037,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.01,0.041,-0.11,-0.18,-0.038,0.46,0.0006,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 +33290000,0.82,-0.0015,-0.016,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.039,0.46,0.00058,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00035,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 +33390000,0.89,-0.0018,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.015,0.038,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.9e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1 +33490000,0.95,-0.00026,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.018,0.037,-0.11,-0.18,-0.04,0.46,0.0017,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1 +33590000,0.99,-0.003,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.018,0.037,-0.11,-0.19,-0.042,0.46,0.0025,-0.013,-0.026,0,0,0.00035,0.00031,0.003,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00017,1e-05,0.00041,9.5e-05,0.00016,0.0004,1,1 +33690000,1,-0.0064,0.005,0.024,-1.6,-0.86,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.018,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00028,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1 +33790000,0.98,-0.0073,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0068,-0.027,0,0,0.00037,0.00026,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,4.9e-07,3.1e-06,0.028,0.022,9.3e-05,9.7e-05,6.4e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1 +33890000,0.94,-0.0075,0.0082,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,4.9e-07,3e-06,0.028,0.022,9.3e-05,8.1e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1 +33990000,0.87,-0.0095,0.0057,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00027,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.8e-07,3e-06,0.028,0.022,9.3e-05,7.1e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1 +34090000,0.81,-0.011,0.0044,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.01,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.034,0.33,0.33,0.063,2.8e-07,4.9e-07,3e-06,0.027,0.022,9.3e-05,6.6e-05,4.9e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1 +34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.039,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00028,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.7e-07,3e-06,0.026,0.021,9.3e-05,6e-05,4.6e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1 +34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.038,0.051,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00029,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.7e-07,3e-06,0.025,0.021,9.3e-05,5.7e-05,4.5e-06,0.0004,1.4e-05,1.6e-05,0.0004,1,1 +34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.036,0.05,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00025,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.5e-05,4.4e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1 +34490000,0.69,-0.00036,0.0066,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.073,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.4e-05,4.3e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1 +34590000,0.68,0.00092,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.05,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.085,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.2e-05,4.3e-06,0.0004,1e-05,1.1e-05,0.0004,1,1 +34690000,0.67,0.0017,0.0079,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.034,0.049,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00024,0.0003,0.0017,0.098,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,9.6e-06,1e-05,0.0004,1,1 +34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.036,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00024,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,8.9e-06,9.2e-06,0.0004,1,1 +34890000,0.66,0.0025,0.0082,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1 +34990000,0.66,-0.00086,0.016,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00024,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.9e-06,8e-06,0.0004,1,1 +35090000,0.66,-0.00092,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.5e-06,7.5e-06,0.0004,1,1 +35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.28,0.014,0.52,0.55,0.054,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1 +35290000,0.66,-0.0012,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00084,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.23,0.31,0.013,0.56,0.6,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1 +35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.25,0.34,0.013,0.61,0.66,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.6e-06,6.4e-06,0.0004,1,1 +35490000,0.66,-0.0012,0.016,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.28,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.4e-06,6.2e-06,0.0004,1,1 +35590000,0.66,-0.0012,0.016,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00092,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.31,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,4e-06,0.0004,6.2e-06,5.9e-06,0.0004,1,1 +35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.046,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.33,0.44,0.011,0.79,0.9,0.049,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1 +35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.36,0.48,0.01,0.86,1,0.048,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1 +35890000,0.66,-0.0013,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.4,0.52,0.01,0.95,1.1,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,5.7e-06,5.3e-06,0.0004,1,1 +35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00094,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.43,0.56,0.0097,1,1.2,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.6e-06,5.1e-06,0.0004,1,1 +36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00096,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.46,0.6,0.0093,1.2,1.4,0.046,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.5e-06,5e-06,0.0004,1,1 +36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.5,0.65,0.009,1.3,1.5,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.4e-06,4.8e-06,0.0004,1,1 +36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.53,0.69,0.0088,1.4,1.7,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.3e-06,4.7e-06,0.0004,1,1 +36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.57,0.74,0.0086,1.6,1.9,0.044,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.2e-06,4.6e-06,0.0004,1,1 +36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.61,0.79,0.0083,1.7,2.1,0.043,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.0004,5.2e-06,4.5e-06,0.0004,1,1 +36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.65,0.84,0.0082,1.9,2.4,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5.1e-06,4.4e-06,0.0004,1,1 +36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.69,0.89,0.0081,2.1,2.6,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.3e-06,0.0004,1,1 +36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.74,0.94,0.0079,2.3,2.9,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.2e-06,0.0004,1,1 +36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.78,1,0.0078,2.6,3.2,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4.1e-06,0.0004,1,1 +36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.82,1.1,0.0077,2.8,3.6,0.04,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1 +37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.87,1.1,0.0076,3.1,4,0.04,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 +37190000,0.66,-0.0014,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.92,1.2,0.0076,3.4,4.4,0.039,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 +37290000,0.66,-0.0015,0.017,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.97,1.2,0.0075,3.7,4.8,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.8e-06,0.0004,1,1 +37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,1,1.3,0.0075,4.1,5.3,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 +37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.4,5.8,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 +37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.9,6.3,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 +37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.2,1.5,0.0074,5.3,6.9,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.6e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 +37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.2,1.5,0.0074,5.8,7.5,0.037,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.5e-06,0.0004,1,1 +37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.6,0.0074,6.3,8.2,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 +37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.7,0.0074,6.8,8.9,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 +38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.7,0.0074,7.4,9.6,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.5e-06,3.4e-06,0.0004,1,1 +38190000,0.66,-0.0016,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0074,8,10,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 +38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.6,11,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 +38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,9.3,12,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 +38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.07,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,10,13,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 +38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.1,0.0075,11,14,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 +38690000,0.66,-0.0016,0.017,0.75,-4.3,-4.1,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.2,0.0075,12,15,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1 +38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00026,0.0016,1.8,2.3,0.0075,12,16,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 +38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.9,2.3,0.0075,13,17,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 6b71f5f6d749..6cb6d950815c 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -9,343 +9,343 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00054,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,4.9e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00066,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,5e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00066,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.9e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.7e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00056,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1290000,1,-0.012,-0.014,0.00042,0.019,-0.017,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.88,0.88,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00049,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.3e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.95,0.95,0.27,0.14,0.14,0.15,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.3e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,0.23,0.21,0.21,0.14,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0036,-0.068,-0.00073,-0.00073,-8.2e-08,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,0.19,0.14,0.14,0.13,0.0079,0.0079,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0075,-0.0059,-0.067,-0.00072,-0.00072,-3.8e-08,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00039,1.3,1.3,0.17,0.21,0.21,0.12,0.0079,0.0079,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-1.2e-08,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,0.15,0.31,0.31,0.12,0.0079,0.0079,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0081,-0.0053,-0.074,-0.0011,-0.0012,-3.1e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00035,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.3e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.3e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-7.7e-08,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3.3e-08,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00039,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-7e-09,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.1e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00035,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00039,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-7.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.021,0.00031,1.2,1.2,0.11,0.2,0.2,0.11,0.0056,0.0056,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-7.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,0.11,0.3,0.3,0.1,0.0056,0.0056,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-7.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-7.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.3e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2490000,1,-0.011,-0.014,0.00047,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.3e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2590000,1,-0.01,-0.013,0.00039,0.023,-0.006,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-1.9e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.88,0.88,0.099,0.18,0.18,0.094,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-1.9e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-1.8e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2790000,1,-0.01,-0.013,0.00037,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.012,0.012,0.00024,0.75,0.75,0.095,0.16,0.16,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.93,0.93,0.096,0.23,0.23,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2990000,1,-0.01,-0.013,0.00031,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-2.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.01,0.01,0.00022,0.66,0.66,0.095,0.15,0.15,0.088,0.0027,0.0027,4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-2.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.81,0.81,0.095,0.22,0.22,0.086,0.0027,0.0027,4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3190000,1,-0.01,-0.013,0.00056,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.2e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0089,0.0089,0.00021,0.58,0.58,0.096,0.14,0.14,0.087,0.0023,0.0023,3.4e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.2e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0097,0.0097,0.00022,0.71,0.71,0.095,0.2,0.2,0.086,0.0023,0.0023,3.4e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.005,-0.0013,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0079,0.0079,0.00019,0.52,0.52,0.095,0.14,0.14,0.085,0.002,0.002,2.9e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0018,-0.15,0.0072,-0.0015,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.64,0.64,0.095,0.19,0.19,0.086,0.002,0.002,2.9e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0013,-0.15,0.0051,-0.0009,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.0071,0.0071,0.00018,0.48,0.48,0.094,0.13,0.13,0.086,0.0017,0.0017,2.5e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3690000,1,-0.0095,-0.013,0.00052,0.024,-0.0006,-0.15,0.0074,-0.0011,-0.11,-0.0021,-0.004,-3.9e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.58,0.58,0.093,0.17,0.17,0.085,0.0017,0.0017,2.5e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3790000,1,-0.0094,-0.012,0.00055,0.02,0.0038,-0.15,0.0051,-0.00045,-0.11,-0.0022,-0.0043,-4.4e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3890000,1,-0.0094,-0.012,0.00063,0.021,0.0051,-0.14,0.0072,3.2e-06,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.54,0.54,0.091,0.16,0.16,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3990000,1,-0.0094,-0.013,0.0007,0.026,0.0049,-0.14,0.0096,0.00045,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.65,0.65,0.089,0.22,0.22,0.085,0.0014,0.0014,2.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4090000,1,-0.0093,-0.012,0.00076,0.022,0.0042,-0.12,0.0071,0.00064,-0.098,-0.0022,-0.0045,-4.8e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.9e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4190000,1,-0.0094,-0.012,0.00073,0.024,0.004,-0.12,0.0094,0.0011,-0.1,-0.0022,-0.0045,-4.8e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00018,0.6,0.6,0.086,0.21,0.21,0.086,0.0012,0.0012,1.9e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4290000,1,-0.0095,-0.012,0.00074,0.021,0.0038,-0.12,0.0068,0.00087,-0.11,-0.0021,-0.0047,-5.3e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00016,0.46,0.46,0.084,0.15,0.15,0.085,0.00095,0.00095,1.6e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0047,-5.3e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00017,0.55,0.55,0.081,0.2,0.2,0.084,0.00095,0.00095,1.6e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4490000,1,-0.0094,-0.012,0.00076,0.02,0.004,-0.11,0.0067,0.00089,-0.095,-0.0021,-0.0048,-5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.43,0.43,0.08,0.14,0.14,0.085,0.00077,0.00077,1.5e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-5.7e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.51,0.51,0.077,0.19,0.19,0.084,0.00077,0.00077,1.5e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4690000,1,-0.0094,-0.012,0.00076,0.017,0.003,-0.1,0.0065,0.0009,-0.09,-0.0021,-0.005,-6.2e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.39,0.39,0.074,0.14,0.14,0.083,0.00062,0.00062,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4790000,1,-0.0093,-0.012,0.00086,0.015,0.0052,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.2e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00062,0.00062,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4890000,1,-0.0093,-0.012,0.0009,0.0099,0.0026,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0052,-6.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0035,0.0035,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00049,0.00049,1.1e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4990000,1,-0.0092,-0.012,0.00089,0.013,0.0033,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-6.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00049,0.00049,1.1e-05,0.04,0.04,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5090000,1,-0.0091,-0.011,0.00096,0.01,0.0035,-0.082,0.0045,0.00098,-0.081,-0.002,-0.0053,-6.8e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.003,0.003,0.00014,0.34,0.34,0.065,0.12,0.12,0.082,0.00039,0.00039,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5190000,1,-0.009,-0.012,0.001,0.0096,0.0071,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0053,-6.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.4,0.4,0.063,0.16,0.16,0.081,0.00039,0.00039,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5290000,1,-0.0089,-0.011,0.0011,0.0079,0.0071,-0.068,0.0038,0.0013,-0.072,-0.002,-0.0053,-7.1e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.31,0.31,0.06,0.12,0.12,0.08,0.00031,0.00031,9.3e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5390000,1,-0.0088,-0.011,0.0011,0.0074,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7.1e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00014,0.36,0.36,0.057,0.15,0.15,0.079,0.00031,0.00031,9.3e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5490000,1,-0.0089,-0.011,0.0011,0.0069,0.012,-0.06,0.0031,0.002,-0.065,-0.002,-0.0054,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00013,0.28,0.28,0.056,0.11,0.11,0.079,0.00025,0.00025,8.4e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5590000,1,-0.0089,-0.011,0.00099,0.008,0.015,-0.053,0.0039,0.0033,-0.058,-0.002,-0.0054,-7.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00025,0.00025,8.4e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5690000,1,-0.0089,-0.011,0.0009,0.0074,0.015,-0.052,0.0028,0.0029,-0.055,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.26,0.26,0.051,0.11,0.11,0.076,0.00019,0.00019,7.6e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5790000,1,-0.0088,-0.011,0.00085,0.0087,0.017,-0.049,0.0036,0.0045,-0.053,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00019,0.00019,7.6e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5890000,1,-0.0088,-0.011,0.00089,0.0092,0.015,-0.048,0.0027,0.0037,-0.056,-0.0018,-0.0055,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.24,0.24,0.047,0.1,0.1,0.075,0.00015,0.00015,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5990000,1,-0.0088,-0.011,0.00086,0.011,0.016,-0.041,0.0037,0.0052,-0.05,-0.0018,-0.0055,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00015,0.00015,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0048,0.0069,-0.047,-0.0018,-0.0055,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00013,0.32,0.32,0.044,0.17,0.17,0.074,0.00015,0.00015,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6190000,1,-0.0089,-0.011,0.00068,0.0085,0.016,-0.038,0.0037,0.0056,-0.047,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.25,0.25,0.042,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6290000,1,-0.0089,-0.011,0.00071,0.0078,0.019,-0.041,0.0046,0.0073,-0.053,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.29,0.29,0.04,0.16,0.16,0.072,0.00012,0.00012,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6390000,-0.29,0.025,-0.0062,0.96,-0.0089,0.0093,-0.042,0.0041,0.0051,-0.056,-0.0017,-0.0055,-8.2e-05,0,0,-0.12,-0.095,-0.021,0.51,0.072,-0.027,-0.063,0,0,0.0012,0.0012,0.066,0.2,0.2,0.039,0.12,0.12,0.072,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0038,0.0014,0.00037,0.0014,0.0014,0.0011,0.0014,1,1 -6490000,-0.29,0.026,-0.0062,0.96,-0.027,0.0035,-0.039,0.0048,0.0045,-0.053,-0.0017,-0.0054,-8.1e-05,0,0,-0.13,-0.1,-0.022,0.51,0.076,-0.028,-0.067,0,0,0.0012,0.0012,0.056,0.2,0.2,0.038,0.15,0.15,0.07,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0036,0.0013,0.00021,0.0013,0.0013,0.00096,0.0013,1,1 -6590000,-0.29,0.026,-0.0062,0.96,-0.047,-0.0063,-0.041,0.004,0.0029,-0.056,-0.0016,-0.0053,-8e-05,-0.0003,0.00015,-0.13,-0.1,-0.022,0.5,0.077,-0.029,-0.068,0,0,0.0012,0.0012,0.054,0.21,0.21,0.036,0.18,0.18,0.069,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0033,0.0013,0.00016,0.0013,0.0013,0.00093,0.0013,1,1 -6690000,-0.29,0.026,-0.0061,0.96,-0.066,-0.015,-0.043,0.00029,0.00029,-0.057,-0.0015,-0.0052,-8e-05,-0.00055,0.00035,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0012,0.0012,0.052,0.21,0.21,0.035,0.22,0.22,0.068,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0031,0.0013,0.00014,0.0013,0.0013,0.00092,0.0013,1,1 -6790000,-0.29,0.026,-0.0062,0.96,-0.087,-0.026,-0.041,-0.0024,-0.0042,-0.057,-0.0015,-0.0051,-7.9e-05,-0.0011,0.00062,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0012,0.051,0.22,0.22,0.034,0.26,0.26,0.068,9.9e-05,9.8e-05,5.8e-06,0.04,0.04,0.003,0.0013,0.00013,0.0013,0.0013,0.00091,0.0013,1,1 -6890000,-0.29,0.026,-0.006,0.96,-0.11,-0.032,-0.037,-0.0093,-0.0085,-0.055,-0.0014,-0.005,-7.8e-05,-0.0014,0.00077,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0012,0.051,0.23,0.23,0.032,0.3,0.3,0.067,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.0028,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1 -6990000,-0.29,0.026,-0.0059,0.96,-0.13,-0.04,-0.035,-0.018,-0.013,-0.054,-0.0014,-0.0049,-7.7e-05,-0.0017,0.00088,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.031,0.35,0.35,0.066,9.7e-05,9.7e-05,5.8e-06,0.04,0.04,0.0026,0.0013,0.00011,0.0013,0.0013,0.00091,0.0013,1,1 -7090000,-0.29,0.026,-0.0058,0.96,-0.15,-0.051,-0.035,-0.031,-0.018,-0.055,-0.0014,-0.0049,-7.6e-05,-0.0018,0.00089,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.05,0.25,0.25,0.03,0.4,0.4,0.066,9.6e-05,9.6e-05,5.8e-06,0.04,0.04,0.0024,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1 -7190000,-0.29,0.026,-0.0058,0.96,-0.18,-0.061,-0.034,-0.045,-0.027,-0.058,-0.0014,-0.0048,-7.7e-05,-0.0021,0.0011,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.27,0.27,0.029,0.46,0.46,0.065,9.5e-05,9.5e-05,5.8e-06,0.04,0.04,0.0023,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7290000,-0.29,0.026,-0.0057,0.96,-0.2,-0.07,-0.031,-0.065,-0.032,-0.053,-0.0014,-0.0049,-7.7e-05,-0.002,0.0011,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.05,0.29,0.29,0.028,0.51,0.51,0.064,9.4e-05,9.3e-05,5.8e-06,0.04,0.04,0.0022,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7390000,-0.29,0.026,-0.0056,0.96,-0.23,-0.077,-0.029,-0.089,-0.037,-0.051,-0.0014,-0.0049,-7.7e-05,-0.0019,0.00095,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.049,0.31,0.31,0.027,0.58,0.58,0.064,9.2e-05,9.2e-05,5.8e-06,0.04,0.04,0.002,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7490000,-0.29,0.026,-0.0056,0.96,-0.25,-0.086,-0.023,-0.1,-0.044,-0.044,-0.0014,-0.0047,-7.1e-05,-0.0026,0.00089,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0014,0.0013,0.049,0.34,0.33,0.026,0.64,0.64,0.063,9e-05,9e-05,5.8e-06,0.04,0.04,0.0019,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7590000,-0.29,0.026,-0.0056,0.96,-0.27,-0.096,-0.019,-0.12,-0.055,-0.039,-0.0014,-0.0047,-6.9e-05,-0.003,0.001,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0014,0.0013,0.049,0.37,0.36,0.025,0.71,0.71,0.062,8.8e-05,8.7e-05,5.8e-06,0.04,0.04,0.0018,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7690000,-0.29,0.027,-0.0056,0.96,-0.3,-0.11,-0.018,-0.15,-0.068,-0.035,-0.0014,-0.0046,-6.9e-05,-0.0034,0.0012,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0014,0.0014,0.049,0.4,0.39,0.025,0.79,0.79,0.062,8.6e-05,8.5e-05,5.8e-06,0.04,0.04,0.0017,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7790000,-0.29,0.027,-0.0056,0.96,-0.32,-0.12,-0.02,-0.16,-0.091,-0.039,-0.0012,-0.0043,-6.8e-05,-0.0043,0.0017,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.43,0.43,0.024,0.87,0.87,0.061,8.3e-05,8.2e-05,5.8e-06,0.04,0.04,0.0016,0.0013,8.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 -7890000,-0.29,0.027,-0.0056,0.96,-0.34,-0.13,-0.021,-0.19,-0.11,-0.042,-0.0012,-0.0043,-6.9e-05,-0.0043,0.0018,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.47,0.46,0.023,0.96,0.96,0.06,8e-05,7.9e-05,5.8e-06,0.04,0.04,0.0015,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 -7990000,-0.29,0.027,-0.0055,0.96,-0.37,-0.14,-0.017,-0.24,-0.11,-0.039,-0.0013,-0.0045,-7.1e-05,-0.0038,0.0016,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.51,0.5,0.022,1.1,1.1,0.059,7.7e-05,7.5e-05,5.8e-06,0.04,0.04,0.0015,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8090000,-0.29,0.027,-0.0055,0.96,-0.4,-0.15,-0.017,-0.28,-0.14,-0.041,-0.0011,-0.0045,-7.7e-05,-0.0036,0.0021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.56,0.55,0.022,1.2,1.2,0.059,7.4e-05,7.2e-05,5.8e-06,0.04,0.04,0.0014,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8190000,-0.29,0.027,-0.0057,0.96,-0.024,-0.01,-0.012,-0.29,-0.14,-0.035,-0.001,-0.0045,-8.1e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.021,1e+02,1e+02,0.058,7e-05,6.9e-05,5.7e-06,0.04,0.04,0.0013,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8290000,-0.29,0.027,-0.0057,0.96,-0.051,-0.021,-0.011,-0.29,-0.14,-0.035,-0.0011,-0.0048,-8.6e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.02,1e+02,1e+02,0.057,6.7e-05,6.5e-05,5.7e-06,0.04,0.04,0.0013,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8390000,-0.29,0.027,-0.0056,0.96,-0.075,-0.028,-0.01,-0.3,-0.14,-0.033,-0.0011,-0.0049,-8.8e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.02,51,51,0.057,6.4e-05,6.2e-05,5.7e-06,0.04,0.04,0.0012,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8490000,-0.29,0.027,-0.0054,0.96,-0.099,-0.038,-0.011,-0.3,-0.15,-0.038,-0.0013,-0.005,-8.6e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.019,52,52,0.056,6.1e-05,5.9e-05,5.7e-06,0.04,0.04,0.0011,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8590000,-0.29,0.027,-0.0054,0.96,-0.13,-0.047,-0.006,-0.31,-0.15,-0.032,-0.0011,-0.0049,-8.7e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0016,0.0015,0.049,25,25,0.019,35,35,0.055,5.7e-05,5.6e-05,5.7e-06,0.04,0.04,0.0011,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8690000,-0.29,0.027,-0.0054,0.96,-0.15,-0.055,-0.0078,-0.32,-0.15,-0.034,-0.0012,-0.005,-8.7e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0016,0.0015,0.049,25,25,0.018,37,37,0.055,5.4e-05,5.3e-05,5.7e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8790000,-0.29,0.027,-0.0055,0.96,-0.18,-0.062,-0.0075,-0.33,-0.15,-0.031,-0.0012,-0.0051,-9.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,24,24,0.018,28,28,0.055,5.1e-05,5e-05,5.7e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8890000,-0.29,0.027,-0.0054,0.96,-0.2,-0.074,-0.0029,-0.35,-0.16,-0.025,-0.0012,-0.005,-8.7e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,24,24,0.017,30,30,0.054,4.8e-05,4.7e-05,5.7e-06,0.04,0.04,0.00095,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8990000,-0.29,0.027,-0.0052,0.96,-0.22,-0.085,-0.0018,-0.35,-0.16,-0.027,-0.0013,-0.0048,-8e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,23,23,0.017,25,25,0.054,4.6e-05,4.4e-05,5.7e-06,0.04,0.04,0.00092,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9090000,-0.29,0.027,-0.005,0.96,-0.24,-0.098,-0.003,-0.37,-0.17,-0.027,-0.0014,-0.005,-7.8e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,23,23,0.017,27,27,0.053,4.3e-05,4.1e-05,5.7e-06,0.04,0.04,0.00088,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9190000,-0.29,0.027,-0.0049,0.96,-0.26,-0.11,-0.0023,-0.38,-0.18,-0.028,-0.0015,-0.005,-7.5e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0016,0.0015,0.049,21,21,0.016,23,23,0.053,4e-05,3.9e-05,5.7e-06,0.04,0.04,0.00084,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9290000,-0.29,0.027,-0.0047,0.96,-0.29,-0.12,-0.0004,-0.41,-0.19,-0.025,-0.0015,-0.0049,-7.3e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,21,21,0.016,26,26,0.052,3.8e-05,3.6e-05,5.7e-06,0.04,0.04,0.00081,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9390000,-0.29,0.027,-0.0048,0.96,-0.3,-0.12,0.00091,-0.41,-0.19,-0.025,-0.0014,-0.0049,-7.8e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,19,19,0.015,23,23,0.052,3.6e-05,3.4e-05,5.7e-06,0.04,0.04,0.00078,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9490000,-0.29,0.027,-0.0048,0.96,-0.33,-0.13,0.0026,-0.44,-0.2,-0.022,-0.0014,-0.005,-7.9e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,19,19,0.015,25,25,0.051,3.3e-05,3.2e-05,5.7e-06,0.04,0.04,0.00075,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9590000,-0.29,0.027,-0.0051,0.96,-0.33,-0.12,0.0027,-0.43,-0.19,-0.023,-0.0013,-0.0051,-8.8e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,17,17,0.015,22,22,0.051,3.1e-05,3e-05,5.7e-06,0.04,0.04,0.00072,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9690000,-0.29,0.027,-0.0052,0.96,-0.36,-0.13,0.0057,-0.47,-0.21,-0.022,-0.0012,-0.0051,-9e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,17,17,0.014,25,25,0.051,3e-05,2.8e-05,5.7e-06,0.04,0.04,0.0007,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9790000,-0.29,0.027,-0.0054,0.96,-0.36,-0.12,0.0043,-0.46,-0.2,-0.023,-0.0011,-0.0053,-9.8e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,22,22,0.05,2.8e-05,2.7e-05,5.7e-06,0.04,0.04,0.00068,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9890000,-0.29,0.027,-0.0054,0.96,-0.39,-0.13,0.0058,-0.49,-0.21,-0.023,-0.0011,-0.0052,-9.6e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,25,25,0.049,2.6e-05,2.5e-05,5.7e-06,0.04,0.04,0.00065,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9990000,-0.29,0.027,-0.0056,0.96,-0.38,-0.12,0.0065,-0.48,-0.2,-0.025,-0.001,-0.0053,-0.0001,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,13,13,0.014,22,22,0.049,2.5e-05,2.3e-05,5.7e-06,0.04,0.04,0.00063,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10090000,-0.29,0.027,-0.0057,0.96,-0.41,-0.12,0.0077,-0.52,-0.21,-0.023,-0.00092,-0.0054,-0.00011,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,14,14,0.013,24,24,0.049,2.3e-05,2.2e-05,5.7e-06,0.04,0.04,0.00061,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10190000,-0.29,0.027,-0.006,0.96,-0.44,-0.12,0.0086,-0.57,-0.22,-0.024,-0.00077,-0.0053,-0.00011,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,14,14,0.013,27,27,0.048,2.2e-05,2.1e-05,5.7e-06,0.04,0.04,0.00059,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10290000,-0.29,0.027,-0.006,0.96,-0.43,-0.12,0.0077,-0.55,-0.22,-0.023,-0.00081,-0.0053,-0.00011,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,12,12,0.013,24,24,0.048,2.1e-05,2e-05,5.7e-06,0.04,0.04,0.00058,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10390000,-0.29,0.027,-0.0059,0.96,-0.011,-0.0087,-0.0026,-6e-05,-0.0003,-0.022,-0.00084,-0.0053,-0.00011,-0.0038,0.002,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,1.9e-05,1.8e-05,5.6e-06,0.04,0.04,0.00056,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10490000,-0.29,0.027,-0.006,0.96,-0.04,-0.015,0.0064,-0.0026,-0.0014,-0.018,-0.00075,-0.0053,-0.00011,-0.0038,0.0024,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,1.8e-05,1.7e-05,5.6e-06,0.04,0.04,0.00055,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10590000,-0.29,0.027,-0.0059,0.96,-0.051,-0.014,0.012,-0.0032,-0.001,-0.016,-0.00082,-0.0053,-0.00011,-0.0032,0.002,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,1.7e-05,1.6e-05,5.6e-06,0.039,0.039,0.00054,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10690000,-0.29,0.027,-0.0059,0.96,-0.08,-0.02,0.015,-0.0097,-0.0027,-0.013,-0.0008,-0.0053,-0.00011,-0.0032,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,1.6e-05,1.6e-05,5.6e-06,0.039,0.039,0.00053,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10790000,-0.29,0.027,-0.0058,0.96,-0.078,-0.023,0.013,3.4e-06,-0.0018,-0.012,-0.00081,-0.0053,-0.00011,-0.00092,0.001,-0.14,-0.1,-0.022,0.5,0.079,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.096,0.096,0.17,0.13,0.13,0.062,1.5e-05,1.5e-05,5.6e-06,0.039,0.039,0.00052,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 -10890000,-0.29,0.027,-0.0056,0.96,-0.1,-0.033,0.009,-0.009,-0.0047,-0.015,-0.00091,-0.0053,-0.00011,-0.00093,0.0007,-0.14,-0.1,-0.022,0.5,0.079,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.4e-05,1.4e-05,5.6e-06,0.039,0.039,0.00051,0.0013,6.8e-05,0.0013,0.0013,0.00088,0.0013,1,1 -10990000,-0.29,0.026,-0.0056,0.96,-0.093,-0.034,0.015,-0.0033,-0.0023,-0.0093,-0.00093,-0.0055,-0.00011,0.0039,-0.00059,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.084,0.084,0.12,0.091,0.091,0.065,1.4e-05,1.3e-05,5.6e-06,0.038,0.038,0.00051,0.0013,6.8e-05,0.0013,0.0013,0.00087,0.0013,1,1 -11090000,-0.29,0.026,-0.006,0.96,-0.12,-0.041,0.019,-0.014,-0.0058,-0.0055,-0.00082,-0.0054,-0.00011,0.0038,-0.0003,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0014,0.0013,0.048,0.097,0.098,0.11,0.097,0.097,0.069,1.3e-05,1.2e-05,5.6e-06,0.038,0.038,0.0005,0.0013,6.8e-05,0.0013,0.0013,0.00087,0.0013,1,1 -11190000,-0.29,0.025,-0.0062,0.96,-0.1,-0.036,0.026,-0.0063,-0.0032,0.00088,-0.00081,-0.0056,-0.00012,0.011,-0.0022,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0013,0.0012,0.048,0.08,0.08,0.083,0.072,0.072,0.066,1.2e-05,1.1e-05,5.6e-06,0.037,0.037,0.0005,0.0013,6.7e-05,0.0013,0.0012,0.00086,0.0013,1,1 -11290000,-0.29,0.025,-0.0062,0.96,-0.12,-0.04,0.025,-0.017,-0.0069,0.00092,-0.00081,-0.0056,-0.00012,0.011,-0.0022,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0013,0.0012,0.048,0.095,0.095,0.077,0.078,0.078,0.069,1.2e-05,1.1e-05,5.6e-06,0.037,0.037,0.0005,0.0013,6.7e-05,0.0013,0.0012,0.00086,0.0013,1,1 -11390000,-0.29,0.023,-0.0061,0.96,-0.1,-0.034,0.016,-0.0096,-0.0041,-0.008,-0.00084,-0.0057,-0.00012,0.018,-0.0041,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0011,0.0011,0.048,0.079,0.079,0.062,0.062,0.062,0.066,1.1e-05,1e-05,5.6e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1 -11490000,-0.29,0.023,-0.0061,0.96,-0.12,-0.038,0.021,-0.021,-0.0078,-0.002,-0.00084,-0.0057,-0.00012,0.018,-0.0041,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0011,0.0011,0.048,0.094,0.094,0.057,0.069,0.069,0.067,1e-05,9.8e-06,5.6e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1 -11590000,-0.29,0.022,-0.0062,0.96,-0.1,-0.031,0.019,-0.012,-0.0047,-0.0033,-0.00087,-0.0058,-0.00012,0.025,-0.0061,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.069,0,0,0.001,0.00096,0.048,0.078,0.078,0.048,0.056,0.056,0.065,9.7e-06,9.2e-06,5.6e-06,0.035,0.035,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00084,0.0013,1,1 -11690000,-0.29,0.022,-0.0062,0.96,-0.12,-0.037,0.019,-0.023,-0.0081,-0.0047,-0.00089,-0.0059,-0.00012,0.025,-0.0061,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.069,0,0,0.001,0.00096,0.048,0.092,0.093,0.044,0.063,0.063,0.066,9.2e-06,8.8e-06,5.6e-06,0.035,0.035,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00084,0.0013,1,1 -11790000,-0.29,0.021,-0.006,0.96,-0.094,-0.035,0.02,-0.013,-0.0067,-0.0019,-0.00097,-0.0059,-0.00012,0.031,-0.0081,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.07,0,0,0.00088,0.00085,0.048,0.076,0.076,0.037,0.053,0.053,0.063,8.7e-06,8.2e-06,5.6e-06,0.034,0.034,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 -11890000,-0.29,0.021,-0.0062,0.96,-0.11,-0.039,0.018,-0.023,-0.01,-0.0012,-0.00095,-0.006,-0.00012,0.031,-0.0082,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.07,0,0,0.00088,0.00085,0.047,0.089,0.089,0.034,0.06,0.06,0.063,8.3e-06,7.9e-06,5.6e-06,0.034,0.034,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1 -11990000,-0.29,0.02,-0.0064,0.96,-0.087,-0.029,0.015,-0.016,-0.0067,-0.0049,-0.00096,-0.006,-0.00012,0.037,-0.0093,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.00078,0.00076,0.047,0.077,0.077,0.03,0.062,0.062,0.061,7.9e-06,7.5e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0013,0.0012,0.00081,0.0013,1,1 -12090000,-0.29,0.02,-0.0063,0.96,-0.1,-0.031,0.019,-0.026,-0.0096,0.0012,-0.00093,-0.006,-0.00012,0.037,-0.0095,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.00078,0.00076,0.047,0.089,0.089,0.027,0.071,0.071,0.06,7.6e-06,7.1e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00081,0.0013,1,1 -12190000,-0.29,0.019,-0.0064,0.96,-0.081,-0.019,0.018,-0.014,-0.0034,0.0031,-0.00089,-0.006,-0.00012,0.043,-0.011,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.0007,0.00068,0.047,0.071,0.071,0.024,0.057,0.057,0.058,7.2e-06,6.8e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 -12290000,-0.29,0.019,-0.0065,0.96,-0.087,-0.018,0.017,-0.022,-0.0051,0.0041,-0.00086,-0.006,-0.00012,0.043,-0.011,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.0007,0.00068,0.047,0.081,0.081,0.022,0.065,0.065,0.058,6.9e-06,6.5e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 -12390000,-0.29,0.018,-0.0065,0.96,-0.07,-0.013,0.015,-0.012,-0.0029,-0.0019,-0.00086,-0.006,-0.00012,0.046,-0.013,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00063,0.00061,0.047,0.066,0.066,0.02,0.054,0.054,0.056,6.6e-06,6.2e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00079,0.0012,1,1 -12490000,-0.29,0.019,-0.0066,0.96,-0.077,-0.015,0.02,-0.02,-0.0042,0.00028,-0.00083,-0.006,-0.00012,0.046,-0.013,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00063,0.00061,0.047,0.075,0.075,0.018,0.062,0.062,0.055,6.3e-06,5.9e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00079,0.0012,1,1 -12590000,-0.29,0.018,-0.0065,0.96,-0.063,-0.012,0.021,-0.0099,-0.004,0.0021,-0.00084,-0.0061,-0.00013,0.049,-0.014,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00058,0.00056,0.047,0.061,0.061,0.017,0.052,0.052,0.054,6.1e-06,5.7e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 -12690000,-0.29,0.018,-0.0065,0.96,-0.069,-0.011,0.021,-0.016,-0.0051,0.0038,-0.00083,-0.0061,-0.00013,0.049,-0.015,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00058,0.00057,0.047,0.07,0.07,0.015,0.059,0.059,0.053,5.9e-06,5.5e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 -12790000,-0.29,0.017,-0.0063,0.96,-0.054,-0.016,0.022,-0.0096,-0.008,0.006,-0.00088,-0.006,-0.00013,0.052,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00054,0.00053,0.047,0.061,0.061,0.014,0.061,0.061,0.051,5.6e-06,5.2e-06,5.6e-06,0.031,0.031,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 -12890000,-0.29,0.017,-0.0062,0.96,-0.058,-0.017,0.023,-0.015,-0.0099,0.0091,-0.0009,-0.006,-0.00012,0.052,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00054,0.00053,0.047,0.069,0.069,0.013,0.07,0.07,0.051,5.4e-06,5.1e-06,5.6e-06,0.031,0.031,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 -12990000,-0.29,0.017,-0.0062,0.96,-0.047,-0.014,0.024,-0.0076,-0.0068,0.01,-0.00093,-0.006,-0.00012,0.054,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00051,0.0005,0.046,0.055,0.055,0.012,0.057,0.056,0.05,5.2e-06,4.8e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13090000,-0.29,0.017,-0.0062,0.96,-0.052,-0.016,0.021,-0.013,-0.0086,0.0093,-0.00096,-0.006,-0.00012,0.054,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00051,0.0005,0.046,0.062,0.062,0.011,0.065,0.065,0.049,5e-06,4.7e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13190000,-0.29,0.017,-0.0061,0.96,-0.043,-0.015,0.021,-0.0093,-0.0093,0.01,-0.00098,-0.006,-0.00012,0.055,-0.016,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00048,0.00047,0.046,0.055,0.055,0.011,0.066,0.066,0.047,4.9e-06,4.5e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13290000,-0.29,0.017,-0.0062,0.96,-0.047,-0.016,0.018,-0.014,-0.011,0.0094,-0.00096,-0.006,-0.00012,0.055,-0.016,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00049,0.00048,0.046,0.061,0.061,0.01,0.075,0.075,0.047,4.7e-06,4.3e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13390000,-0.29,0.017,-0.0062,0.96,-0.038,-0.012,0.018,-0.0071,-0.0072,0.01,-0.00095,-0.006,-0.00012,0.056,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00046,0.00045,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,4.5e-06,4.2e-06,5.6e-06,0.031,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13490000,-0.29,0.017,-0.0062,0.96,-0.041,-0.014,0.018,-0.011,-0.0086,0.0064,-0.00094,-0.006,-0.00012,0.057,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00046,0.00045,0.046,0.054,0.054,0.009,0.068,0.068,0.045,4.4e-06,4e-06,5.6e-06,0.031,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13590000,-0.29,0.017,-0.0062,0.96,-0.033,-0.01,0.019,-0.0033,-0.0058,0.005,-0.00092,-0.006,-0.00012,0.058,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00045,0.00044,0.046,0.044,0.044,0.0086,0.055,0.055,0.044,4.3e-06,3.9e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13690000,-0.29,0.016,-0.0061,0.96,-0.035,-0.01,0.019,-0.0067,-0.007,0.0078,-0.00094,-0.006,-0.00012,0.058,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00045,0.00044,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,4.1e-06,3.8e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13790000,-0.29,0.016,-0.0062,0.96,-0.027,-0.0076,0.019,0.00083,-0.0036,0.0074,-0.00093,-0.006,-0.00012,0.059,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00043,0.00042,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4e-06,3.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -13890000,-0.29,0.016,-0.0061,0.96,-0.029,-0.009,0.02,-0.0018,-0.0046,0.0097,-0.00096,-0.006,-0.00012,0.059,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00043,0.00042,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,3.9e-06,3.5e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -13990000,-0.29,0.016,-0.006,0.96,-0.028,-0.012,0.019,-0.00049,-0.005,0.0087,-0.00098,-0.006,-0.00012,0.06,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00042,0.00041,0.046,0.038,0.038,0.0073,0.05,0.05,0.041,3.7e-06,3.4e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14090000,-0.29,0.016,-0.0062,0.96,-0.028,-0.0066,0.021,-0.0036,-0.0055,0.0053,-0.00091,-0.006,-0.00012,0.06,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00042,0.00041,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,3.6e-06,3.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14190000,-0.29,0.016,-0.0062,0.96,-0.023,-0.0051,0.021,-0.00069,-0.0042,0.0056,-0.00087,-0.006,-0.00012,0.06,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.00041,0.046,0.036,0.036,0.007,0.049,0.049,0.04,3.5e-06,3.2e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14290000,-0.29,0.016,-0.0062,0.96,-0.026,-0.0055,0.019,-0.0031,-0.0046,0.0099,-0.00087,-0.006,-0.00012,0.06,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.00041,0.046,0.039,0.04,0.0069,0.055,0.055,0.039,3.4e-06,3.1e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14390000,-0.29,0.016,-0.0062,0.96,-0.024,-0.0049,0.02,-0.00066,-0.005,0.014,-0.00088,-0.006,-0.00012,0.061,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.0004,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,3.3e-06,3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14490000,-0.29,0.016,-0.0064,0.96,-0.024,-0.0043,0.024,-0.0032,-0.0052,0.017,-0.00084,-0.006,-0.00013,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.0004,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.2e-06,2.9e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14590000,-0.29,0.016,-0.0064,0.96,-0.026,-0.0058,0.022,-0.0035,-0.0055,0.013,-0.00083,-0.0059,-0.00013,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.00039,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.1e-06,2.8e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14690000,-0.29,0.016,-0.0064,0.96,-0.027,-0.0061,0.022,-0.0062,-0.0062,0.013,-0.00083,-0.0059,-0.00013,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.0004,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.1e-06,2.7e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14790000,-0.29,0.016,-0.0066,0.96,-0.028,-0.0033,0.022,-0.0048,-0.0016,0.016,-0.00085,-0.0059,-0.00012,0.063,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.00039,0.046,0.03,0.031,0.0064,0.046,0.046,0.036,3e-06,2.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14890000,-0.29,0.016,-0.0064,0.96,-0.03,-0.0014,0.027,-0.008,-0.0021,0.017,-0.00085,-0.0058,-0.00012,0.063,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.00039,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,2.9e-06,2.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14990000,-0.29,0.016,-0.0065,0.96,-0.028,-0.0031,0.029,-0.0064,-0.0032,0.02,-0.00086,-0.0058,-0.00012,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.07,0,0,0.00039,0.00039,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,2.8e-06,2.5e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15090000,-0.29,0.016,-0.0064,0.96,-0.03,-0.0043,0.033,-0.0093,-0.0035,0.022,-0.00085,-0.0058,-0.00012,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.07,0,0,0.00039,0.00039,0.046,0.031,0.032,0.0064,0.051,0.051,0.035,2.7e-06,2.4e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15190000,-0.29,0.016,-0.0066,0.96,-0.028,-0.0023,0.034,-0.0075,-0.0027,0.024,-0.00084,-0.0058,-0.00012,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.027,0.028,0.0064,0.045,0.045,0.035,2.7e-06,2.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15290000,-0.29,0.016,-0.0066,0.96,-0.031,-0.0024,0.034,-0.011,-0.0033,0.021,-0.00085,-0.0058,-0.00012,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,2.6e-06,2.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15390000,-0.29,0.016,-0.0067,0.96,-0.03,-0.0042,0.033,-0.0086,-0.0027,0.022,-0.00085,-0.0058,-0.00012,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.026,0.026,0.0065,0.044,0.044,0.034,2.5e-06,2.2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1 -15490000,-0.29,0.016,-0.0068,0.96,-0.031,-0.0018,0.033,-0.012,-0.0031,0.023,-0.00085,-0.0058,-0.00012,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.028,0.028,0.0065,0.05,0.05,0.034,2.5e-06,2.2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1 -15590000,-0.29,0.016,-0.0067,0.96,-0.028,-0.006,0.033,-0.0071,-0.0062,0.022,-0.00088,-0.0058,-0.00012,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.4e-06,2.1e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1 -15690000,-0.29,0.016,-0.0066,0.96,-0.03,-0.0041,0.034,-0.0093,-0.0067,0.023,-0.00091,-0.0058,-0.00012,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.4e-06,2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -15790000,-0.29,0.016,-0.0066,0.96,-0.026,-0.0026,0.033,-0.0072,-0.0058,0.024,-0.00095,-0.0058,-0.00012,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.024,0.024,0.0066,0.043,0.043,0.033,2.3e-06,2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -15890000,-0.29,0.016,-0.0067,0.96,-0.026,-0.004,0.034,-0.01,-0.0059,0.024,-0.00092,-0.0058,-0.00012,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.026,0.026,0.0068,0.049,0.049,0.034,2.2e-06,1.9e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -15990000,-0.29,0.016,-0.0066,0.96,-0.024,-0.0033,0.031,-0.0084,-0.0049,0.024,-0.00091,-0.0058,-0.00012,0.066,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.2e-06,1.9e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16090000,-0.29,0.016,-0.0066,0.96,-0.026,-0.0021,0.029,-0.011,-0.0051,0.024,-0.0009,-0.0058,-0.00012,0.066,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.024,0.025,0.0069,0.048,0.048,0.033,2.1e-06,1.8e-06,5.6e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16190000,-0.29,0.016,-0.0066,0.96,-0.024,-0.0018,0.028,-0.01,-0.0042,0.021,-0.00088,-0.0058,-0.00012,0.066,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.1e-06,1.8e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16290000,-0.29,0.016,-0.0066,0.96,-0.026,-0.00094,0.028,-0.013,-0.0044,0.022,-0.00089,-0.0058,-0.00012,0.066,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.023,0.024,0.007,0.048,0.048,0.033,2e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16390000,-0.29,0.016,-0.0066,0.96,-0.025,-0.0013,0.028,-0.01,-0.0041,0.022,-0.0009,-0.0058,-0.00012,0.067,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16490000,-0.29,0.016,-0.0067,0.96,-0.03,-0.00031,0.031,-0.013,-0.0041,0.027,-0.00089,-0.0058,-0.00012,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.023,0.0072,0.047,0.047,0.033,1.9e-06,1.6e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16590000,-0.29,0.016,-0.0067,0.96,-0.033,0.00016,0.034,-0.011,-0.0035,0.027,-0.0009,-0.0058,-0.00012,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.02,0.02,0.0072,0.042,0.042,0.033,1.9e-06,1.6e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 -16690000,-0.29,0.016,-0.0067,0.96,-0.036,0.0038,0.034,-0.015,-0.0035,0.028,-0.00091,-0.0058,-0.00012,0.067,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.022,0.0073,0.047,0.047,0.033,1.9e-06,1.6e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 -16790000,-0.29,0.016,-0.0066,0.96,-0.036,0.0036,0.033,-0.012,-0.0031,0.028,-0.00093,-0.0058,-0.00012,0.067,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.0073,0.042,0.042,0.033,1.8e-06,1.5e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 -16890000,-0.29,0.016,-0.0065,0.96,-0.036,0.0032,0.034,-0.016,-0.0032,0.027,-0.00095,-0.0058,-0.00012,0.067,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.8e-06,1.5e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 -16990000,-0.29,0.016,-0.0066,0.96,-0.034,0.0037,0.034,-0.014,-0.0033,0.025,-0.00096,-0.0058,-0.00012,0.067,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.02,0.021,0.0074,0.049,0.049,0.033,1.7e-06,1.5e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 -17090000,-0.29,0.016,-0.0067,0.96,-0.038,0.0056,0.034,-0.018,-0.0029,0.025,-0.00095,-0.0058,-0.00012,0.068,-0.02,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.7e-06,1.4e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17190000,-0.29,0.016,-0.0068,0.96,-0.037,0.0074,0.035,-0.017,-0.0046,0.028,-0.00095,-0.0058,-0.00013,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.022,0.0076,0.056,0.057,0.033,1.7e-06,1.4e-06,5.6e-06,0.03,0.029,0.00041,0.0012,6e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17290000,-0.29,0.016,-0.0068,0.96,-0.04,0.0079,0.035,-0.021,-0.0035,0.028,-0.00093,-0.0058,-0.00013,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.023,0.023,0.0077,0.062,0.063,0.033,1.6e-06,1.4e-06,5.6e-06,0.03,0.029,0.00041,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17390000,-0.29,0.016,-0.0067,0.96,-0.03,0.013,0.034,-0.013,-0.002,0.028,-0.00096,-0.0058,-0.00013,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.0076,0.052,0.052,0.033,1.6e-06,1.3e-06,5.6e-06,0.03,0.029,0.00041,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17490000,-0.29,0.016,-0.0067,0.96,-0.03,0.014,0.034,-0.016,-0.00051,0.03,-0.00096,-0.0058,-0.00013,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.3e-06,5.6e-06,0.03,0.029,0.0004,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17590000,-0.29,0.016,-0.0067,0.96,-0.03,0.012,0.033,-0.015,-0.00075,0.027,-0.00096,-0.0058,-0.00013,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.5e-06,1.3e-06,5.5e-06,0.03,0.029,0.0004,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17690000,-0.29,0.016,-0.0068,0.96,-0.031,0.013,0.034,-0.018,0.00034,0.03,-0.00097,-0.0058,-0.00013,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.2e-06,5.6e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17790000,-0.29,0.016,-0.0069,0.96,-0.031,0.013,0.035,-0.017,0.0011,0.035,-0.00098,-0.0058,-0.00013,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.2e-06,5.5e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17890000,-0.29,0.016,-0.0068,0.96,-0.035,0.014,0.034,-0.02,0.0023,0.039,-0.00099,-0.0058,-0.00013,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.02,0.021,0.0079,0.062,0.062,0.033,1.4e-06,1.2e-06,5.5e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -17990000,-0.29,0.016,-0.0068,0.96,-0.033,0.015,0.034,-0.016,0.0047,0.04,-0.00099,-0.0058,-0.00013,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.2e-06,5.5e-06,0.03,0.029,0.00038,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18090000,-0.29,0.016,-0.0069,0.96,-0.035,0.016,0.033,-0.02,0.0062,0.038,-0.00099,-0.0058,-0.00013,0.068,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.1e-06,5.5e-06,0.03,0.029,0.00038,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18190000,-0.28,0.016,-0.0068,0.96,-0.032,0.014,0.034,-0.015,0.0041,0.036,-0.001,-0.0058,-0.00013,0.069,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.0079,0.049,0.049,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18290000,-0.28,0.016,-0.0068,0.96,-0.035,0.014,0.033,-0.019,0.0052,0.035,-0.001,-0.0058,-0.00013,0.069,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.018,0.008,0.053,0.054,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18390000,-0.28,0.016,-0.0068,0.96,-0.031,0.013,0.032,-0.014,0.0044,0.034,-0.001,-0.0058,-0.00014,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18490000,-0.28,0.016,-0.0068,0.96,-0.035,0.012,0.031,-0.017,0.0053,0.036,-0.001,-0.0058,-0.00013,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.017,0.018,0.008,0.05,0.051,0.034,1.3e-06,1e-06,5.5e-06,0.03,0.029,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18590000,-0.28,0.015,-0.0067,0.96,-0.033,0.013,0.031,-0.014,0.0047,0.038,-0.001,-0.0058,-0.00014,0.069,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.2e-06,1e-06,5.5e-06,0.03,0.029,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18690000,-0.28,0.015,-0.0066,0.96,-0.033,0.011,0.029,-0.017,0.0056,0.037,-0.0011,-0.0058,-0.00014,0.069,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1e-06,5.5e-06,0.03,0.029,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18790000,-0.28,0.015,-0.0066,0.96,-0.03,0.011,0.029,-0.013,0.0048,0.035,-0.0011,-0.0058,-0.00014,0.069,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,9.7e-07,5.5e-06,0.03,0.029,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18890000,-0.28,0.015,-0.0066,0.96,-0.03,0.012,0.027,-0.016,0.006,0.031,-0.0011,-0.0058,-0.00014,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,9.6e-07,5.4e-06,0.03,0.029,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -18990000,-0.28,0.015,-0.0065,0.96,-0.027,0.012,0.028,-0.014,0.0052,0.034,-0.0011,-0.0058,-0.00015,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0079,0.042,0.042,0.034,1.1e-06,9.3e-07,5.4e-06,0.03,0.029,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19090000,-0.28,0.015,-0.0066,0.96,-0.027,0.012,0.028,-0.017,0.0059,0.031,-0.0011,-0.0058,-0.00014,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.008,0.045,0.046,0.035,1.1e-06,9.2e-07,5.4e-06,0.03,0.029,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19190000,-0.28,0.015,-0.0065,0.96,-0.024,0.013,0.028,-0.014,0.0058,0.03,-0.0011,-0.0058,-0.00015,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9e-07,5.4e-06,0.03,0.029,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19290000,-0.28,0.015,-0.0065,0.96,-0.025,0.013,0.028,-0.017,0.007,0.029,-0.0011,-0.0058,-0.00015,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,8.9e-07,5.4e-06,0.03,0.029,0.00032,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19390000,-0.28,0.015,-0.0066,0.96,-0.024,0.012,0.029,-0.015,0.0069,0.028,-0.0011,-0.0058,-0.00016,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,8.6e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19490000,-0.28,0.015,-0.0067,0.96,-0.026,0.013,0.029,-0.018,0.0083,0.027,-0.0011,-0.0058,-0.00016,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,8.5e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19590000,-0.28,0.015,-0.0066,0.96,-0.023,0.014,0.031,-0.015,0.0065,0.028,-0.0011,-0.0058,-0.00017,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0078,0.039,0.039,0.035,1e-06,8.3e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -19690000,-0.28,0.015,-0.0066,0.96,-0.023,0.012,0.029,-0.018,0.0073,0.027,-0.0011,-0.0058,-0.00017,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.2e-07,5.4e-06,0.03,0.029,0.0003,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -19790000,-0.28,0.015,-0.0067,0.96,-0.02,0.012,0.027,-0.018,0.0079,0.023,-0.0011,-0.0058,-0.00017,0.069,-0.02,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,9.9e-07,8e-07,5.3e-06,0.03,0.029,0.0003,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -19890000,-0.28,0.015,-0.0067,0.96,-0.021,0.012,0.028,-0.02,0.0091,0.022,-0.0011,-0.0058,-0.00017,0.069,-0.02,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,9.8e-07,7.9e-07,5.3e-06,0.03,0.029,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -19990000,-0.28,0.016,-0.0067,0.96,-0.018,0.013,0.025,-0.015,0.0084,0.019,-0.0011,-0.0058,-0.00018,0.069,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.5e-07,7.7e-07,5.3e-06,0.03,0.029,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20090000,-0.28,0.016,-0.0067,0.96,-0.021,0.016,0.025,-0.017,0.0097,0.022,-0.0011,-0.0058,-0.00018,0.069,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0076,0.047,0.048,0.035,9.4e-07,7.6e-07,5.3e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20190000,-0.28,0.016,-0.0067,0.96,-0.021,0.013,0.026,-0.019,0.01,0.021,-0.0011,-0.0058,-0.00018,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0075,0.049,0.05,0.035,9.2e-07,7.5e-07,5.3e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20290000,-0.28,0.016,-0.0067,0.96,-0.02,0.016,0.026,-0.021,0.011,0.022,-0.0011,-0.0058,-0.00018,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.1e-07,7.4e-07,5.3e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20390000,-0.28,0.016,-0.0066,0.96,-0.018,0.014,0.026,-0.021,0.011,0.023,-0.0011,-0.0058,-0.00019,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,8.9e-07,7.2e-07,5.2e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20490000,-0.28,0.016,-0.0066,0.96,-0.015,0.016,0.026,-0.023,0.012,0.021,-0.0011,-0.0058,-0.00018,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,8.8e-07,7.1e-07,5.2e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20590000,-0.28,0.016,-0.0065,0.96,-0.015,0.015,0.025,-0.023,0.011,0.019,-0.0011,-0.0058,-0.00018,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.018,0.0074,0.064,0.065,0.035,8.6e-07,7e-07,5.2e-06,0.029,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20690000,-0.28,0.016,-0.0065,0.96,-0.014,0.016,0.026,-0.024,0.013,0.02,-0.0011,-0.0058,-0.00019,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.5e-07,6.9e-07,5.2e-06,0.029,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20790000,-0.28,0.015,-0.0059,0.96,-0.0088,0.011,0.011,-0.018,0.0093,0.019,-0.0012,-0.0058,-0.00019,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00035,0.046,0.015,0.017,0.0073,0.056,0.057,0.035,8.2e-07,6.7e-07,5.2e-06,0.029,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20890000,-0.28,0.011,0.0028,0.96,-0.0041,0.001,-0.11,-0.02,0.0098,0.012,-0.0012,-0.0058,-0.00019,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00036,0.00034,0.046,0.016,0.018,0.0073,0.061,0.062,0.035,8.2e-07,6.6e-07,5.2e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20990000,-0.28,0.0069,0.0058,0.96,0.01,-0.015,-0.25,-0.016,0.0075,-0.0029,-0.0011,-0.0058,-0.0002,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0072,0.051,0.052,0.034,7.9e-07,6.4e-07,5.1e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21090000,-0.28,0.0074,0.0042,0.96,0.024,-0.028,-0.37,-0.015,0.0055,-0.033,-0.0011,-0.0058,-0.00021,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00034,0.046,0.015,0.017,0.0072,0.056,0.057,0.035,7.9e-07,6.4e-07,5.1e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21190000,-0.28,0.0093,0.0016,0.96,0.03,-0.033,-0.49,-0.012,0.0042,-0.07,-0.0011,-0.0058,-0.0002,0.07,-0.021,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00033,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.6e-07,6.2e-07,5.1e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21290000,-0.28,0.011,-0.00045,0.96,0.028,-0.035,-0.62,-0.0097,0.0016,-0.13,-0.0011,-0.0058,-0.00021,0.07,-0.021,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.6e-07,6.2e-07,5.1e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21390000,-0.29,0.012,-0.0019,0.96,0.022,-0.028,-0.75,-0.011,0.005,-0.19,-0.0011,-0.0058,-0.00018,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.007,0.054,0.055,0.035,7.4e-07,6e-07,5e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21490000,-0.29,0.012,-0.0027,0.96,0.015,-0.026,-0.88,-0.0091,0.0021,-0.28,-0.0011,-0.0058,-0.00018,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.018,0.007,0.059,0.06,0.035,7.4e-07,6e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21590000,-0.29,0.012,-0.0033,0.96,0.0031,-0.02,-1,-0.013,0.0071,-0.37,-0.0011,-0.0058,-0.00015,0.07,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.018,0.0069,0.061,0.063,0.034,7.2e-07,5.9e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21690000,-0.29,0.012,-0.0036,0.96,-0.0023,-0.016,-1.1,-0.013,0.0047,-0.48,-0.0011,-0.0058,-0.00014,0.07,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.017,0.02,0.0069,0.066,0.068,0.035,7.2e-07,5.8e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21790000,-0.29,0.012,-0.004,0.96,-0.0083,-0.0076,-1.3,-0.015,0.011,-0.6,-0.0011,-0.0058,-0.00011,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.017,0.02,0.0069,0.068,0.07,0.034,7e-07,5.7e-07,4.9e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21890000,-0.29,0.012,-0.0043,0.96,-0.014,-0.0031,-1.4,-0.016,0.011,-0.74,-0.0011,-0.0058,-0.00011,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.046,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,5.7e-07,4.9e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21990000,-0.29,0.013,-0.0051,0.96,-0.02,0.0053,-1.4,-0.023,0.018,-0.88,-0.0011,-0.0058,-8.3e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.046,0.018,0.02,0.0068,0.076,0.079,0.034,6.8e-07,5.5e-07,4.9e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22090000,-0.29,0.014,-0.0057,0.96,-0.023,0.0086,-1.4,-0.024,0.019,-1,-0.0011,-0.0058,-7.6e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.046,0.019,0.021,0.0068,0.082,0.085,0.034,6.7e-07,5.5e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22190000,-0.29,0.014,-0.0062,0.96,-0.03,0.015,-1.4,-0.028,0.026,-1.2,-0.0011,-0.0058,-4.8e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.4e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22290000,-0.29,0.014,-0.0069,0.96,-0.038,0.02,-1.4,-0.032,0.028,-1.3,-0.0011,-0.0058,-4.9e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.5e-07,5.3e-07,4.8e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22390000,-0.29,0.015,-0.0072,0.96,-0.045,0.027,-1.4,-0.038,0.032,-1.5,-0.0011,-0.0058,-5e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0066,0.093,0.096,0.034,6.4e-07,5.2e-07,4.8e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22490000,-0.29,0.015,-0.0073,0.96,-0.051,0.033,-1.4,-0.043,0.036,-1.6,-0.0011,-0.0058,-5.3e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0066,0.1,0.1,0.034,6.4e-07,5.2e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22590000,-0.29,0.016,-0.0071,0.96,-0.056,0.038,-1.4,-0.044,0.039,-1.7,-0.0011,-0.0058,-4.5e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.1e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22690000,-0.29,0.016,-0.0071,0.96,-0.061,0.043,-1.4,-0.051,0.043,-1.9,-0.0011,-0.0058,-4.7e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.02,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5e-07,4.7e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22790000,-0.29,0.016,-0.007,0.96,-0.067,0.048,-1.4,-0.057,0.046,-2,-0.0011,-0.0058,-5.6e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,4.9e-07,4.7e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22890000,-0.29,0.017,-0.0071,0.96,-0.072,0.052,-1.4,-0.063,0.05,-2.2,-0.0011,-0.0058,-4.7e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,4.9e-07,4.7e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22990000,-0.29,0.017,-0.0069,0.96,-0.075,0.052,-1.4,-0.066,0.048,-2.3,-0.0011,-0.0058,-5.3e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.8e-07,4.8e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23090000,-0.28,0.017,-0.0069,0.96,-0.081,0.056,-1.4,-0.073,0.054,-2.5,-0.0011,-0.0058,-5.1e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0064,0.13,0.13,0.034,5.8e-07,4.8e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23190000,-0.28,0.017,-0.0068,0.96,-0.082,0.051,-1.4,-0.073,0.05,-2.6,-0.0011,-0.0058,-7.9e-05,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.7e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23290000,-0.28,0.018,-0.0072,0.96,-0.089,0.054,-1.4,-0.081,0.054,-2.7,-0.0011,-0.0058,-7.4e-05,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0063,0.14,0.14,0.034,5.7e-07,4.7e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23390000,-0.28,0.018,-0.0071,0.96,-0.088,0.057,-1.4,-0.076,0.056,-2.9,-0.0011,-0.0058,-9.6e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.6e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23490000,-0.28,0.018,-0.0072,0.96,-0.095,0.057,-1.4,-0.086,0.06,-3,-0.0011,-0.0058,-8.6e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.5e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23590000,-0.28,0.018,-0.0073,0.96,-0.093,0.051,-1.4,-0.081,0.05,-3.2,-0.0011,-0.0058,-0.00012,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.4e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23690000,-0.28,0.018,-0.0079,0.96,-0.092,0.053,-1.3,-0.091,0.055,-3.3,-0.0011,-0.0058,-0.00011,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.4e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23790000,-0.28,0.021,-0.0094,0.96,-0.077,0.05,-0.95,-0.081,0.05,-3.4,-0.0012,-0.0058,-0.00012,0.069,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00039,0.00036,0.045,0.02,0.023,0.0061,0.16,0.16,0.033,5.3e-07,4.3e-07,4.4e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23890000,-0.28,0.026,-0.012,0.96,-0.07,0.051,-0.52,-0.088,0.054,-3.5,-0.0012,-0.0058,-0.00012,0.069,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00042,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.2e-07,4.3e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23990000,-0.28,0.028,-0.014,0.96,-0.061,0.049,-0.13,-0.076,0.049,-3.6,-0.0012,-0.0058,-0.00014,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.3e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24090000,-0.28,0.027,-0.014,0.96,-0.067,0.056,0.1,-0.081,0.054,-3.6,-0.0012,-0.0058,-0.00013,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00042,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.2e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24190000,-0.28,0.023,-0.011,0.96,-0.071,0.053,0.09,-0.068,0.041,-3.6,-0.0012,-0.0058,-0.00016,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.2e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24290000,-0.28,0.019,-0.0092,0.96,-0.075,0.055,0.068,-0.075,0.046,-3.6,-0.0012,-0.0058,-0.00016,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00038,0.00035,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.1e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24390000,-0.28,0.018,-0.0084,0.96,-0.059,0.048,0.084,-0.057,0.037,-3.6,-0.0013,-0.0058,-0.00017,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00035,0.045,0.02,0.022,0.006,0.19,0.19,0.033,4.9e-07,4.1e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24490000,-0.28,0.018,-0.0086,0.96,-0.054,0.045,0.082,-0.062,0.04,-3.6,-0.0013,-0.0058,-0.00016,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.024,0.006,0.2,0.2,0.033,4.9e-07,4.1e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24590000,-0.28,0.019,-0.0093,0.96,-0.043,0.043,0.077,-0.044,0.034,-3.6,-0.0013,-0.0059,-0.00018,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.02,0.023,0.0059,0.2,0.2,0.033,4.8e-07,4e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24690000,-0.28,0.018,-0.0098,0.96,-0.04,0.042,0.077,-0.048,0.038,-3.5,-0.0013,-0.0059,-0.00017,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24790000,-0.28,0.018,-0.0099,0.96,-0.034,0.04,0.068,-0.036,0.03,-3.5,-0.0013,-0.0059,-0.00019,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.02,0.023,0.0059,0.21,0.21,0.032,4.7e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24890000,-0.28,0.017,-0.0098,0.96,-0.033,0.043,0.058,-0.039,0.033,-3.5,-0.0013,-0.0059,-0.00018,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0059,0.22,0.22,0.032,4.7e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24990000,-0.28,0.017,-0.0096,0.96,-0.021,0.043,0.051,-0.025,0.028,-3.5,-0.0013,-0.0059,-0.0002,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25090000,-0.28,0.017,-0.0099,0.96,-0.016,0.043,0.048,-0.026,0.032,-3.5,-0.0013,-0.0059,-0.0002,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0058,0.23,0.23,0.032,4.6e-07,3.8e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25190000,-0.28,0.017,-0.01,0.96,-0.006,0.039,0.048,-0.011,0.022,-3.5,-0.0013,-0.0059,-0.00023,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.8e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25290000,-0.28,0.016,-0.01,0.96,-0.0012,0.042,0.043,-0.011,0.026,-3.5,-0.0013,-0.0059,-0.00023,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.8e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25390000,-0.28,0.016,-0.011,0.96,0.0075,0.04,0.042,-0.0015,0.021,-3.5,-0.0013,-0.0059,-0.00025,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.5e-07,3.7e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25490000,-0.28,0.016,-0.011,0.96,0.012,0.041,0.041,-0.0014,0.024,-3.5,-0.0013,-0.0059,-0.00025,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.4e-07,3.7e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25590000,-0.28,0.016,-0.011,0.96,0.017,0.036,0.042,0.0056,0.0097,-3.5,-0.0014,-0.0059,-0.00028,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.4e-07,3.7e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25690000,-0.28,0.015,-0.01,0.96,0.018,0.035,0.031,0.0074,0.013,-3.5,-0.0014,-0.0059,-0.00027,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.4e-07,3.7e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25790000,-0.28,0.015,-0.01,0.96,0.028,0.03,0.031,0.014,0.0034,-3.5,-0.0014,-0.0058,-0.00029,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.3e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25890000,-0.28,0.015,-0.01,0.96,0.034,0.03,0.033,0.018,0.007,-3.5,-0.0014,-0.0059,-0.0003,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.3e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25990000,-0.28,0.015,-0.01,0.96,0.036,0.024,0.027,0.014,-0.0039,-3.5,-0.0014,-0.0058,-0.00032,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.27,0.032,4.2e-07,3.6e-07,3.8e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26090000,-0.28,0.015,-0.0099,0.96,0.041,0.025,0.026,0.018,-0.0021,-3.5,-0.0014,-0.0058,-0.00031,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26190000,-0.28,0.015,-0.0097,0.96,0.046,0.015,0.021,0.021,-0.018,-3.5,-0.0014,-0.0058,-0.00032,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26290000,-0.28,0.016,-0.0097,0.96,0.046,0.015,0.015,0.024,-0.016,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26390000,-0.28,0.016,-0.0091,0.96,0.043,0.0057,0.019,0.016,-0.03,-3.5,-0.0014,-0.0058,-0.00035,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4.1e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26490000,-0.28,0.016,-0.0089,0.96,0.047,0.0034,0.029,0.021,-0.03,-3.5,-0.0014,-0.0058,-0.00035,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4.1e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26590000,-0.28,0.016,-0.0083,0.96,0.045,-0.0066,0.029,0.02,-0.042,-3.5,-0.0014,-0.0058,-0.00037,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26690000,-0.28,0.015,-0.0082,0.96,0.047,-0.01,0.027,0.024,-0.043,-3.5,-0.0014,-0.0058,-0.00038,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26790000,-0.28,0.015,-0.008,0.96,0.05,-0.017,0.027,0.021,-0.056,-3.5,-0.0014,-0.0058,-0.0004,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.3e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26890000,-0.28,0.015,-0.0074,0.96,0.056,-0.019,0.022,0.027,-0.058,-3.5,-0.0014,-0.0058,-0.00039,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26990000,-0.28,0.015,-0.0068,0.96,0.056,-0.026,0.022,0.019,-0.064,-3.5,-0.0014,-0.0058,-0.0004,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.9e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27090000,-0.28,0.016,-0.0066,0.96,0.059,-0.032,0.025,0.025,-0.067,-3.5,-0.0014,-0.0058,-0.0004,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00034,0.045,0.022,0.024,0.0055,0.32,0.33,0.031,3.9e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27190000,-0.28,0.016,-0.0067,0.96,0.059,-0.036,0.027,0.015,-0.07,-3.5,-0.0014,-0.0058,-0.0004,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27290000,-0.28,0.017,-0.0068,0.96,0.067,-0.04,0.14,0.021,-0.074,-3.5,-0.0014,-0.0058,-0.0004,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.6e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27390000,-0.28,0.019,-0.008,0.96,0.07,-0.033,0.46,0.0052,-0.026,-3.5,-0.0014,-0.0058,-0.00037,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27490000,-0.28,0.021,-0.0092,0.96,0.076,-0.036,0.78,0.013,-0.03,-3.5,-0.0014,-0.0058,-0.00038,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.0004,0.00036,0.045,0.015,0.018,0.0055,0.15,0.15,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27590000,-0.28,0.02,-0.0092,0.96,0.068,-0.038,0.87,0.0067,-0.02,-3.4,-0.0014,-0.0058,-0.00036,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27690000,-0.28,0.017,-0.0083,0.96,0.062,-0.036,0.78,0.013,-0.024,-3.3,-0.0014,-0.0058,-0.00036,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27790000,-0.28,0.015,-0.0071,0.96,0.058,-0.033,0.77,0.011,-0.019,-3.2,-0.0014,-0.0058,-0.00034,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00034,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27890000,-0.28,0.016,-0.0067,0.96,0.065,-0.039,0.81,0.016,-0.023,-3.2,-0.0014,-0.0058,-0.00034,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00034,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.7e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27990000,-0.28,0.016,-0.0071,0.96,0.065,-0.042,0.8,0.019,-0.025,-3.1,-0.0014,-0.0058,-0.00034,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28090000,-0.28,0.016,-0.0074,0.96,0.068,-0.042,0.8,0.026,-0.03,-3,-0.0014,-0.0058,-0.00033,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28190000,-0.28,0.016,-0.0068,0.96,0.065,-0.04,0.81,0.027,-0.032,-2.9,-0.0013,-0.0058,-0.00031,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.015,0.017,0.0054,0.084,0.086,0.031,3.6e-07,3.1e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28290000,-0.28,0.016,-0.0063,0.96,0.069,-0.043,0.81,0.033,-0.037,-2.9,-0.0013,-0.0058,-0.00031,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.015,0.018,0.0054,0.088,0.09,0.031,3.6e-07,3.1e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28390000,-0.28,0.017,-0.0062,0.96,0.071,-0.045,0.81,0.036,-0.037,-2.8,-0.0013,-0.0058,-0.00028,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.015,0.018,0.0054,0.091,0.092,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28490000,-0.28,0.018,-0.0065,0.96,0.073,-0.048,0.81,0.044,-0.042,-2.7,-0.0013,-0.0058,-0.00028,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.019,0.0054,0.095,0.097,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28590000,-0.28,0.017,-0.0065,0.96,0.066,-0.049,0.81,0.044,-0.045,-2.6,-0.0013,-0.0058,-0.00027,0.071,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.1,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28690000,-0.28,0.017,-0.0063,0.96,0.065,-0.049,0.81,0.05,-0.05,-2.6,-0.0013,-0.0058,-0.00027,0.072,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.5e-07,3e-07,3.2e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28790000,-0.28,0.017,-0.0057,0.96,0.063,-0.048,0.81,0.052,-0.048,-2.5,-0.0013,-0.0058,-0.00024,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28890000,-0.28,0.016,-0.0055,0.96,0.066,-0.05,0.81,0.058,-0.054,-2.4,-0.0013,-0.0058,-0.00023,0.072,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28990000,-0.28,0.016,-0.0053,0.96,0.064,-0.047,0.81,0.059,-0.053,-2.3,-0.0013,-0.0058,-0.00022,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,2.9e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29090000,-0.28,0.016,-0.0051,0.96,0.067,-0.049,0.81,0.066,-0.058,-2.3,-0.0013,-0.0058,-0.00022,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,2.9e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29190000,-0.28,0.017,-0.005,0.96,0.068,-0.048,0.8,0.068,-0.057,-2.2,-0.0013,-0.0058,-0.00019,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29290000,-0.28,0.017,-0.0053,0.96,0.072,-0.053,0.81,0.077,-0.061,-2.1,-0.0013,-0.0058,-0.00019,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.4e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29390000,-0.28,0.016,-0.0058,0.96,0.068,-0.05,0.81,0.075,-0.058,-2,-0.0013,-0.0058,-0.00016,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29490000,-0.28,0.016,-0.0058,0.96,0.071,-0.051,0.81,0.082,-0.064,-2,-0.0013,-0.0058,-0.00015,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29590000,-0.28,0.016,-0.0057,0.96,0.068,-0.049,0.81,0.08,-0.062,-1.9,-0.0013,-0.0058,-0.00012,0.071,-0.032,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29690000,-0.28,0.016,-0.0058,0.96,0.073,-0.047,0.81,0.088,-0.067,-1.8,-0.0013,-0.0058,-0.00011,0.07,-0.032,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.022,0.0053,0.15,0.15,0.031,3.3e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29790000,-0.27,0.016,-0.0055,0.96,0.07,-0.041,0.81,0.085,-0.063,-1.7,-0.0013,-0.0058,-7.9e-05,0.07,-0.032,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29890000,-0.27,0.016,-0.005,0.96,0.071,-0.042,0.8,0.093,-0.067,-1.7,-0.0013,-0.0058,-7.2e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.019,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29990000,-0.27,0.016,-0.0051,0.96,0.066,-0.04,0.8,0.087,-0.066,-1.6,-0.0013,-0.0058,-5.5e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.045,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,2.9e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30090000,-0.27,0.016,-0.0053,0.96,0.067,-0.04,0.8,0.095,-0.069,-1.5,-0.0013,-0.0058,-7.2e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30190000,-0.27,0.016,-0.0053,0.96,0.063,-0.033,0.8,0.09,-0.06,-1.5,-0.0013,-0.0058,-5.7e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.17,0.17,0.031,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30290000,-0.27,0.016,-0.0053,0.96,0.063,-0.033,0.8,0.097,-0.063,-1.4,-0.0013,-0.0058,-5.6e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.17,0.18,0.031,3.2e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30390000,-0.27,0.016,-0.0053,0.96,0.06,-0.027,0.8,0.096,-0.057,-1.3,-0.0013,-0.0058,-2.2e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30490000,-0.27,0.016,-0.0053,0.96,0.063,-0.027,0.8,0.1,-0.06,-1.2,-0.0013,-0.0058,-1.5e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30590000,-0.27,0.017,-0.0056,0.96,0.061,-0.025,0.8,0.098,-0.056,-1.2,-0.0012,-0.0058,1.2e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3.1e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30690000,-0.27,0.017,-0.006,0.96,0.059,-0.024,0.8,0.1,-0.059,-1.1,-0.0012,-0.0058,1e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3.1e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.014,0.8,0.096,-0.046,-1,-0.0012,-0.0058,3.9e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.01,0.79,0.1,-0.047,-0.95,-0.0012,-0.0058,2.7e-05,0.071,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -30990000,-0.27,0.016,-0.0053,0.96,0.047,-0.0086,0.79,0.096,-0.046,-0.88,-0.0012,-0.0058,3.2e-05,0.071,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31090000,-0.27,0.016,-0.0055,0.96,0.046,-0.0072,0.79,0.1,-0.046,-0.81,-0.0012,-0.0058,2.4e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31190000,-0.27,0.016,-0.0056,0.96,0.043,-0.0037,0.8,0.094,-0.042,-0.74,-0.0012,-0.0058,5e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31290000,-0.27,0.017,-0.0058,0.96,0.039,-0.0018,0.8,0.097,-0.043,-0.67,-0.0012,-0.0058,5.6e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31390000,-0.27,0.016,-0.0056,0.96,0.035,0.0031,0.8,0.091,-0.039,-0.59,-0.0012,-0.0058,5.5e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31490000,-0.27,0.017,-0.0053,0.96,0.036,0.0065,0.8,0.096,-0.038,-0.52,-0.0012,-0.0058,5.2e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31590000,-0.27,0.017,-0.0052,0.96,0.037,0.0084,0.8,0.093,-0.035,-0.45,-0.0012,-0.0058,6.6e-05,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31690000,-0.27,0.017,-0.0051,0.96,0.04,0.0097,0.8,0.098,-0.034,-0.38,-0.0012,-0.0058,7.6e-05,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31790000,-0.27,0.018,-0.0054,0.96,0.034,0.015,0.8,0.094,-0.025,-0.3,-0.0012,-0.0058,9.7e-05,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.5e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31890000,-0.27,0.018,-0.0051,0.96,0.033,0.017,0.8,0.098,-0.023,-0.23,-0.0012,-0.0058,0.0001,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31990000,-0.27,0.017,-0.0055,0.96,0.029,0.019,0.79,0.095,-0.018,-0.17,-0.0012,-0.0058,0.0001,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.9e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32090000,-0.27,0.017,-0.0059,0.96,0.031,0.023,0.8,0.099,-0.015,-0.095,-0.0012,-0.0058,9.9e-05,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.9e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32190000,-0.27,0.017,-0.0061,0.96,0.027,0.03,0.8,0.094,-0.0067,-0.027,-0.0012,-0.0058,0.0001,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32290000,-0.27,0.017,-0.006,0.96,0.027,0.033,0.8,0.097,-0.0036,0.042,-0.0012,-0.0058,0.00011,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32390000,-0.27,0.017,-0.0061,0.96,0.024,0.035,0.8,0.093,-0.00038,0.12,-0.0012,-0.0058,0.00011,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.093,-0.077,0.092,0.0079,0.12,-0.0012,-0.0058,0.0001,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32590000,-0.27,0.016,-0.0091,0.96,-0.014,0.091,-0.079,0.092,-0.00015,0.1,-0.0012,-0.0058,9.1e-05,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00038,0.00035,0.043,0.021,0.024,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32690000,-0.27,0.015,-0.0091,0.96,-0.01,0.098,-0.081,0.091,0.0093,0.088,-0.0012,-0.0058,9e-05,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32790000,-0.27,0.016,-0.009,0.96,-0.0061,0.096,-0.082,0.092,0.00074,0.073,-0.0012,-0.0058,7.9e-05,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32890000,-0.27,0.016,-0.0089,0.96,-0.0065,0.1,-0.083,0.091,0.01,0.058,-0.0012,-0.0058,8.5e-05,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.3,0.31,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32990000,-0.27,0.016,-0.0088,0.96,-0.0026,0.096,-0.083,0.092,-0.0038,0.044,-0.0012,-0.0058,7e-05,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33090000,-0.27,0.016,-0.0087,0.96,0.0013,0.1,-0.08,0.092,0.0061,0.037,-0.0012,-0.0058,7.1e-05,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33190000,-0.27,0.016,-0.0086,0.96,0.0057,0.097,-0.079,0.093,-0.0098,0.029,-0.0012,-0.0058,4e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33290000,-0.27,0.016,-0.0086,0.96,0.0098,0.1,-0.079,0.094,-0.00037,0.021,-0.0012,-0.0058,5.7e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33390000,-0.27,0.016,-0.0086,0.96,0.014,0.096,-0.077,0.093,-0.0094,0.013,-0.0013,-0.0058,4.5e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33490000,-0.27,0.016,-0.0085,0.96,0.02,0.1,-0.076,0.096,0.0004,0.0031,-0.0013,-0.0058,5.4e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33590000,-0.27,0.016,-0.0084,0.96,0.023,0.097,-0.073,0.095,-0.013,-0.0048,-0.0013,-0.0058,4.6e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -33690000,-0.27,0.016,-0.0084,0.96,0.026,0.1,-0.074,0.096,-0.0038,-0.013,-0.0013,-0.0058,5.1e-05,0.074,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -33790000,-0.27,0.016,-0.0083,0.96,0.029,0.097,-0.068,0.093,-0.018,-0.02,-0.0013,-0.0058,2.9e-05,0.074,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -33890000,-0.27,0.016,-0.0083,0.96,0.033,0.099,-0.068,0.096,-0.0081,-0.026,-0.0013,-0.0058,4.5e-05,0.074,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -33990000,-0.27,0.016,-0.0082,0.96,0.036,0.096,-0.064,0.095,-0.017,-0.03,-0.0013,-0.0058,2.8e-05,0.075,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.098,-0.0072,-0.034,-0.0013,-0.0058,3.2e-05,0.075,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34190000,-0.27,0.016,-0.0081,0.96,0.04,0.097,-0.06,0.093,-0.019,-0.038,-0.0013,-0.0057,2.4e-05,0.075,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.36,0.37,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34290000,-0.27,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.097,-0.0092,-0.044,-0.0013,-0.0057,3.6e-05,0.075,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34390000,-0.27,0.016,-0.0078,0.96,0.043,0.096,-0.054,0.092,-0.021,-0.048,-0.0013,-0.0057,2.4e-05,0.076,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34490000,-0.27,0.016,-0.0079,0.96,0.045,0.1,-0.052,0.096,-0.011,-0.05,-0.0013,-0.0057,3.6e-05,0.076,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34590000,-0.27,0.016,-0.0078,0.96,0.049,0.093,0.74,0.091,-0.026,-0.022,-0.0013,-0.0057,2.3e-05,0.076,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.019,0.021,0.005,0.38,0.38,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34690000,-0.27,0.015,-0.0078,0.96,0.058,0.094,1.7,0.096,-0.016,0.097,-0.0013,-0.0057,2.9e-05,0.076,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34790000,-0.27,0.015,-0.0077,0.96,0.062,0.087,2.7,0.089,-0.03,0.28,-0.0013,-0.0057,1.9e-05,0.077,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.3e-07,2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34890000,-0.27,0.015,-0.0077,0.96,0.071,0.088,3.7,0.096,-0.021,0.57,-0.0013,-0.0057,2.5e-05,0.077,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.3e-07,2e-06,0.028,0.028,0.0001,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +2790000,1,-0.01,-0.013,0.00037,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2990000,1,-0.01,-0.013,0.00031,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-2.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-2.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3190000,1,-0.01,-0.013,0.00056,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.2e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00021,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.4e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.2e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.4e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,2.9e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,2.9e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.0071,0.00018,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,2.5e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3690000,1,-0.0095,-0.013,0.00052,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,2.5e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00017,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3890000,1,-0.0094,-0.013,0.00063,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,2.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4090000,1,-0.0093,-0.012,0.00076,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-4.8e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.9e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-4.8e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1.9e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4290000,1,-0.0095,-0.012,0.00074,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.3e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,1.7e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,1.7e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4490000,1,-0.0094,-0.012,0.00076,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,1.5e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-5.7e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00016,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,1.5e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4690000,1,-0.0094,-0.012,0.00076,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.1e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4790000,1,-0.0093,-0.012,0.00086,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.1e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4890000,1,-0.0092,-0.012,0.0009,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-6.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-6.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5090000,1,-0.0091,-0.011,0.00096,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-6.8e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-6.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.3e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,9.3e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00013,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.4e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5590000,1,-0.0088,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.4e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.6e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.6e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5990000,1,-0.0088,-0.012,0.00086,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6190000,1,-0.0089,-0.011,0.00068,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6290000,1,-0.0089,-0.011,0.00071,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6390000,1,-0.0089,-0.011,0.00072,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6590000,1,-0.009,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6690000,1,-0.0089,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6790000,1,-0.009,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6890000,1,-0.0088,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6990000,-0.29,0.024,-0.0065,0.96,-0.0055,0.0091,-0.037,0.0023,0.0053,-0.055,-0.0016,-0.0056,-8.7e-05,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0012,0.0012,0.072,0.16,0.16,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1 +7090000,-0.28,0.025,-0.0064,0.96,-0.026,-0.00083,-0.037,0.0022,0.0052,-0.056,-0.0015,-0.0055,-8.7e-05,0,0,-0.13,-0.099,-0.021,0.51,0.075,-0.029,-0.065,0,0,0.0012,0.0012,0.058,0.16,0.16,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00099,0.0013,1,1 +7190000,-0.28,0.026,-0.0064,0.96,-0.047,-0.0082,-0.036,0.00063,0.0038,-0.058,-0.0015,-0.0055,-8.6e-05,3.9e-05,-1e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.054,0.17,0.17,0.029,0.16,0.16,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.00094,0.0013,1,1 +7290000,-0.28,0.026,-0.0064,0.96,-0.07,-0.017,-0.033,-0.0034,0.0023,-0.054,-0.0015,-0.0054,-8.5e-05,0.00011,-5e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.053,0.18,0.18,0.028,0.19,0.19,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00093,0.0013,1,1 +7390000,-0.28,0.026,-0.0062,0.96,-0.091,-0.024,-0.031,-0.0098,-8.5e-05,-0.052,-0.0015,-0.0054,-8.4e-05,0.00016,-4e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.052,0.19,0.19,0.027,0.22,0.22,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00092,0.0013,1,1 +7490000,-0.28,0.026,-0.0062,0.96,-0.11,-0.032,-0.025,-0.015,-0.0034,-0.046,-0.0015,-0.0053,-8.1e-05,0.00033,7.2e-07,-0.13,-0.1,-0.022,0.5,0.077,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.2,0.2,0.026,0.26,0.26,0.063,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1 +7590000,-0.28,0.026,-0.0063,0.96,-0.13,-0.041,-0.021,-0.024,-0.0083,-0.04,-0.0015,-0.0052,-8e-05,0.00045,-2.7e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.22,0.21,0.025,0.3,0.3,0.062,6.6e-05,6.5e-05,4.6e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00091,0.0013,1,1 +7690000,-0.28,0.026,-0.0063,0.96,-0.16,-0.051,-0.02,-0.034,-0.015,-0.036,-0.0014,-0.0051,-7.9e-05,0.00056,-6.8e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.23,0.23,0.025,0.34,0.34,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1 +7790000,-0.28,0.026,-0.0062,0.96,-0.18,-0.061,-0.022,-0.041,-0.025,-0.041,-0.0014,-0.005,-7.8e-05,0.00088,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.26,0.25,0.024,0.39,0.39,0.061,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1 +7890000,-0.28,0.026,-0.0062,0.96,-0.2,-0.071,-0.022,-0.057,-0.033,-0.044,-0.0013,-0.0049,-7.7e-05,0.00099,-0.00028,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.28,0.28,0.023,0.45,0.45,0.06,6.4e-05,6.4e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1 +7990000,-0.28,0.026,-0.0061,0.96,-0.22,-0.078,-0.018,-0.08,-0.039,-0.04,-0.0013,-0.0049,-7.7e-05,0.00089,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.3,0.3,0.022,0.51,0.51,0.059,6.3e-05,6.3e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1 +8090000,-0.28,0.026,-0.006,0.96,-0.25,-0.09,-0.019,-0.1,-0.053,-0.043,-0.0013,-0.0049,-8e-05,0.00093,-0.00038,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.33,0.33,0.022,0.57,0.57,0.059,6.2e-05,6.2e-05,4.6e-06,0.04,0.04,0.0014,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1 +8190000,-0.28,0.026,-0.0061,0.96,-0.27,-0.1,-0.014,-0.12,-0.069,-0.036,-0.0012,-0.0048,-8.2e-05,0.00096,-0.0005,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.36,0.36,0.021,0.64,0.64,0.058,6.1e-05,6.1e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1 +8290000,-0.28,0.026,-0.0061,0.96,-0.3,-0.11,-0.013,-0.16,-0.077,-0.036,-0.0012,-0.005,-8.4e-05,0.0007,-0.00042,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.02,0.72,0.72,0.057,6e-05,6e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1 +8390000,-0.28,0.026,-0.0061,0.96,-0.33,-0.12,-0.011,-0.2,-0.089,-0.034,-0.0012,-0.005,-8.5e-05,0.00063,-0.00041,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.43,0.43,0.02,0.81,0.8,0.057,5.9e-05,5.9e-05,4.6e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 +8490000,-0.28,0.026,-0.0059,0.96,-0.35,-0.12,-0.012,-0.23,-0.094,-0.039,-0.0013,-0.005,-8.2e-05,0.00062,-0.00029,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.47,0.46,0.019,0.9,0.9,0.056,5.8e-05,5.7e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 +8590000,-0.28,0.027,-0.0059,0.96,-0.38,-0.14,-0.0073,-0.26,-0.12,-0.034,-0.0012,-0.0049,-8.2e-05,0.00079,-0.00042,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.51,0.51,0.019,1,1,0.055,5.6e-05,5.5e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 +8690000,-0.28,0.027,-0.0059,0.96,-0.4,-0.14,-0.0089,-0.3,-0.13,-0.035,-0.0012,-0.0049,-8.2e-05,0.00071,-0.00035,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.56,0.55,0.018,1.1,1.1,0.055,5.5e-05,5.4e-05,4.6e-06,0.04,0.04,0.001,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1 +8790000,-0.28,0.027,-0.0059,0.96,-0.43,-0.15,-0.0084,-0.35,-0.14,-0.032,-0.0012,-0.005,-8.5e-05,0.00052,-0.0004,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.61,0.6,0.018,1.2,1.2,0.055,5.3e-05,5.2e-05,4.6e-06,0.04,0.04,0.00099,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 +8890000,-0.28,0.027,-0.0059,0.96,-0.46,-0.16,-0.0039,-0.38,-0.16,-0.026,-0.0012,-0.0049,-8.1e-05,0.00064,-0.00031,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.66,0.65,0.017,1.4,1.4,0.054,5.1e-05,5e-05,4.5e-06,0.04,0.04,0.00095,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1 +8990000,-0.28,0.027,-0.0058,0.96,-0.47,-0.17,-0.0028,-0.41,-0.17,-0.029,-0.0013,-0.0047,-7.5e-05,0.001,-0.0003,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.72,0.7,0.017,1.5,1.5,0.054,4.9e-05,4.8e-05,4.5e-06,0.04,0.04,0.00091,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9090000,-0.28,0.027,-0.0056,0.96,-0.5,-0.18,-0.0038,-0.47,-0.17,-0.029,-0.0014,-0.0048,-7.2e-05,0.00081,-2.1e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.77,0.76,0.016,1.7,1.7,0.053,4.7e-05,4.6e-05,4.5e-06,0.04,0.04,0.00087,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9190000,-0.28,0.027,-0.0055,0.96,-0.53,-0.18,-0.0029,-0.52,-0.18,-0.029,-0.0015,-0.0048,-6.9e-05,0.0008,0.00012,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.84,0.82,0.016,1.9,1.9,0.052,4.5e-05,4.4e-05,4.5e-06,0.04,0.04,0.00084,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9290000,-0.28,0.027,-0.0054,0.96,-0.56,-0.19,-0.0011,-0.56,-0.21,-0.026,-0.0014,-0.0047,-6.7e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.9,0.88,0.016,2.1,2.1,0.052,4.3e-05,4.2e-05,4.5e-06,0.04,0.04,0.0008,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9390000,-0.28,0.027,-0.0054,0.96,-0.023,-0.0084,0.0003,-0.57,-0.21,-0.026,-0.0013,-0.0047,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.052,4.2e-05,4e-05,4.5e-06,0.04,0.04,0.00077,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9490000,-0.28,0.027,-0.0053,0.96,-0.049,-0.017,0.0021,-0.58,-0.21,-0.023,-0.0014,-0.0048,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.051,4e-05,3.8e-05,4.5e-06,0.04,0.04,0.00074,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9590000,-0.28,0.027,-0.0056,0.96,-0.076,-0.023,0.0023,-0.58,-0.21,-0.024,-0.0012,-0.0048,-8e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,51,51,0.05,3.8e-05,3.7e-05,4.5e-06,0.04,0.04,0.00072,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9690000,-0.28,0.027,-0.0057,0.96,-0.1,-0.031,0.0054,-0.59,-0.21,-0.023,-0.0012,-0.0048,-8.2e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,52,52,0.05,3.6e-05,3.5e-05,4.5e-06,0.04,0.04,0.00069,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9790000,-0.28,0.027,-0.0059,0.96,-0.13,-0.038,0.0041,-0.59,-0.22,-0.023,-0.001,-0.005,-9.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,35,35,0.05,3.4e-05,3.3e-05,4.5e-06,0.04,0.04,0.00067,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9890000,-0.28,0.027,-0.0058,0.96,-0.16,-0.047,0.0057,-0.61,-0.22,-0.023,-0.0011,-0.0049,-8.9e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,37,37,0.049,3.2e-05,3.1e-05,4.5e-06,0.04,0.04,0.00064,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 +9990000,-0.28,0.027,-0.006,0.96,-0.18,-0.051,0.0065,-0.61,-0.22,-0.025,-0.00096,-0.005,-9.6e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.014,28,28,0.049,3.1e-05,3e-05,4.5e-06,0.04,0.04,0.00062,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10090000,-0.28,0.027,-0.0061,0.96,-0.21,-0.054,0.0078,-0.63,-0.23,-0.023,-0.00084,-0.0051,-0.0001,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.013,30,30,0.049,2.9e-05,2.8e-05,4.5e-06,0.04,0.04,0.0006,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10190000,-0.28,0.027,-0.0064,0.96,-0.23,-0.056,0.0087,-0.64,-0.23,-0.024,-0.00067,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,25,25,0.048,2.8e-05,2.7e-05,4.5e-06,0.04,0.04,0.00058,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10290000,-0.28,0.027,-0.0064,0.96,-0.26,-0.065,0.0079,-0.66,-0.23,-0.023,-0.00072,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,27,27,0.048,2.6e-05,2.5e-05,4.5e-06,0.04,0.04,0.00057,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10390000,-0.28,0.028,-0.0063,0.96,-0.012,-0.0081,-0.0025,-7.9e-05,-0.00028,-0.023,-0.00074,-0.0049,-0.0001,0.001,0.00015,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,2.5e-05,2.4e-05,4.5e-06,0.04,0.04,0.00055,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10490000,-0.28,0.027,-0.0064,0.96,-0.041,-0.014,0.0066,-0.0027,-0.0013,-0.018,-0.00066,-0.005,-0.00011,0.00082,2.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,2.4e-05,2.3e-05,4.5e-06,0.04,0.04,0.00054,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10590000,-0.28,0.027,-0.0063,0.96,-0.052,-0.013,0.012,-0.0032,-0.00096,-0.016,-0.00073,-0.005,-0.0001,0.0014,7.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,2.2e-05,2.1e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10690000,-0.28,0.027,-0.0063,0.96,-0.081,-0.018,0.015,-0.0099,-0.0025,-0.013,-0.0007,-0.005,-0.00011,0.0014,2.4e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 +10790000,-0.28,0.027,-0.0062,0.96,-0.079,-0.021,0.013,-7.5e-06,-0.0018,-0.012,-0.00072,-0.005,-0.00011,0.0035,-0.0011,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.095,0.095,0.17,0.13,0.13,0.062,2e-05,1.9e-05,4.5e-06,0.039,0.039,0.00051,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 +10890000,-0.28,0.027,-0.006,0.96,-0.11,-0.03,0.0093,-0.0092,-0.0044,-0.015,-0.00083,-0.005,-0.0001,0.0036,-0.00084,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 +10990000,-0.28,0.026,-0.006,0.96,-0.096,-0.031,0.016,-0.0034,-0.0023,-0.0093,-0.00085,-0.0052,-0.00011,0.0077,-0.0021,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.083,0.083,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 +11090000,-0.28,0.027,-0.0064,0.96,-0.12,-0.039,0.019,-0.014,-0.0055,-0.0055,-0.00072,-0.0052,-0.00011,0.0078,-0.0025,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.096,0.097,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,4.5e-06,0.039,0.039,0.00049,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 +11190000,-0.28,0.025,-0.0065,0.96,-0.1,-0.034,0.026,-0.0065,-0.0031,0.00085,-0.00071,-0.0053,-0.00011,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.079,0.079,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 +11290000,-0.28,0.025,-0.0066,0.96,-0.13,-0.038,0.025,-0.018,-0.0066,0.00091,-0.00071,-0.0054,-0.00012,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.094,0.094,0.077,0.078,0.078,0.069,1.5e-05,1.4e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 +11390000,-0.28,0.024,-0.0065,0.96,-0.11,-0.032,0.016,-0.01,-0.004,-0.008,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.078,0.078,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.8e-05,0.0013,0.0012,0.00085,0.0013,1,1 +11490000,-0.28,0.024,-0.0064,0.96,-0.13,-0.036,0.021,-0.022,-0.0074,-0.002,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.093,0.093,0.057,0.069,0.069,0.067,1.3e-05,1.3e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1 +11590000,-0.28,0.023,-0.0065,0.96,-0.11,-0.029,0.019,-0.013,-0.0046,-0.0033,-0.00079,-0.0056,-0.00012,0.027,-0.0085,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00098,0.048,0.077,0.077,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 +11690000,-0.28,0.022,-0.0065,0.96,-0.12,-0.035,0.019,-0.024,-0.0078,-0.0047,-0.00081,-0.0057,-0.00012,0.027,-0.0083,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00099,0.048,0.092,0.092,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 +11790000,-0.28,0.021,-0.0063,0.96,-0.097,-0.033,0.02,-0.014,-0.0064,-0.0019,-0.0009,-0.0057,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00091,0.00087,0.048,0.076,0.076,0.037,0.053,0.053,0.063,1.1e-05,1.1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 +11890000,-0.28,0.021,-0.0065,0.96,-0.11,-0.037,0.018,-0.024,-0.0097,-0.0012,-0.00088,-0.0058,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00091,0.00087,0.048,0.089,0.089,0.034,0.06,0.06,0.063,1.1e-05,1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 +11990000,-0.28,0.02,-0.0066,0.96,-0.091,-0.028,0.015,-0.017,-0.0064,-0.005,-0.0009,-0.0059,-0.00012,0.039,-0.011,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.076,0.076,0.03,0.062,0.062,0.061,1e-05,9.8e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1 +12090000,-0.28,0.02,-0.0066,0.96,-0.1,-0.03,0.019,-0.027,-0.0092,0.0011,-0.00086,-0.0058,-0.00012,0.039,-0.012,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.089,0.088,0.027,0.071,0.071,0.06,9.8e-06,9.3e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00081,0.0013,1,1 +12190000,-0.28,0.019,-0.0067,0.96,-0.084,-0.018,0.018,-0.014,-0.0032,0.0029,-0.00082,-0.0059,-0.00012,0.045,-0.013,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.07,0.07,0.024,0.057,0.057,0.058,9.2e-06,8.8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 +12290000,-0.28,0.019,-0.0068,0.96,-0.09,-0.017,0.017,-0.023,-0.0048,0.004,-0.00079,-0.0059,-0.00012,0.045,-0.014,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.081,0.081,0.022,0.065,0.065,0.058,8.9e-06,8.5e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 +12390000,-0.28,0.019,-0.0068,0.96,-0.073,-0.012,0.015,-0.013,-0.0027,-0.002,-0.00078,-0.0059,-0.00012,0.048,-0.015,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00066,0.00063,0.047,0.066,0.065,0.02,0.054,0.054,0.056,8.4e-06,8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 +12490000,-0.28,0.019,-0.0069,0.96,-0.081,-0.013,0.019,-0.021,-0.004,9.6e-05,-0.00076,-0.0059,-0.00013,0.048,-0.016,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00066,0.00064,0.047,0.075,0.075,0.018,0.062,0.062,0.055,8.1e-06,7.7e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 +12590000,-0.28,0.018,-0.0068,0.96,-0.065,-0.011,0.021,-0.01,-0.0039,0.0019,-0.00076,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00058,0.047,0.061,0.061,0.017,0.052,0.052,0.054,7.7e-06,7.4e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 +12690000,-0.28,0.018,-0.0067,0.96,-0.072,-0.0098,0.02,-0.017,-0.0049,0.0035,-0.00075,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00059,0.047,0.069,0.069,0.015,0.059,0.059,0.053,7.4e-06,7e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 +12790000,-0.28,0.018,-0.0065,0.96,-0.056,-0.015,0.022,-0.01,-0.0078,0.0057,-0.00082,-0.0059,-0.00013,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.061,0.061,0.014,0.061,0.061,0.051,7.1e-06,6.7e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 +12890000,-0.28,0.018,-0.0065,0.96,-0.061,-0.016,0.023,-0.016,-0.0096,0.0088,-0.00084,-0.0059,-0.00012,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.069,0.069,0.013,0.07,0.07,0.051,6.8e-06,6.5e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 +12990000,-0.28,0.017,-0.0065,0.96,-0.05,-0.013,0.023,-0.008,-0.0066,0.01,-0.00088,-0.0059,-0.00012,0.056,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.047,0.055,0.055,0.012,0.056,0.056,0.05,6.5e-06,6.2e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 +13090000,-0.28,0.017,-0.0064,0.96,-0.054,-0.015,0.021,-0.013,-0.0083,0.0089,-0.00091,-0.0059,-0.00012,0.056,-0.018,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.046,0.062,0.062,0.011,0.065,0.065,0.049,6.3e-06,5.9e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 +13190000,-0.28,0.017,-0.0063,0.96,-0.046,-0.015,0.02,-0.0097,-0.0091,0.0096,-0.00094,-0.0059,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.055,0.055,0.011,0.066,0.066,0.047,6e-06,5.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 +13290000,-0.28,0.017,-0.0064,0.96,-0.049,-0.015,0.017,-0.015,-0.011,0.009,-0.00092,-0.0058,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.061,0.061,0.01,0.075,0.075,0.047,5.8e-06,5.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 +13390000,-0.28,0.017,-0.0064,0.96,-0.04,-0.011,0.017,-0.0074,-0.007,0.0097,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,5.6e-06,5.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 +13490000,-0.28,0.017,-0.0064,0.96,-0.044,-0.014,0.017,-0.012,-0.0083,0.006,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.054,0.054,0.009,0.068,0.068,0.045,5.4e-06,5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 +13590000,-0.28,0.017,-0.0064,0.96,-0.035,-0.01,0.018,-0.0035,-0.0057,0.0045,-0.00088,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00045,0.046,0.045,0.045,0.0085,0.055,0.055,0.044,5.2e-06,4.9e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 +13690000,-0.28,0.017,-0.0063,0.96,-0.037,-0.0095,0.019,-0.0071,-0.0067,0.0072,-0.00089,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00046,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,5e-06,4.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 +13790000,-0.28,0.016,-0.0064,0.96,-0.029,-0.0071,0.019,0.00061,-0.0035,0.0068,-0.00089,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4.8e-06,4.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 +13890000,-0.28,0.016,-0.0063,0.96,-0.031,-0.0086,0.02,-0.0022,-0.0044,0.0091,-0.00092,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,4.7e-06,4.4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1 +13990000,-0.28,0.016,-0.0062,0.96,-0.03,-0.012,0.018,-0.00073,-0.0048,0.008,-0.00094,-0.0059,-0.00012,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.039,0.039,0.0073,0.05,0.05,0.041,4.5e-06,4.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14090000,-0.28,0.016,-0.0064,0.96,-0.031,-0.0062,0.02,-0.004,-0.0053,0.0046,-0.00087,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,4.4e-06,4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14190000,-0.28,0.016,-0.0064,0.96,-0.025,-0.0047,0.02,-0.00094,-0.004,0.0049,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.036,0.036,0.007,0.049,0.049,0.04,4.2e-06,3.9e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14290000,-0.28,0.016,-0.0064,0.96,-0.028,-0.0051,0.018,-0.0036,-0.0044,0.0092,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.04,0.04,0.0069,0.055,0.055,0.039,4.1e-06,3.8e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14390000,-0.28,0.016,-0.0064,0.96,-0.026,-0.0045,0.019,-0.00096,-0.0049,0.014,-0.00083,-0.0059,-0.00012,0.064,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,4e-06,3.6e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14490000,-0.28,0.016,-0.0066,0.96,-0.026,-0.0039,0.023,-0.0037,-0.005,0.016,-0.00079,-0.0059,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00042,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.8e-06,3.5e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14590000,-0.28,0.016,-0.0067,0.96,-0.028,-0.0054,0.021,-0.0038,-0.0053,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.7e-06,3.4e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14690000,-0.28,0.016,-0.0067,0.96,-0.029,-0.0058,0.021,-0.0067,-0.006,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.6e-06,3.3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 +14790000,-0.28,0.016,-0.0068,0.96,-0.03,-0.003,0.021,-0.0052,-0.0014,0.015,-0.0008,-0.0058,-0.00012,0.065,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.031,0.031,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +14890000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0012,0.026,-0.0086,-0.002,0.016,-0.00081,-0.0057,-0.00012,0.066,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.00041,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +14990000,-0.28,0.016,-0.0067,0.96,-0.031,-0.003,0.028,-0.0069,-0.003,0.018,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15090000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0042,0.032,-0.01,-0.0033,0.021,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.032,0.032,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15190000,-0.28,0.016,-0.0068,0.96,-0.03,-0.0022,0.033,-0.008,-0.0026,0.023,-0.0008,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15290000,-0.28,0.016,-0.0069,0.96,-0.034,-0.0024,0.032,-0.012,-0.0032,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15390000,-0.28,0.016,-0.0069,0.96,-0.032,-0.0042,0.032,-0.0092,-0.0026,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.027,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15490000,-0.28,0.016,-0.007,0.96,-0.034,-0.0018,0.032,-0.012,-0.003,0.021,-0.00082,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.029,0.0065,0.05,0.05,0.034,2.8e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15590000,-0.28,0.016,-0.0069,0.96,-0.03,-0.006,0.032,-0.0077,-0.0061,0.02,-0.00085,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15690000,-0.28,0.016,-0.0068,0.96,-0.032,-0.0041,0.032,-0.01,-0.0067,0.021,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15790000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0028,0.032,-0.0077,-0.0057,0.023,-0.00092,-0.0057,-0.00012,0.068,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.024,0.024,0.0066,0.043,0.044,0.033,2.6e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15890000,-0.28,0.016,-0.0069,0.96,-0.029,-0.0041,0.033,-0.011,-0.0058,0.023,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 +15990000,-0.28,0.016,-0.0068,0.96,-0.027,-0.0035,0.03,-0.0091,-0.0049,0.022,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16090000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0023,0.028,-0.012,-0.005,0.022,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.025,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16190000,-0.28,0.016,-0.0068,0.96,-0.026,-0.002,0.027,-0.011,-0.0041,0.019,-0.00086,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16290000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0011,0.027,-0.014,-0.0043,0.021,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.024,0.024,0.007,0.048,0.048,0.033,2.3e-06,2e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16390000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0015,0.027,-0.011,-0.0041,0.021,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16490000,-0.28,0.016,-0.0069,0.96,-0.033,-0.00051,0.029,-0.014,-0.0041,0.025,-0.00086,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.023,0.023,0.0072,0.047,0.047,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16590000,-0.28,0.016,-0.0069,0.96,-0.036,1.4e-05,0.033,-0.012,-0.0035,0.025,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.021,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16690000,-0.28,0.016,-0.0069,0.96,-0.039,0.0036,0.033,-0.016,-0.0035,0.026,-0.00089,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16790000,-0.28,0.016,-0.0068,0.96,-0.039,0.0034,0.032,-0.013,-0.0031,0.026,-0.00091,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0073,0.042,0.042,0.033,2e-06,1.7e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16890000,-0.28,0.016,-0.0067,0.96,-0.039,0.0029,0.033,-0.017,-0.0032,0.025,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +16990000,-0.28,0.016,-0.0067,0.96,-0.036,0.0033,0.033,-0.015,-0.0034,0.024,-0.00094,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.049,0.049,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +17090000,-0.28,0.016,-0.0068,0.96,-0.041,0.0053,0.033,-0.019,-0.0029,0.023,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.9e-06,1.6e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +17190000,-0.28,0.016,-0.0069,0.96,-0.039,0.0071,0.034,-0.018,-0.0046,0.026,-0.00093,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0076,0.057,0.057,0.033,1.8e-06,1.6e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +17290000,-0.28,0.016,-0.0069,0.96,-0.042,0.0077,0.034,-0.022,-0.0035,0.026,-0.00092,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.023,0.024,0.0077,0.062,0.063,0.033,1.8e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +17390000,-0.28,0.016,-0.0069,0.96,-0.032,0.013,0.033,-0.014,-0.002,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +17490000,-0.28,0.016,-0.0069,0.96,-0.032,0.014,0.033,-0.017,-0.00051,0.028,-0.00094,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.022,0.0078,0.058,0.058,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 +17590000,-0.28,0.016,-0.0069,0.96,-0.032,0.012,0.032,-0.016,-0.00075,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 +17690000,-0.28,0.016,-0.007,0.96,-0.033,0.012,0.033,-0.019,0.0003,0.028,-0.00096,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.02,0.02,0.0078,0.054,0.054,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 +17790000,-0.28,0.016,-0.007,0.96,-0.033,0.013,0.033,-0.018,0.0011,0.033,-0.00097,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 +17890000,-0.28,0.016,-0.0069,0.96,-0.037,0.014,0.033,-0.021,0.0022,0.038,-0.00098,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.021,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 +17990000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.017,0.0047,0.038,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 +18090000,-0.28,0.016,-0.007,0.96,-0.037,0.016,0.032,-0.021,0.0061,0.037,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.008,0.057,0.057,0.034,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 +18190000,-0.28,0.016,-0.007,0.96,-0.034,0.013,0.033,-0.016,0.004,0.035,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18290000,-0.28,0.016,-0.007,0.96,-0.037,0.013,0.031,-0.02,0.005,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.019,0.008,0.053,0.054,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18390000,-0.28,0.016,-0.0069,0.96,-0.033,0.013,0.031,-0.014,0.0042,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0079,0.046,0.047,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18490000,-0.28,0.016,-0.0069,0.96,-0.037,0.012,0.03,-0.018,0.005,0.034,-0.001,-0.0057,-0.00013,0.072,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.018,0.008,0.051,0.051,0.034,1.3e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18590000,-0.28,0.016,-0.0068,0.96,-0.035,0.012,0.03,-0.015,0.0045,0.037,-0.001,-0.0057,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18690000,-0.28,0.016,-0.0067,0.96,-0.035,0.011,0.028,-0.017,0.0053,0.035,-0.0011,-0.0058,-0.00013,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18790000,-0.28,0.015,-0.0067,0.96,-0.031,0.011,0.028,-0.014,0.0046,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18890000,-0.28,0.015,-0.0067,0.96,-0.032,0.011,0.026,-0.017,0.0057,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 +18990000,-0.28,0.015,-0.0066,0.96,-0.029,0.011,0.027,-0.015,0.005,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.015,0.0079,0.042,0.042,0.034,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19090000,-0.28,0.015,-0.0067,0.96,-0.029,0.012,0.027,-0.017,0.0056,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.016,0.0079,0.045,0.046,0.035,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19190000,-0.28,0.016,-0.0066,0.96,-0.026,0.013,0.027,-0.015,0.0056,0.028,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.8e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19290000,-0.28,0.016,-0.0066,0.96,-0.027,0.013,0.027,-0.018,0.0067,0.027,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,9.7e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19390000,-0.28,0.015,-0.0067,0.96,-0.025,0.011,0.028,-0.016,0.0067,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,9.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19490000,-0.28,0.015,-0.0068,0.96,-0.028,0.012,0.028,-0.019,0.008,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1.1e-06,9.3e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19590000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.03,-0.016,0.0063,0.026,-0.0011,-0.0058,-0.00016,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0077,0.039,0.04,0.035,1.1e-06,9e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19690000,-0.28,0.016,-0.0067,0.96,-0.024,0.011,0.028,-0.019,0.007,0.026,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.9e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19790000,-0.28,0.015,-0.0068,0.96,-0.021,0.011,0.026,-0.019,0.0075,0.022,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,1e-06,8.7e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19890000,-0.28,0.016,-0.0068,0.96,-0.023,0.011,0.027,-0.021,0.0087,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,1e-06,8.6e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 +19990000,-0.28,0.016,-0.0068,0.96,-0.02,0.012,0.024,-0.016,0.0081,0.017,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.7e-07,8.3e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 +20090000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.024,-0.018,0.0093,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0076,0.047,0.048,0.035,9.7e-07,8.2e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 +20190000,-0.28,0.016,-0.0068,0.96,-0.023,0.013,0.025,-0.019,0.0097,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0075,0.05,0.05,0.035,9.4e-07,8e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 +20290000,-0.28,0.016,-0.0068,0.96,-0.021,0.015,0.025,-0.022,0.011,0.021,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.3e-07,7.9e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 +20390000,-0.28,0.016,-0.0067,0.96,-0.019,0.013,0.025,-0.022,0.01,0.022,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,9.1e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 +20490000,-0.28,0.016,-0.0067,0.96,-0.017,0.015,0.025,-0.024,0.011,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,9e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 +20590000,-0.28,0.016,-0.0066,0.96,-0.017,0.014,0.025,-0.024,0.01,0.018,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0074,0.064,0.065,0.035,8.8e-07,7.5e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 +20690000,-0.28,0.016,-0.0066,0.96,-0.016,0.014,0.026,-0.025,0.012,0.019,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.7e-07,7.4e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 +20790000,-0.28,0.016,-0.006,0.96,-0.01,0.01,0.01,-0.019,0.0088,0.017,-0.0012,-0.0058,-0.00018,0.072,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.017,0.0073,0.057,0.057,0.035,8.4e-07,7.1e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 +20890000,-0.28,0.011,0.0027,0.96,-0.0058,-5.9e-05,-0.11,-0.021,0.0092,0.011,-0.0012,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00034,0.046,0.017,0.018,0.0073,0.061,0.062,0.035,8.3e-07,7.1e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 +20990000,-0.28,0.0071,0.0057,0.96,0.0086,-0.017,-0.25,-0.017,0.007,-0.004,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.016,0.0072,0.052,0.052,0.034,8e-07,6.9e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 +21090000,-0.28,0.0076,0.0042,0.96,0.022,-0.029,-0.37,-0.016,0.005,-0.035,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.017,0.0072,0.056,0.057,0.035,8e-07,6.8e-07,4.2e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 +21190000,-0.28,0.0095,0.0015,0.96,0.028,-0.035,-0.49,-0.013,0.0038,-0.071,-0.0011,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.7e-07,6.6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21290000,-0.28,0.011,-0.00054,0.96,0.026,-0.037,-0.62,-0.011,0.0011,-0.13,-0.0011,-0.0058,-0.00019,0.072,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.7e-07,6.5e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21390000,-0.28,0.012,-0.002,0.96,0.019,-0.029,-0.75,-0.013,0.0046,-0.19,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.016,0.017,0.007,0.054,0.055,0.035,7.5e-07,6.4e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21490000,-0.28,0.012,-0.0028,0.96,0.013,-0.027,-0.88,-0.011,0.0015,-0.28,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.017,0.018,0.007,0.059,0.06,0.035,7.4e-07,6.3e-07,4.1e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21590000,-0.28,0.012,-0.0034,0.96,0.0009,-0.021,-1,-0.015,0.0065,-0.37,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.017,0.018,0.0069,0.061,0.063,0.034,7.3e-07,6.2e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21690000,-0.28,0.012,-0.0037,0.96,-0.0046,-0.017,-1.1,-0.015,0.004,-0.48,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0069,0.066,0.068,0.035,7.2e-07,6.1e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21790000,-0.28,0.012,-0.0041,0.96,-0.011,-0.0087,-1.3,-0.017,0.01,-0.6,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.019,0.0069,0.069,0.07,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21890000,-0.28,0.013,-0.0044,0.96,-0.017,-0.0041,-1.4,-0.018,0.01,-0.74,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +21990000,-0.28,0.013,-0.0052,0.96,-0.022,0.0043,-1.4,-0.024,0.018,-0.88,-0.0011,-0.0058,-8.8e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0068,0.077,0.079,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +22090000,-0.28,0.014,-0.0058,0.96,-0.025,0.0075,-1.4,-0.025,0.018,-1,-0.0011,-0.0058,-8.2e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0068,0.083,0.085,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +22190000,-0.28,0.014,-0.0063,0.96,-0.032,0.014,-1.4,-0.03,0.025,-1.2,-0.0011,-0.0058,-5.9e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22290000,-0.28,0.014,-0.007,0.96,-0.04,0.019,-1.4,-0.034,0.027,-1.3,-0.0011,-0.0058,-6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22390000,-0.28,0.015,-0.0073,0.96,-0.047,0.026,-1.4,-0.04,0.031,-1.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.094,0.096,0.034,6.4e-07,5.5e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22490000,-0.28,0.015,-0.0074,0.96,-0.053,0.032,-1.4,-0.045,0.034,-1.6,-0.0011,-0.0058,-6.4e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0066,0.1,0.1,0.034,6.4e-07,5.4e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22590000,-0.28,0.016,-0.0073,0.96,-0.058,0.038,-1.4,-0.046,0.038,-1.7,-0.0011,-0.0058,-5.7e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22690000,-0.28,0.016,-0.0072,0.96,-0.062,0.042,-1.4,-0.053,0.042,-1.9,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22790000,-0.28,0.016,-0.0071,0.96,-0.069,0.047,-1.4,-0.059,0.045,-2,-0.0011,-0.0058,-6.6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22890000,-0.28,0.017,-0.0072,0.96,-0.074,0.051,-1.4,-0.065,0.048,-2.2,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22990000,-0.28,0.017,-0.007,0.96,-0.076,0.051,-1.4,-0.068,0.047,-2.3,-0.0011,-0.0058,-6.3e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23090000,-0.28,0.017,-0.007,0.96,-0.082,0.055,-1.4,-0.075,0.053,-2.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0064,0.13,0.13,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23190000,-0.28,0.017,-0.0069,0.96,-0.084,0.05,-1.4,-0.074,0.049,-2.6,-0.0011,-0.0058,-8.4e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.9e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23290000,-0.28,0.018,-0.0073,0.96,-0.09,0.054,-1.4,-0.083,0.053,-2.7,-0.0011,-0.0058,-8e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.14,0.14,0.034,5.6e-07,4.8e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23390000,-0.28,0.018,-0.0073,0.96,-0.089,0.056,-1.4,-0.077,0.055,-2.9,-0.0011,-0.0058,-9.8e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23490000,-0.28,0.018,-0.0073,0.96,-0.096,0.057,-1.4,-0.088,0.059,-3,-0.0011,-0.0058,-9e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.051,-1.4,-0.083,0.049,-3.2,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23690000,-0.28,0.019,-0.008,0.96,-0.093,0.053,-1.3,-0.092,0.053,-3.3,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23790000,-0.28,0.021,-0.0095,0.96,-0.077,0.049,-0.95,-0.082,0.049,-3.4,-0.0012,-0.0058,-0.00012,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00039,0.00036,0.045,0.021,0.022,0.0061,0.16,0.16,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23890000,-0.28,0.026,-0.012,0.96,-0.071,0.05,-0.52,-0.089,0.053,-3.5,-0.0012,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00042,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23990000,-0.28,0.028,-0.014,0.96,-0.061,0.048,-0.13,-0.077,0.048,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +24090000,-0.28,0.027,-0.014,0.96,-0.067,0.055,0.1,-0.082,0.053,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +24190000,-0.28,0.023,-0.011,0.96,-0.071,0.052,0.089,-0.069,0.04,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +24290000,-0.28,0.02,-0.0093,0.96,-0.076,0.055,0.068,-0.076,0.045,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.048,0.084,-0.058,0.036,-3.6,-0.0013,-0.0058,-0.00016,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.02,0.022,0.006,0.19,0.19,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +24490000,-0.28,0.019,-0.0087,0.96,-0.054,0.044,0.081,-0.063,0.039,-3.6,-0.0013,-0.0058,-0.00014,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.021,0.023,0.006,0.2,0.2,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.042,0.077,-0.045,0.033,-3.6,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.022,0.0059,0.2,0.2,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24690000,-0.28,0.019,-0.0099,0.96,-0.041,0.041,0.076,-0.049,0.037,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24790000,-0.28,0.018,-0.01,0.96,-0.034,0.04,0.068,-0.037,0.029,-3.5,-0.0013,-0.0058,-0.00017,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0059,0.21,0.21,0.032,4.7e-07,4.1e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24890000,-0.28,0.017,-0.0099,0.96,-0.033,0.042,0.058,-0.04,0.032,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0059,0.22,0.22,0.032,4.7e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24990000,-0.28,0.017,-0.0097,0.96,-0.021,0.043,0.05,-0.026,0.027,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25090000,-0.28,0.017,-0.01,0.96,-0.016,0.043,0.048,-0.027,0.031,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.23,0.23,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25190000,-0.28,0.017,-0.01,0.96,-0.006,0.038,0.048,-0.011,0.021,-3.5,-0.0013,-0.0059,-0.0002,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25290000,-0.28,0.016,-0.01,0.96,-0.0013,0.041,0.043,-0.012,0.026,-3.5,-0.0013,-0.0059,-0.00021,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25390000,-0.28,0.016,-0.011,0.96,0.0076,0.039,0.041,-0.0022,0.02,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25490000,-0.28,0.016,-0.011,0.96,0.012,0.04,0.041,-0.0021,0.024,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25590000,-0.28,0.016,-0.011,0.96,0.017,0.035,0.042,0.0049,0.0094,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25690000,-0.28,0.015,-0.01,0.96,0.018,0.034,0.031,0.0066,0.013,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25790000,-0.28,0.015,-0.01,0.96,0.028,0.029,0.031,0.014,0.0031,-3.5,-0.0014,-0.0058,-0.00025,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.2e-07,3.7e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25890000,-0.28,0.015,-0.01,0.96,0.034,0.029,0.033,0.017,0.0067,-3.5,-0.0014,-0.0058,-0.00026,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.2e-07,3.7e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +25990000,-0.28,0.015,-0.01,0.96,0.036,0.024,0.027,0.013,-0.004,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.27,0.27,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26090000,-0.28,0.015,-0.0099,0.96,0.041,0.024,0.025,0.017,-0.0023,-3.5,-0.0014,-0.0058,-0.00027,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26190000,-0.28,0.015,-0.0098,0.96,0.046,0.015,0.021,0.02,-0.018,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26290000,-0.28,0.016,-0.0098,0.96,0.046,0.014,0.015,0.024,-0.016,-3.5,-0.0014,-0.0058,-0.00029,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0051,0.019,0.015,-0.03,-3.5,-0.0014,-0.0058,-0.0003,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4e-07,3.5e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26490000,-0.28,0.016,-0.009,0.96,0.046,0.0028,0.028,0.02,-0.03,-3.5,-0.0014,-0.0058,-0.00031,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.0071,0.029,0.019,-0.042,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26690000,-0.28,0.016,-0.0083,0.96,0.047,-0.011,0.027,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26790000,-0.27,0.015,-0.0081,0.96,0.049,-0.017,0.027,0.02,-0.055,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26890000,-0.27,0.015,-0.0074,0.96,0.055,-0.02,0.022,0.026,-0.057,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +26990000,-0.27,0.016,-0.0069,0.96,0.056,-0.026,0.021,0.018,-0.064,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27090000,-0.27,0.016,-0.0067,0.96,0.058,-0.033,0.025,0.024,-0.067,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.33,0.33,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27190000,-0.27,0.016,-0.0068,0.96,0.058,-0.036,0.027,0.014,-0.069,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27290000,-0.27,0.017,-0.0069,0.96,0.066,-0.041,0.14,0.02,-0.073,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27390000,-0.27,0.019,-0.0081,0.96,0.07,-0.034,0.46,0.0048,-0.026,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27490000,-0.27,0.021,-0.0093,0.96,0.076,-0.037,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.016,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27590000,-0.27,0.02,-0.0093,0.96,0.067,-0.039,0.87,0.0064,-0.02,-3.4,-0.0014,-0.0058,-0.00032,0.074,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27690000,-0.27,0.017,-0.0084,0.96,0.061,-0.036,0.78,0.013,-0.024,-3.3,-0.0014,-0.0058,-0.00031,0.075,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +27790000,-0.27,0.016,-0.0072,0.96,0.058,-0.034,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27890000,-0.27,0.016,-0.0068,0.96,0.064,-0.04,0.81,0.016,-0.023,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27990000,-0.27,0.016,-0.0072,0.96,0.064,-0.042,0.8,0.019,-0.026,-3.1,-0.0014,-0.0058,-0.00029,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28090000,-0.27,0.016,-0.0075,0.96,0.068,-0.043,0.8,0.026,-0.03,-3,-0.0014,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28190000,-0.27,0.016,-0.0069,0.96,0.065,-0.041,0.81,0.027,-0.032,-2.9,-0.0013,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.085,0.085,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28290000,-0.27,0.017,-0.0064,0.96,0.069,-0.044,0.81,0.033,-0.037,-2.9,-0.0013,-0.0058,-0.00027,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.016,0.018,0.0054,0.089,0.09,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28390000,-0.27,0.017,-0.0063,0.96,0.07,-0.046,0.81,0.035,-0.038,-2.8,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0054,0.091,0.092,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28490000,-0.27,0.018,-0.0066,0.96,0.073,-0.049,0.81,0.043,-0.042,-2.7,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.095,0.097,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28590000,-0.27,0.018,-0.0066,0.96,0.065,-0.049,0.81,0.043,-0.045,-2.6,-0.0013,-0.0058,-0.00023,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.099,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28690000,-0.27,0.017,-0.0064,0.96,0.064,-0.05,0.81,0.05,-0.05,-2.6,-0.0013,-0.0058,-0.00024,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28790000,-0.27,0.017,-0.0058,0.96,0.062,-0.049,0.81,0.051,-0.049,-2.5,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28890000,-0.27,0.016,-0.0056,0.96,0.065,-0.051,0.81,0.057,-0.054,-2.4,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28990000,-0.27,0.016,-0.0054,0.96,0.063,-0.048,0.81,0.058,-0.054,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29090000,-0.27,0.017,-0.0052,0.96,0.067,-0.05,0.81,0.066,-0.059,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29190000,-0.27,0.017,-0.0051,0.96,0.067,-0.049,0.8,0.067,-0.058,-2.2,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29290000,-0.27,0.017,-0.0054,0.96,0.071,-0.054,0.81,0.076,-0.062,-2.1,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29390000,-0.27,0.016,-0.0059,0.96,0.067,-0.051,0.81,0.074,-0.059,-2,-0.0013,-0.0058,-0.00014,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29490000,-0.27,0.016,-0.0059,0.96,0.07,-0.052,0.81,0.081,-0.065,-2,-0.0013,-0.0058,-0.00013,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.05,0.81,0.08,-0.063,-1.9,-0.0013,-0.0058,-0.00011,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.018,0.021,0.0053,0.14,0.14,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.049,0.81,0.087,-0.068,-1.8,-0.0013,-0.0058,-9.8e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.019,0.022,0.0053,0.15,0.15,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.042,0.8,0.084,-0.064,-1.7,-0.0013,-0.0058,-6.9e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29890000,-0.27,0.016,-0.005,0.96,0.07,-0.044,0.8,0.092,-0.069,-1.7,-0.0013,-0.0058,-6.2e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.041,0.8,0.087,-0.068,-1.6,-0.0013,-0.0058,-4.8e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30090000,-0.27,0.017,-0.0053,0.96,0.067,-0.041,0.8,0.094,-0.07,-1.5,-0.0013,-0.0058,-6.2e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.089,-0.061,-1.5,-0.0013,-0.0058,-5e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.17,0.17,0.031,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.096,-0.065,-1.4,-0.0013,-0.0058,-4.9e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.029,0.8,0.095,-0.059,-1.3,-0.0013,-0.0058,-1.9e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.18,0.18,0.03,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.028,0.8,0.1,-0.062,-1.2,-0.0013,-0.0058,-1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30590000,-0.27,0.017,-0.0056,0.96,0.061,-0.026,0.8,0.097,-0.058,-1.2,-0.0013,-0.0058,1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30690000,-0.27,0.017,-0.006,0.96,0.058,-0.026,0.8,0.1,-0.061,-1.1,-0.0013,-0.0058,1.1e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00035,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.016,0.8,0.095,-0.049,-1,-0.0012,-0.0058,3.6e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.012,0.79,0.099,-0.05,-0.95,-0.0012,-0.0058,2.6e-05,0.072,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30990000,-0.27,0.016,-0.0054,0.96,0.046,-0.01,0.79,0.095,-0.048,-0.88,-0.0012,-0.0058,3e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0087,0.79,0.099,-0.049,-0.81,-0.0012,-0.0058,2.2e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31190000,-0.27,0.017,-0.0057,0.96,0.042,-0.0051,0.8,0.093,-0.044,-0.74,-0.0012,-0.0058,4.6e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0033,0.8,0.096,-0.045,-0.67,-0.0012,-0.0058,5.2e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0017,0.8,0.09,-0.042,-0.59,-0.0012,-0.0058,5.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0051,0.8,0.095,-0.041,-0.52,-0.0012,-0.0058,4.8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +31590000,-0.27,0.017,-0.0052,0.96,0.036,0.007,0.8,0.092,-0.037,-0.45,-0.0012,-0.0058,6.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +31690000,-0.27,0.017,-0.0052,0.96,0.04,0.0082,0.8,0.097,-0.037,-0.38,-0.0012,-0.0058,7.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +31790000,-0.27,0.018,-0.0054,0.96,0.034,0.014,0.8,0.093,-0.027,-0.3,-0.0012,-0.0058,9e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +31890000,-0.27,0.018,-0.0052,0.96,0.032,0.016,0.8,0.097,-0.025,-0.23,-0.0012,-0.0058,9.4e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +31990000,-0.27,0.017,-0.0055,0.96,0.029,0.017,0.79,0.094,-0.02,-0.17,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32090000,-0.27,0.017,-0.0059,0.96,0.03,0.021,0.8,0.098,-0.018,-0.096,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32190000,-0.27,0.017,-0.0061,0.96,0.027,0.029,0.8,0.093,-0.0092,-0.027,-0.0012,-0.0058,9.7e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32290000,-0.27,0.017,-0.006,0.96,0.027,0.031,0.8,0.096,-0.0063,0.042,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32390000,-0.27,0.017,-0.0062,0.96,0.023,0.033,0.79,0.092,-0.0029,0.12,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.092,-0.077,0.091,0.0054,0.12,-0.0012,-0.0058,9.6e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32590000,-0.27,0.016,-0.0092,0.96,-0.014,0.09,-0.08,0.091,-0.0025,0.1,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.021,0.023,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32690000,-0.27,0.016,-0.0092,0.96,-0.01,0.097,-0.081,0.09,0.0069,0.088,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32790000,-0.27,0.016,-0.009,0.96,-0.0062,0.095,-0.082,0.092,-0.0016,0.073,-0.0012,-0.0058,7.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32890000,-0.27,0.016,-0.009,0.96,-0.0066,0.1,-0.084,0.09,0.0078,0.058,-0.0012,-0.0058,8.1e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32990000,-0.27,0.016,-0.0088,0.96,-0.0026,0.095,-0.083,0.091,-0.006,0.044,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33090000,-0.27,0.016,-0.0088,0.96,0.0013,0.1,-0.08,0.091,0.0037,0.037,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33190000,-0.27,0.016,-0.0086,0.96,0.0057,0.096,-0.079,0.092,-0.012,0.029,-0.0012,-0.0058,4e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33290000,-0.27,0.016,-0.0087,0.96,0.0098,0.099,-0.079,0.093,-0.0027,0.021,-0.0013,-0.0058,5.7e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33390000,-0.27,0.016,-0.0086,0.96,0.014,0.095,-0.077,0.092,-0.012,0.012,-0.0013,-0.0058,4.6e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33490000,-0.27,0.016,-0.0086,0.96,0.02,0.099,-0.076,0.095,-0.0019,0.0028,-0.0013,-0.0058,5.4e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33590000,-0.27,0.016,-0.0084,0.96,0.023,0.096,-0.073,0.094,-0.015,-0.0051,-0.0013,-0.0058,4.8e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33690000,-0.27,0.016,-0.0084,0.96,0.026,0.099,-0.074,0.095,-0.0061,-0.013,-0.0013,-0.0058,5.3e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33790000,-0.27,0.016,-0.0083,0.96,0.029,0.096,-0.068,0.092,-0.02,-0.02,-0.0013,-0.0058,3.3e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33890000,-0.27,0.016,-0.0083,0.96,0.033,0.097,-0.068,0.095,-0.01,-0.027,-0.0013,-0.0058,4.8e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33990000,-0.27,0.016,-0.0082,0.96,0.036,0.095,-0.064,0.094,-0.019,-0.03,-0.0013,-0.0057,3.3e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0094,-0.035,-0.0013,-0.0057,3.6e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34190000,-0.27,0.016,-0.0081,0.96,0.04,0.096,-0.06,0.092,-0.021,-0.038,-0.0013,-0.0057,3e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.022,0.005,0.36,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34290000,-0.26,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.012,-0.044,-0.0013,-0.0057,4e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34390000,-0.26,0.016,-0.0078,0.96,0.043,0.095,-0.054,0.091,-0.023,-0.048,-0.0013,-0.0057,3e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34490000,-0.26,0.016,-0.0079,0.96,0.046,0.099,-0.052,0.095,-0.014,-0.051,-0.0013,-0.0057,4.2e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34590000,-0.26,0.016,-0.0078,0.96,0.049,0.092,0.74,0.09,-0.028,-0.022,-0.0013,-0.0057,3e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34690000,-0.26,0.015,-0.0078,0.96,0.058,0.092,1.7,0.095,-0.019,0.097,-0.0013,-0.0057,3.5e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34790000,-0.26,0.015,-0.0077,0.96,0.063,0.086,2.7,0.088,-0.032,0.28,-0.0013,-0.0057,2.6e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34890000,-0.26,0.015,-0.0077,0.96,0.071,0.086,3.7,0.094,-0.023,0.57,-0.0013,-0.0057,3.2e-05,0.079,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 From 62b8db153bf73ade8c63ff7a8d7e4324abb1712c Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 20 Mar 2024 13:43:47 +0100 Subject: [PATCH 018/652] mpc: fix PositionControl unit test The unit test assumes the position controller is in "decoupled" mode --- src/modules/mc_pos_control/PositionControl/PositionControl.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mc_pos_control/PositionControl/PositionControl.hpp b/src/modules/mc_pos_control/PositionControl/PositionControl.hpp index 7575409bbc78..85af876cd136 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControl.hpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControl.hpp @@ -216,7 +216,7 @@ class PositionControl float _lim_tilt{}; ///< Maximum tilt from level the output attitude is allowed to have float _hover_thrust{}; ///< Thrust [HOVER_THRUST_MIN, HOVER_THRUST_MAX] with which the vehicle hovers not accelerating down or up with level orientation - bool _decouple_horizontal_and_vertical_acceleration{false}; ///< Ignore vertical acceleration setpoint to remove its effect on the tilt setpoint + bool _decouple_horizontal_and_vertical_acceleration{true}; ///< Ignore vertical acceleration setpoint to remove its effect on the tilt setpoint // States matrix::Vector3f _pos; /**< current position */ From 35532609c9f8b337372c57d12f12e24aa5634738 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 20 Mar 2024 11:10:37 -0400 Subject: [PATCH 019/652] mathlib: utilities refactor float to function template (for optional double precision usage) Co-authored-by: Mathieu Bresciani --- src/lib/mathlib/math/Utilities.hpp | 99 +++++++++++++++++------------- 1 file changed, 58 insertions(+), 41 deletions(-) diff --git a/src/lib/mathlib/math/Utilities.hpp b/src/lib/mathlib/math/Utilities.hpp index 9b8f7047c422..890346b9733c 100644 --- a/src/lib/mathlib/math/Utilities.hpp +++ b/src/lib/mathlib/math/Utilities.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-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 @@ -51,17 +51,18 @@ static constexpr float sq(float var) { return var * var; } // rot312(1) - Second rotation is a RH rotation about the X axis (rad) // rot312(2) - Third rotation is a RH rotation about the Y axis (rad) // See http://www.atacolorado.com/eulersequences.doc -inline matrix::Dcmf taitBryan312ToRotMat(const matrix::Vector3f &rot312) +template +inline matrix::Dcm taitBryan312ToRotMat(const matrix::Vector3 &rot312) { // Calculate the frame2 to frame 1 rotation matrix from a 312 Tait-Bryan rotation sequence - const float c2 = cosf(rot312(2)); // third rotation is pitch - const float s2 = sinf(rot312(2)); - const float s1 = sinf(rot312(1)); // second rotation is roll - const float c1 = cosf(rot312(1)); - const float s0 = sinf(rot312(0)); // first rotation is yaw - const float c0 = cosf(rot312(0)); - - matrix::Dcmf R; + const T c2 = cosf(rot312(2)); // third rotation is pitch + const T s2 = sinf(rot312(2)); + const T s1 = sinf(rot312(1)); // second rotation is roll + const T c1 = cosf(rot312(1)); + const T s0 = sinf(rot312(0)); // first rotation is yaw + const T c0 = cosf(rot312(0)); + + matrix::Dcm R; R(0, 0) = c0 * c2 - s0 * s1 * s2; R(1, 1) = c0 * c1; R(2, 2) = c2 * c1; @@ -75,20 +76,21 @@ inline matrix::Dcmf taitBryan312ToRotMat(const matrix::Vector3f &rot312) return R; } -inline matrix::Dcmf quatToInverseRotMat(const matrix::Quatf &quat) +template +inline matrix::Dcm quatToInverseRotMat(const matrix::Quaternion &quat) { - const float q00 = quat(0) * quat(0); - const float q11 = quat(1) * quat(1); - const float q22 = quat(2) * quat(2); - const float q33 = quat(3) * quat(3); - const float q01 = quat(0) * quat(1); - const float q02 = quat(0) * quat(2); - const float q03 = quat(0) * quat(3); - const float q12 = quat(1) * quat(2); - const float q13 = quat(1) * quat(3); - const float q23 = quat(2) * quat(3); - - matrix::Dcmf dcm; + const T q00 = quat(0) * quat(0); + const T q11 = quat(1) * quat(1); + const T q22 = quat(2) * quat(2); + const T q33 = quat(3) * quat(3); + const T q01 = quat(0) * quat(1); + const T q02 = quat(0) * quat(2); + const T q03 = quat(0) * quat(3); + const T q12 = quat(1) * quat(2); + const T q13 = quat(1) * quat(3); + const T q23 = quat(2) * quat(3); + + matrix::Dcm dcm; dcm(0, 0) = q00 + q11 - q22 - q33; dcm(1, 1) = q00 - q11 + q22 - q33; dcm(2, 2) = q00 - q11 - q22 + q33; @@ -105,40 +107,46 @@ inline matrix::Dcmf quatToInverseRotMat(const matrix::Quatf &quat) // We should use a 3-2-1 Tait-Bryan (yaw-pitch-roll) rotation sequence // when there is more roll than pitch tilt and a 3-1-2 rotation sequence // when there is more pitch than roll tilt to avoid gimbal lock. -inline bool shouldUse321RotationSequence(const matrix::Dcmf &R) +template +inline bool shouldUse321RotationSequence(const matrix::Dcm &R) { return fabsf(R(2, 0)) < fabsf(R(2, 1)); } -inline float getEuler321Yaw(const matrix::Dcmf &R) +template +inline float getEuler321Yaw(const matrix::Dcm &R) { return atan2f(R(1, 0), R(0, 0)); } -inline float getEuler312Yaw(const matrix::Dcmf &R) +template +inline float getEuler312Yaw(const matrix::Dcm &R) { return atan2f(-R(0, 1), R(1, 1)); } -inline float getEuler321Yaw(const matrix::Quatf &q) +template +inline T getEuler321Yaw(const matrix::Quaternion &q) { // Values from yaw_input_321.c file produced by // https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw321.m - const float a = 2.f * (q(0) * q(3) + q(1) * q(2)); - const float b = sq(q(0)) + sq(q(1)) - sq(q(2)) - sq(q(3)); + const T a = static_cast(2.) * (q(0) * q(3) + q(1) * q(2)); + const T b = sq(q(0)) + sq(q(1)) - sq(q(2)) - sq(q(3)); return atan2f(a, b); } -inline float getEuler312Yaw(const matrix::Quatf &q) +template +inline T getEuler312Yaw(const matrix::Quaternion &q) { // Values from yaw_input_312.c file produced by // https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw312.m - const float a = 2.f * (q(0) * q(3) - q(1) * q(2)); - const float b = sq(q(0)) - sq(q(1)) + sq(q(2)) - sq(q(3)); + const T a = static_cast(2.) * (q(0) * q(3) - q(1) * q(2)); + const T b = sq(q(0)) - sq(q(1)) + sq(q(2)) - sq(q(3)); return atan2f(a, b); } -inline float getEulerYaw(const matrix::Dcmf &R) +template +inline T getEulerYaw(const matrix::Dcm &R) { if (shouldUse321RotationSequence(R)) { return getEuler321Yaw(R); @@ -148,23 +156,32 @@ inline float getEulerYaw(const matrix::Dcmf &R) } } -inline matrix::Dcmf updateEuler321YawInRotMat(float yaw, const matrix::Dcmf &rot_in) +template +inline T getEulerYaw(const matrix::Quaternion &q) { - matrix::Eulerf euler321(rot_in); + return getEulerYaw(matrix::Dcm(q)); +} + +template +inline matrix::Dcm updateEuler321YawInRotMat(T yaw, const matrix::Dcm &rot_in) +{ + matrix::Euler euler321(rot_in); euler321(2) = yaw; - return matrix::Dcmf(euler321); + return matrix::Dcm(euler321); } -inline matrix::Dcmf updateEuler312YawInRotMat(float yaw, const matrix::Dcmf &rot_in) +template +inline matrix::Dcm updateEuler312YawInRotMat(T yaw, const matrix::Dcm &rot_in) { - const matrix::Vector3f rotVec312(yaw, // yaw - asinf(rot_in(2, 1)), // roll - atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch + const matrix::Vector3 rotVec312(yaw, // yaw + asinf(rot_in(2, 1)), // roll + atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch return taitBryan312ToRotMat(rotVec312); } // Checks which euler rotation sequence to use and update yaw in rotation matrix -inline matrix::Dcmf updateYawInRotMat(float yaw, const matrix::Dcmf &rot_in) +template +inline matrix::Dcm updateYawInRotMat(T yaw, const matrix::Dcm &rot_in) { if (shouldUse321RotationSequence(rot_in)) { return updateEuler321YawInRotMat(yaw, rot_in); From af16544809c4863a8f9417937320a3d5485f00b7 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Tue, 19 Mar 2024 12:26:31 -0600 Subject: [PATCH 020/652] boards: ark septentrio update flash size and enable ekf2 --- boards/ark/septentrio-gps/default.px4board | 1 + boards/ark/septentrio-gps/init/rc.board_defaults | 2 ++ boards/ark/septentrio-gps/nuttx-config/canbootloader/defconfig | 1 + boards/ark/septentrio-gps/nuttx-config/nsh/defconfig | 1 + .../septentrio-gps/nuttx-config/scripts/canbootloader_script.ld | 2 +- boards/ark/septentrio-gps/nuttx-config/scripts/script.ld | 2 +- 6 files changed, 7 insertions(+), 2 deletions(-) diff --git a/boards/ark/septentrio-gps/default.px4board b/boards/ark/septentrio-gps/default.px4board index 1480a0b4da05..b62a95d689d5 100644 --- a/boards/ark/septentrio-gps/default.px4board +++ b/boards/ark/septentrio-gps/default.px4board @@ -20,6 +20,7 @@ CONFIG_UAVCANNODE_RTK_DATA=y CONFIG_UAVCANNODE_SAFETY_BUTTON=y CONFIG_UAVCANNODE_STATIC_PRESSURE=y CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y +CONFIG_MODULES_EKF2=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_SENSORS=y diff --git a/boards/ark/septentrio-gps/init/rc.board_defaults b/boards/ark/septentrio-gps/init/rc.board_defaults index c50d81602629..0db1234ce96d 100644 --- a/boards/ark/septentrio-gps/init/rc.board_defaults +++ b/boards/ark/septentrio-gps/init/rc.board_defaults @@ -11,3 +11,5 @@ param set-default SENS_IMU_CLPNOTI 0 safety_button start tone_alarm start + +ekf2 start diff --git a/boards/ark/septentrio-gps/nuttx-config/canbootloader/defconfig b/boards/ark/septentrio-gps/nuttx-config/canbootloader/defconfig index 6b3c2c951842..0208af2cac25 100644 --- a/boards/ark/septentrio-gps/nuttx-config/canbootloader/defconfig +++ b/boards/ark/septentrio-gps/nuttx-config/canbootloader/defconfig @@ -50,6 +50,7 @@ CONFIG_STACK_COLORATION=y CONFIG_START_DAY=30 CONFIG_START_MONTH=11 CONFIG_STDIO_DISABLE_BUFFERING=y +CONFIG_STM32_FLASH_CONFIG_G=y CONFIG_STM32_NOEXT_VECTORS=y CONFIG_STM32_TIM8=y CONFIG_TASK_NAME_SIZE=0 diff --git a/boards/ark/septentrio-gps/nuttx-config/nsh/defconfig b/boards/ark/septentrio-gps/nuttx-config/nsh/defconfig index 81007d30a44f..176ae3eccc5b 100644 --- a/boards/ark/septentrio-gps/nuttx-config/nsh/defconfig +++ b/boards/ark/septentrio-gps/nuttx-config/nsh/defconfig @@ -123,6 +123,7 @@ CONFIG_STM32_ADC1=y CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y CONFIG_STM32_DMA1=y CONFIG_STM32_DMA2=y +CONFIG_STM32_FLASH_CONFIG_G=y CONFIG_STM32_FLASH_PREFETCH=y CONFIG_STM32_FLOWCONTROL_BROKEN=y CONFIG_STM32_I2C1=y diff --git a/boards/ark/septentrio-gps/nuttx-config/scripts/canbootloader_script.ld b/boards/ark/septentrio-gps/nuttx-config/scripts/canbootloader_script.ld index cbf9fddc32dc..48a59fe92d0e 100644 --- a/boards/ark/septentrio-gps/nuttx-config/scripts/canbootloader_script.ld +++ b/boards/ark/septentrio-gps/nuttx-config/scripts/canbootloader_script.ld @@ -33,7 +33,7 @@ * ****************************************************************************/ -/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and * 256Kb of SRAM. SRAM is split up into three blocks: * * 1) 112Kb of SRAM beginning at address 0x2000:0000 diff --git a/boards/ark/septentrio-gps/nuttx-config/scripts/script.ld b/boards/ark/septentrio-gps/nuttx-config/scripts/script.ld index d8573d2bcdde..2f4769b8f5b4 100644 --- a/boards/ark/septentrio-gps/nuttx-config/scripts/script.ld +++ b/boards/ark/septentrio-gps/nuttx-config/scripts/script.ld @@ -33,7 +33,7 @@ * ****************************************************************************/ -/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and * 256Kb of SRAM. SRAM is split up into three blocks: * * 1) 112Kb of SRAM beginning at address 0x2000:0000 From 34c19b2e5a39831373509d69c71b346d098b975d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 20 Mar 2024 12:35:34 -0400 Subject: [PATCH 021/652] boards/px4/fmu-v5x: default remove systemcmds/sd_stress to save flash --- boards/px4/fmu-v5x/default.px4board | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index e2b5833dfecb..4107d049e1d3 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -104,7 +104,6 @@ CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_REFLECT=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 From 710286da722beae72a488af52b6c1e603f68eea7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C3=98yvind=20Taksdal=20Stubhaug?= Date: Wed, 20 Mar 2024 17:38:47 +0100 Subject: [PATCH 022/652] uavcan: publish new can interface status as uorb topic (#22873) --- msg/CMakeLists.txt | 1 + msg/CanInterfaceStatus.msg | 6 +++++ src/drivers/uavcan/CMakeLists.txt | 1 + src/drivers/uavcan/uavcan_main.cpp | 35 ++++++++++++++++++++++++++++ src/drivers/uavcan/uavcan_main.hpp | 5 ++++ src/modules/logger/logged_topics.cpp | 1 + 6 files changed, 49 insertions(+) create mode 100644 msg/CanInterfaceStatus.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 3b1e2647e3c5..c53402bd0f35 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -58,6 +58,7 @@ set(msg_files CameraCapture.msg CameraStatus.msg CameraTrigger.msg + CanInterfaceStatus.msg CellularStatus.msg CollisionConstraints.msg CollisionReport.msg diff --git a/msg/CanInterfaceStatus.msg b/msg/CanInterfaceStatus.msg new file mode 100644 index 000000000000..4129c8d56386 --- /dev/null +++ b/msg/CanInterfaceStatus.msg @@ -0,0 +1,6 @@ +uint64 timestamp # time since system start (microseconds) +uint8 interface + +uint64 io_errors +uint64 frames_tx +uint64 frames_rx diff --git a/src/drivers/uavcan/CMakeLists.txt b/src/drivers/uavcan/CMakeLists.txt index 4146edab05b8..39a9bb3ff2ff 100644 --- a/src/drivers/uavcan/CMakeLists.txt +++ b/src/drivers/uavcan/CMakeLists.txt @@ -75,6 +75,7 @@ add_definitions( -DUAVCAN_${UAVCAN_DRIVER_UPPER}_${OS_UPPER}=1 -DUAVCAN_${UAVCAN_DRIVER_UPPER}_NUM_IFACES=${config_uavcan_num_ifaces} -DUAVCAN_${UAVCAN_DRIVER_UPPER}_TIMER_NUMBER=${UAVCAN_TIMER} + -DUAVCAN_NUM_IFACES=${config_uavcan_num_ifaces} -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAVCAN_DRIVER=uavcan_${UAVCAN_DRIVER} -DUAVCAN_IMPLEMENT_PLACEMENT_NEW=1 diff --git a/src/drivers/uavcan/uavcan_main.cpp b/src/drivers/uavcan/uavcan_main.cpp index 277b2526ddd4..fbdc534a9c30 100644 --- a/src/drivers/uavcan/uavcan_main.cpp +++ b/src/drivers/uavcan/uavcan_main.cpp @@ -744,6 +744,41 @@ UavcanNode::Run() _node.spinOnce(); // expected to be non-blocking + // Publish status + constexpr hrt_abstime status_pub_interval = 100_ms; + + if (hrt_absolute_time() - _last_can_status_pub >= status_pub_interval) { + _last_can_status_pub = hrt_absolute_time(); + + for (int i = 0; i < _node.getDispatcher().getCanIOManager().getCanDriver().getNumIfaces(); i++) { + if (i > UAVCAN_NUM_IFACES) { + break; + } + + auto iface = _node.getDispatcher().getCanIOManager().getCanDriver().getIface(i); + + if (!iface) { + continue; + } + + auto iface_perf_cnt = _node.getDispatcher().getCanIOManager().getIfacePerfCounters(i); + can_interface_status_s status{ + .timestamp = hrt_absolute_time(), + .io_errors = iface_perf_cnt.errors, + .frames_tx = iface_perf_cnt.frames_tx, + .frames_rx = iface_perf_cnt.frames_rx, + .interface = static_cast(i), + }; + + if (_can_status_pub_handles[i] == nullptr) { + int instance{0}; + _can_status_pub_handles[i] = orb_advertise_multi(ORB_ID(can_interface_status), nullptr, &instance); + } + + (void)orb_publish(ORB_ID(can_interface_status), _can_status_pub_handles[i], &status); + } + } + // check for parameter updates if (_parameter_update_sub.updated()) { // clear update diff --git a/src/drivers/uavcan/uavcan_main.hpp b/src/drivers/uavcan/uavcan_main.hpp index 54119259ef16..5afa04ef672e 100644 --- a/src/drivers/uavcan/uavcan_main.hpp +++ b/src/drivers/uavcan/uavcan_main.hpp @@ -96,6 +96,7 @@ #include #include #include +#include #include #include #include @@ -309,6 +310,10 @@ class UavcanNode : public px4::ScheduledWorkItem, public ModuleParams uORB::Publication _param_response_pub{ORB_ID(uavcan_parameter_value)}; uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::PublicationMulti _can_status_pub{ORB_ID(can_interface_status)}; + + hrt_abstime _last_can_status_pub{0}; + orb_advert_t _can_status_pub_handles[UAVCAN_NUM_IFACES] = {nullptr}; /* * The MAVLink parameter bridge needs to know the maximum parameter index diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 68b3d27b42fd..cd72d324a0c9 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -53,6 +53,7 @@ void LoggedTopics::add_default_topics() add_optional_topic("autotune_attitude_control_status", 100); add_optional_topic("camera_capture"); add_optional_topic("camera_trigger"); + add_optional_topic("can_interface_status", 10); add_topic("cellular_status", 200); add_topic("commander_state"); add_topic("config_overrides"); From 5f6dc1c5d09a117bdeb4bda715d934de316c39ad Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Thu, 21 Mar 2024 17:53:34 -0700 Subject: [PATCH 023/652] uORB: SubscriptionBlocking purged the broken attempt to set the mutex protocol in constructor --- .../common/uORB/SubscriptionBlocking.hpp | 25 ------------------- 1 file changed, 25 deletions(-) diff --git a/platforms/common/uORB/SubscriptionBlocking.hpp b/platforms/common/uORB/SubscriptionBlocking.hpp index 7ec29e329b6e..5c5580d855cb 100644 --- a/platforms/common/uORB/SubscriptionBlocking.hpp +++ b/platforms/common/uORB/SubscriptionBlocking.hpp @@ -56,31 +56,6 @@ class SubscriptionBlocking : public SubscriptionCallback SubscriptionBlocking(const orb_metadata *meta, uint32_t interval_us = 0, uint8_t instance = 0) : SubscriptionCallback(meta, interval_us, instance) { - // pthread_mutexattr_init - pthread_mutexattr_t attr; - int ret_attr_init = pthread_mutexattr_init(&attr); - - if (ret_attr_init != 0) { - PX4_ERR("pthread_mutexattr_init failed, status=%d", ret_attr_init); - } - -#if defined(PTHREAD_PRIO_NONE) - // pthread_mutexattr_settype - // PTHREAD_PRIO_NONE not available on cygwin - int ret_mutexattr_settype = pthread_mutexattr_settype(&attr, PTHREAD_PRIO_NONE); - - if (ret_mutexattr_settype != 0) { - PX4_ERR("pthread_mutexattr_settype failed, status=%d", ret_mutexattr_settype); - } - -#endif // PTHREAD_PRIO_NONE - - // pthread_mutex_init - int ret_mutex_init = pthread_mutex_init(&_mutex, &attr); - - if (ret_mutex_init != 0) { - PX4_ERR("pthread_mutex_init failed, status=%d", ret_mutex_init); - } } virtual ~SubscriptionBlocking() From 82a1aa37dbfb060406ed72f28e511786010c8f5f Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Thu, 21 Mar 2024 17:54:43 -0700 Subject: [PATCH 024/652] uORB: fix for uORB communicator, only send most recent data for new subscription (#22893) --- platforms/common/uORB/uORBDeviceNode.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/platforms/common/uORB/uORBDeviceNode.cpp b/platforms/common/uORB/uORBDeviceNode.cpp index e83b3f3e04e3..fd4ef60e63e0 100644 --- a/platforms/common/uORB/uORBDeviceNode.cpp +++ b/platforms/common/uORB/uORBDeviceNode.cpp @@ -412,7 +412,10 @@ int16_t uORB::DeviceNode::process_add_subscription() uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator(); if (_data != nullptr && ch != nullptr) { // _data will not be null if there is a publisher. - ch->send_message(_meta->o_name, _meta->o_size, _data); + // Only send the most recent data to initialize the remote end. + if (_data_valid) { + ch->send_message(_meta->o_name, _meta->o_size, _data + (_meta->o_size * ((_generation.load() - 1) % _meta->o_queue))); + } } return PX4_OK; From d0251b8688fd768727fe8c644ef2fabae168452c Mon Sep 17 00:00:00 2001 From: Thomas Frans <160142177+flyingthingsintothings@users.noreply.github.com> Date: Fri, 22 Mar 2024 01:56:20 +0100 Subject: [PATCH 025/652] add `.editorconfig` for consistent code style across editors (#22916) EditorConfig is a well-known convention to share style settings across different editors. Adding one will make it easier for new contributors or people who like to use a different editor to contribute. --- .editorconfig | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 .editorconfig diff --git a/.editorconfig b/.editorconfig new file mode 100644 index 000000000000..87496c115e9e --- /dev/null +++ b/.editorconfig @@ -0,0 +1,6 @@ +root = true + +[*.{c,cpp,cc,h,hpp}] +indent_style = tab +tab_width = 8 +max_line_length = 120 From 2e12e14a23db3dc949c1004fc2290b4bcb05038d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 20 Mar 2024 08:47:02 +0100 Subject: [PATCH 026/652] boards/px4/fmu-v5x: remove sd_stress & reflect to reduce flash usage --- boards/px4/fmu-v5x/default.px4board | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 4107d049e1d3..a4c2baf0dc37 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -102,7 +102,6 @@ CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y -CONFIG_SYSTEMCMDS_REFLECT=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y From bb9f4d42f30a98e76542e31f767d9d9e34671ba9 Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Wed, 20 Mar 2024 10:30:37 +0100 Subject: [PATCH 027/652] gps: fix incorrect task id in module startup --- src/drivers/gps/gps.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 4ed29a8c6e35..fcbd5a0c8384 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -1406,7 +1406,7 @@ int GPS::task_spawn(int argc, char *argv[], Instance instance) entry_point, (char *const *)argv); if (task_id < 0) { - task_id = -1; + _task_id = -1; return -errno; } From 69028f37a91b48add269ef699101922e52410446 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Thu, 21 Mar 2024 18:00:23 -0700 Subject: [PATCH 028/652] New platform independent Serial interface (#21723) --- boards/modalai/fc-v2/default.px4board | 2 +- boards/modalai/voxl2-slpi/default.px4board | 1 + platforms/common/CMakeLists.txt | 1 + platforms/common/Serial.cpp | 138 ++++++ .../include/px4_platform_common/Serial.hpp | 97 +++++ .../px4_platform_common/SerialCommon.hpp | 70 ++++ .../common/include/px4_platform_common/time.h | 13 +- platforms/nuttx/src/px4/common/SerialImpl.cpp | 394 ++++++++++++++++++ .../src/px4/common/include/SerialImpl.hpp | 104 +++++ .../nuttx/src/px4/common/px4_layer.cmake | 2 + .../src/px4/common/px4_protected_layers.cmake | 2 + platforms/posix/include/SerialImpl.hpp | 103 +++++ platforms/posix/src/px4/common/CMakeLists.txt | 2 + platforms/posix/src/px4/common/SerialImpl.cpp | 387 +++++++++++++++++ platforms/qurt/CMakeLists.txt | 1 - platforms/qurt/include/SerialImpl.hpp | 108 +++++ platforms/qurt/src/px4/CMakeLists.txt | 1 + platforms/qurt/src/px4/SerialImpl.cpp | 326 +++++++++++++++ platforms/qurt/src/px4/drv_hrt.cpp | 2 +- src/drivers/gps/gps.cpp | 325 +++++++-------- 20 files changed, 1902 insertions(+), 177 deletions(-) create mode 100644 platforms/common/Serial.cpp create mode 100644 platforms/common/include/px4_platform_common/Serial.hpp create mode 100644 platforms/common/include/px4_platform_common/SerialCommon.hpp create mode 100644 platforms/nuttx/src/px4/common/SerialImpl.cpp create mode 100644 platforms/nuttx/src/px4/common/include/SerialImpl.hpp create mode 100644 platforms/posix/include/SerialImpl.hpp create mode 100644 platforms/posix/src/px4/common/SerialImpl.cpp create mode 100644 platforms/qurt/include/SerialImpl.hpp create mode 100644 platforms/qurt/src/px4/SerialImpl.cpp diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index be01cfa93415..c4e7d3649597 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -60,7 +60,7 @@ CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y -CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +# CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y diff --git a/boards/modalai/voxl2-slpi/default.px4board b/boards/modalai/voxl2-slpi/default.px4board index 73e75dd7bcb0..b6ce6133fcdf 100644 --- a/boards/modalai/voxl2-slpi/default.px4board +++ b/boards/modalai/voxl2-slpi/default.px4board @@ -4,6 +4,7 @@ CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP101XX=y CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y +CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y diff --git a/platforms/common/CMakeLists.txt b/platforms/common/CMakeLists.txt index a0bafe7d59de..cb0721fe6911 100644 --- a/platforms/common/CMakeLists.txt +++ b/platforms/common/CMakeLists.txt @@ -52,6 +52,7 @@ add_library(px4_platform STATIC shutdown.cpp spi.cpp pab_manifest.c + Serial.cpp ${SRCS} ) target_link_libraries(px4_platform prebuild_targets px4_work_queue) diff --git a/platforms/common/Serial.cpp b/platforms/common/Serial.cpp new file mode 100644 index 000000000000..2f93a66a6ebf --- /dev/null +++ b/platforms/common/Serial.cpp @@ -0,0 +1,138 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +namespace device +{ + +Serial::Serial(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, + FlowControl flowcontrol) : + _impl(port, baudrate, bytesize, parity, stopbits, flowcontrol) +{ + // If no baudrate was specified then set it to a reasonable default value + if (baudrate == 0) { + (void) _impl.setBaudrate(9600); + } +} + +Serial::~Serial() +{ +} + +bool Serial::open() +{ + return _impl.open(); +} + +bool Serial::isOpen() const +{ + return _impl.isOpen(); +} + +bool Serial::close() +{ + return _impl.close(); +} + +ssize_t Serial::read(uint8_t *buffer, size_t buffer_size) +{ + return _impl.read(buffer, buffer_size); +} + +ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +{ + return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_us); +} + +ssize_t Serial::write(const void *buffer, size_t buffer_size) +{ + return _impl.write(buffer, buffer_size); +} + +uint32_t Serial::getBaudrate() const +{ + return _impl.getBaudrate(); +} + +bool Serial::setBaudrate(uint32_t baudrate) +{ + return _impl.setBaudrate(baudrate); +} + +ByteSize Serial::getBytesize() const +{ + return _impl.getBytesize(); +} + +bool Serial::setBytesize(ByteSize bytesize) +{ + return _impl.setBytesize(bytesize); +} + +Parity Serial::getParity() const +{ + return _impl.getParity(); +} + +bool Serial::setParity(Parity parity) +{ + return _impl.setParity(parity); +} + +StopBits Serial::getStopbits() const +{ + return _impl.getStopbits(); +} + +bool Serial::setStopbits(StopBits stopbits) +{ + return _impl.setStopbits(stopbits); +} + +FlowControl Serial::getFlowcontrol() const +{ + return _impl.getFlowcontrol(); +} + +bool Serial::setFlowcontrol(FlowControl flowcontrol) +{ + return _impl.setFlowcontrol(flowcontrol); +} + +const char *Serial::getPort() const +{ + return _impl.getPort(); +} + +} // namespace device diff --git a/platforms/common/include/px4_platform_common/Serial.hpp b/platforms/common/include/px4_platform_common/Serial.hpp new file mode 100644 index 000000000000..ce02b5ac6308 --- /dev/null +++ b/platforms/common/include/px4_platform_common/Serial.hpp @@ -0,0 +1,97 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include + +#include + +using device::SerialConfig::ByteSize; +using device::SerialConfig::Parity; +using device::SerialConfig::StopBits; +using device::SerialConfig::FlowControl; + +namespace device __EXPORT +{ + +class Serial +{ +public: + Serial(const char *port, uint32_t baudrate = 57600, + ByteSize bytesize = ByteSize::EightBits, Parity parity = Parity::None, + StopBits stopbits = StopBits::One, FlowControl flowcontrol = FlowControl::Disabled); + virtual ~Serial(); + + // Open sets up the port and gets it configured based on desired configuration + bool open(); + bool isOpen() const; + + bool close(); + + ssize_t read(uint8_t *buffer, size_t buffer_size); + ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); + + ssize_t write(const void *buffer, size_t buffer_size); + + // If port is already open then the following configuration functions + // will reconfigure the port. If the port is not yet open then they will + // simply store the configuration in preparation for the port to be opened. + + uint32_t getBaudrate() const; + bool setBaudrate(uint32_t baudrate); + + ByteSize getBytesize() const; + bool setBytesize(ByteSize bytesize); + + Parity getParity() const; + bool setParity(Parity parity); + + StopBits getStopbits() const; + bool setStopbits(StopBits stopbits); + + FlowControl getFlowcontrol() const; + bool setFlowcontrol(FlowControl flowcontrol); + + const char *getPort() const; + +private: + // Disable copy constructors + Serial(const Serial &); + Serial &operator=(const Serial &); + + // platform implementation + SerialImpl _impl; +}; + +} // namespace device diff --git a/platforms/common/include/px4_platform_common/SerialCommon.hpp b/platforms/common/include/px4_platform_common/SerialCommon.hpp new file mode 100644 index 000000000000..bbe9be0ad9fe --- /dev/null +++ b/platforms/common/include/px4_platform_common/SerialCommon.hpp @@ -0,0 +1,70 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +namespace device +{ +namespace SerialConfig +{ + + +// ByteSize: number of data bits +enum class ByteSize { + FiveBits = 5, + SixBits = 6, + SevenBits = 7, + EightBits = 8, +}; + +// Parity: enable parity checking +enum class Parity { + None = 0, + Odd = 1, + Even = 2, +}; + +// StopBits: number of stop bits +enum class StopBits { + One = 1, + Two = 2 +}; + +// FlowControl: enable flow control +enum class FlowControl { + Disabled = 0, + Enabled = 1, +}; + +} // namespace SerialConfig +} // namespace device diff --git a/platforms/common/include/px4_platform_common/time.h b/platforms/common/include/px4_platform_common/time.h index 1b4d8a27560c..d61e23c75cfb 100644 --- a/platforms/common/include/px4_platform_common/time.h +++ b/platforms/common/include/px4_platform_common/time.h @@ -13,11 +13,21 @@ __END_DECLS #define px4_clock_gettime system_clock_gettime #endif -#if defined(ENABLE_LOCKSTEP_SCHEDULER) +#if defined(ENABLE_LOCKSTEP_SCHEDULER) || defined(__PX4_QURT) __BEGIN_DECLS __EXPORT int px4_clock_settime(clockid_t clk_id, const struct timespec *tp); +__END_DECLS + +#else + +#define px4_clock_settime system_clock_settime +#endif + +#if defined(ENABLE_LOCKSTEP_SCHEDULER) + +__BEGIN_DECLS __EXPORT int px4_usleep(useconds_t usec); __EXPORT unsigned int px4_sleep(unsigned int seconds); __EXPORT int px4_pthread_cond_timedwait(pthread_cond_t *cond, @@ -27,7 +37,6 @@ __END_DECLS #else -#define px4_clock_settime system_clock_settime #define px4_usleep system_usleep #define px4_sleep system_sleep #define px4_pthread_cond_timedwait system_pthread_cond_timedwait diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp new file mode 100644 index 000000000000..7490dd604cc4 --- /dev/null +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -0,0 +1,394 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include // strncpy +#include +#include +#include +#include +#include +#include + +#define MODULE_NAME "SerialImpl" + +namespace device +{ + +SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, + FlowControl flowcontrol) : + _baudrate(baudrate), + _bytesize(bytesize), + _parity(parity), + _stopbits(stopbits), + _flowcontrol(flowcontrol) +{ + if (port) { + strncpy(_port, port, sizeof(_port) - 1); + _port[sizeof(_port) - 1] = '\0'; + + } else { + _port[0] = 0; + } +} + +SerialImpl::~SerialImpl() +{ + if (isOpen()) { + close(); + } +} + +bool SerialImpl::validateBaudrate(uint32_t baudrate) +{ + return ((baudrate == 9600) || + (baudrate == 19200) || + (baudrate == 38400) || + (baudrate == 57600) || + (baudrate == 115200) || + (baudrate == 230400) || + (baudrate == 460800) || + (baudrate == 921600)); +} + +bool SerialImpl::configure() +{ + /* process baud rate */ + int speed; + + if (! validateBaudrate(_baudrate)) { + PX4_ERR("ERR: unknown baudrate: %lu", _baudrate); + return false; + } + + switch (_baudrate) { + case 9600: speed = B9600; break; + + case 19200: speed = B19200; break; + + case 38400: speed = B38400; break; + + case 57600: speed = B57600; break; + + case 115200: speed = B115200; break; + + case 230400: speed = B230400; break; + +#ifndef B460800 +#define B460800 460800 +#endif + + case 460800: speed = B460800; break; + +#ifndef B921600 +#define B921600 921600 +#endif + + case 921600: speed = B921600; break; + + default: + PX4_ERR("ERR: unknown baudrate: %lu", _baudrate); + return false; + } + + struct termios uart_config; + + int termios_state; + + /* fill the struct for the new configuration */ + if ((termios_state = tcgetattr(_serial_fd, &uart_config)) < 0) { + PX4_ERR("ERR: %d (tcgetattr)", termios_state); + return false; + } + + /* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */ + + // + // Input flags - Turn off input processing + // + // convert break to null byte, no CR to NL translation, + // no NL to CR translation, don't mark parity errors or breaks + // no input parity check, don't strip high bit off, + // no XON/XOFF software flow control + // + uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | + INLCR | PARMRK | INPCK | ISTRIP | IXON); + + // + // Output flags - Turn off output processing + // + // no CR to NL translation, no NL to CR-NL translation, + // no NL to CR translation, no column 0 CR suppression, + // no Ctrl-D suppression, no fill characters, no case mapping, + // no local output processing + // + // config.c_oflag &= ~(OCRNL | ONLCR | ONLRET | + // ONOCR | ONOEOT| OFILL | OLCUC | OPOST); + uart_config.c_oflag = 0; + + // + // No line processing + // + // echo off, echo newline off, canonical mode off, + // extended input processing off, signal chars off + // + uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG); + + /* no parity, one stop bit, disable flow control */ + uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS); + + /* set baud rate */ + if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { + PX4_ERR("ERR: %d (cfsetispeed)", termios_state); + return false; + } + + if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { + PX4_ERR("ERR: %d (cfsetospeed)", termios_state); + return false; + } + + if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) { + PX4_ERR("ERR: %d (tcsetattr)", termios_state); + return false; + } + + return true; +} + +bool SerialImpl::open() +{ + if (isOpen()) { + return true; + } + + // Open the serial port + int serial_fd = ::open(_port, O_RDWR | O_NOCTTY); + + if (serial_fd < 0) { + PX4_ERR("failed to open %s err: %d", _port, errno); + return false; + } + + _serial_fd = serial_fd; + + // Configure the serial port + if (! configure()) { + PX4_ERR("failed to configure %s err: %d", _port, errno); + return false; + } + + _open = true; + + return _open; +} + +bool SerialImpl::isOpen() const +{ + return _open; +} + +bool SerialImpl::close() +{ + + if (_serial_fd >= 0) { + ::close(_serial_fd); + } + + _serial_fd = -1; + _open = false; + + return true; +} + +ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) +{ + if (!_open) { + PX4_ERR("Cannot read from serial device until it has been opened"); + return -1; + } + + int ret = ::read(_serial_fd, buffer, buffer_size); + + if (ret < 0) { + PX4_DEBUG("%s read error %d", _port, ret); + } + + return ret; +} + +ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +{ + if (!_open) { + PX4_ERR("Cannot readAtLeast from serial device until it has been opened"); + return -1; + } + + if (buffer_size < character_count) { + PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__); + return -1; + } + + const hrt_abstime start_time_us = hrt_absolute_time(); + int total_bytes_read = 0; + + while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) { + // Poll for incoming UART data. + pollfd fds[1]; + fds[0].fd = _serial_fd; + fds[0].events = POLLIN; + + hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us); + + if (remaining_time <= 0) { break; } + + int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time); + + if (ret > 0) { + if (fds[0].revents & POLLIN) { + const unsigned sleeptime = character_count * 1000000 / (_baudrate / 10); + + int err = 0; + int bytes_available = 0; + err = ::ioctl(_serial_fd, FIONREAD, (unsigned long)&bytes_available); + + if (err != 0 || bytes_available < (int)character_count) { + px4_usleep(sleeptime); + } + + ret = read(&buffer[total_bytes_read], buffer_size - total_bytes_read); + + if (ret > 0) { + total_bytes_read += ret; + } + + } else { + PX4_ERR("Got a poll error"); + return -1; + } + } + } + + return total_bytes_read; +} + +ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) +{ + if (!_open) { + PX4_ERR("Cannot write to serial device until it has been opened"); + return -1; + } + + int written = ::write(_serial_fd, buffer, buffer_size); + ::fsync(_serial_fd); + + if (written < 0) { + PX4_ERR("%s write error %d", _port, written); + } + + return written; +} + +const char *SerialImpl::getPort() const +{ + return _port; +} + +uint32_t SerialImpl::getBaudrate() const +{ + return _baudrate; +} + +bool SerialImpl::setBaudrate(uint32_t baudrate) +{ + if (! validateBaudrate(baudrate)) { + PX4_ERR("ERR: invalid baudrate: %lu", baudrate); + return false; + } + + // check if already configured + if ((baudrate == _baudrate) && _open) { + return true; + } + + _baudrate = baudrate; + + // process baud rate change now if port is already open + if (_open) { + return configure(); + } + + return true; +} + +ByteSize SerialImpl::getBytesize() const +{ + return _bytesize; +} + +bool SerialImpl::setBytesize(ByteSize bytesize) +{ + return bytesize == ByteSize::EightBits; +} + +Parity SerialImpl::getParity() const +{ + return _parity; +} + +bool SerialImpl::setParity(Parity parity) +{ + return parity == Parity::None; +} + +StopBits SerialImpl::getStopbits() const +{ + return _stopbits; +} + +bool SerialImpl::setStopbits(StopBits stopbits) +{ + return stopbits == StopBits::One; +} + +FlowControl SerialImpl::getFlowcontrol() const +{ + return _flowcontrol; +} + +bool SerialImpl::setFlowcontrol(FlowControl flowcontrol) +{ + return flowcontrol == FlowControl::Disabled; +} + +} // namespace device diff --git a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp new file mode 100644 index 000000000000..58d41bf759c9 --- /dev/null +++ b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp @@ -0,0 +1,104 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include +#include + +#include + +using device::SerialConfig::ByteSize; +using device::SerialConfig::Parity; +using device::SerialConfig::StopBits; +using device::SerialConfig::FlowControl; + +namespace device +{ + +class SerialImpl +{ +public: + + SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, + FlowControl flowcontrol); + virtual ~SerialImpl(); + + bool open(); + bool isOpen() const; + + bool close(); + + ssize_t read(uint8_t *buffer, size_t buffer_size); + ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); + + ssize_t write(const void *buffer, size_t buffer_size); + + const char *getPort() const; + + uint32_t getBaudrate() const; + bool setBaudrate(uint32_t baudrate); + + ByteSize getBytesize() const; + bool setBytesize(ByteSize bytesize); + + Parity getParity() const; + bool setParity(Parity parity); + + StopBits getStopbits() const; + bool setStopbits(StopBits stopbits); + + FlowControl getFlowcontrol() const; + bool setFlowcontrol(FlowControl flowcontrol); + +private: + + int _serial_fd{-1}; + + bool _open{false}; + + char _port[32] {}; + + uint32_t _baudrate{0}; + + ByteSize _bytesize{ByteSize::EightBits}; + Parity _parity{Parity::None}; + StopBits _stopbits{StopBits::One}; + FlowControl _flowcontrol{FlowControl::Disabled}; + + bool validateBaudrate(uint32_t baudrate); + bool configure(); + +}; + +} // namespace device diff --git a/platforms/nuttx/src/px4/common/px4_layer.cmake b/platforms/nuttx/src/px4/common/px4_layer.cmake index 69fd1a007da9..9199a9528997 100644 --- a/platforms/nuttx/src/px4/common/px4_layer.cmake +++ b/platforms/nuttx/src/px4/common/px4_layer.cmake @@ -3,6 +3,8 @@ add_library(px4_layer ${KERNEL_SRCS} cdc_acm_check.cpp + ${PX4_SOURCE_DIR}/platforms/common/Serial.cpp + SerialImpl.cpp ) target_link_libraries(px4_layer diff --git a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake index 9c57b488b6d3..a1c6ebc39175 100644 --- a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake +++ b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake @@ -15,6 +15,8 @@ add_library(px4_layer usr_board_ctrl.c usr_hrt.cpp usr_mcu_version.cpp + ${PX4_SOURCE_DIR}/platforms/common/Serial.cpp + SerialImpl.cpp ) target_link_libraries(px4_layer diff --git a/platforms/posix/include/SerialImpl.hpp b/platforms/posix/include/SerialImpl.hpp new file mode 100644 index 000000000000..efc95d7d517a --- /dev/null +++ b/platforms/posix/include/SerialImpl.hpp @@ -0,0 +1,103 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include +#include + +#include + +using device::SerialConfig::ByteSize; +using device::SerialConfig::Parity; +using device::SerialConfig::StopBits; +using device::SerialConfig::FlowControl; + +namespace device +{ + +class SerialImpl +{ +public: + + SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, + FlowControl flowcontrol); + virtual ~SerialImpl(); + + bool open(); + bool isOpen() const; + + bool close(); + + ssize_t read(uint8_t *buffer, size_t buffer_size); + ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); + + ssize_t write(const void *buffer, size_t buffer_size); + + const char *getPort() const; + + uint32_t getBaudrate() const; + bool setBaudrate(uint32_t baudrate); + + ByteSize getBytesize() const; + bool setBytesize(ByteSize bytesize); + + Parity getParity() const; + bool setParity(Parity parity); + + StopBits getStopbits() const; + bool setStopbits(StopBits stopbits); + + FlowControl getFlowcontrol() const; + bool setFlowcontrol(FlowControl flowcontrol); + +private: + + int _serial_fd{-1}; + + bool _open{false}; + + char _port[32] {}; + + uint32_t _baudrate{0}; + + ByteSize _bytesize{ByteSize::EightBits}; + Parity _parity{Parity::None}; + StopBits _stopbits{StopBits::One}; + FlowControl _flowcontrol{FlowControl::Disabled}; + + bool validateBaudrate(uint32_t baudrate); + bool configure(); +}; + +} // namespace device diff --git a/platforms/posix/src/px4/common/CMakeLists.txt b/platforms/posix/src/px4/common/CMakeLists.txt index 34b65cdf44aa..90d4a77992bb 100644 --- a/platforms/posix/src/px4/common/CMakeLists.txt +++ b/platforms/posix/src/px4/common/CMakeLists.txt @@ -46,6 +46,8 @@ add_library(px4_layer drv_hrt.cpp cpuload.cpp print_load.cpp + ${PX4_SOURCE_DIR}/platforms/common/Serial.cpp + SerialImpl.cpp ) target_compile_definitions(px4_layer PRIVATE MODULE_NAME="px4") target_compile_options(px4_layer PRIVATE -Wno-cast-align) # TODO: fix and enable diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp new file mode 100644 index 000000000000..79e3422aedf2 --- /dev/null +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -0,0 +1,387 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include // strncpy +#include +#include +#include +#include +#include +#include + +namespace device +{ + +SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, + FlowControl flowcontrol) : + _baudrate(baudrate), + _bytesize(bytesize), + _parity(parity), + _stopbits(stopbits), + _flowcontrol(flowcontrol) +{ + if (port) { + strncpy(_port, port, sizeof(_port) - 1); + _port[sizeof(_port) - 1] = '\0'; + + } else { + _port[0] = 0; + } +} + +SerialImpl::~SerialImpl() +{ + if (isOpen()) { + close(); + } +} + +bool SerialImpl::validateBaudrate(uint32_t baudrate) +{ + return ((baudrate == 9600) || + (baudrate == 19200) || + (baudrate == 38400) || + (baudrate == 57600) || + (baudrate == 115200) || + (baudrate == 230400) || + (baudrate == 460800) || + (baudrate == 921600)); +} + +bool SerialImpl::configure() +{ + /* process baud rate */ + int speed; + + if (! validateBaudrate(_baudrate)) { + PX4_ERR("ERR: unknown baudrate: %u", _baudrate); + return false; + } + + switch (_baudrate) { + case 9600: speed = B9600; break; + + case 19200: speed = B19200; break; + + case 38400: speed = B38400; break; + + case 57600: speed = B57600; break; + + case 115200: speed = B115200; break; + + case 230400: speed = B230400; break; + +#ifndef B460800 +#define B460800 460800 +#endif + + case 460800: speed = B460800; break; + +#ifndef B921600 +#define B921600 921600 +#endif + + case 921600: speed = B921600; break; + + default: + PX4_ERR("ERR: unknown baudrate: %d", _baudrate); + return false; + } + + struct termios uart_config; + + int termios_state; + + /* fill the struct for the new configuration */ + if ((termios_state = tcgetattr(_serial_fd, &uart_config)) < 0) { + PX4_ERR("ERR: %d (tcgetattr)", termios_state); + return false; + } + + /* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */ + + // + // Input flags - Turn off input processing + // + // convert break to null byte, no CR to NL translation, + // no NL to CR translation, don't mark parity errors or breaks + // no input parity check, don't strip high bit off, + // no XON/XOFF software flow control + // + uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | + INLCR | PARMRK | INPCK | ISTRIP | IXON); + + // + // Output flags - Turn off output processing + // + // no CR to NL translation, no NL to CR-NL translation, + // no NL to CR translation, no column 0 CR suppression, + // no Ctrl-D suppression, no fill characters, no case mapping, + // no local output processing + // + // config.c_oflag &= ~(OCRNL | ONLCR | ONLRET | + // ONOCR | ONOEOT| OFILL | OLCUC | OPOST); + uart_config.c_oflag = 0; + + // + // No line processing + // + // echo off, echo newline off, canonical mode off, + // extended input processing off, signal chars off + // + uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG); + + /* no parity, one stop bit, disable flow control */ + uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS); + + /* set baud rate */ + if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { + PX4_ERR("ERR: %d (cfsetispeed)", termios_state); + return false; + } + + if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { + PX4_ERR("ERR: %d (cfsetospeed)", termios_state); + return false; + } + + if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) { + PX4_ERR("ERR: %d (tcsetattr)", termios_state); + return false; + } + + return true; +} + +bool SerialImpl::open() +{ + if (isOpen()) { + return true; + } + + // Open the serial port + int serial_fd = ::open(_port, O_RDWR | O_NOCTTY); + + if (serial_fd < 0) { + PX4_ERR("failed to open %s err: %d", _port, errno); + return false; + } + + _serial_fd = serial_fd; + + // Configure the serial port + if (! configure()) { + PX4_ERR("failed to configure %s err: %d", _port, errno); + return false; + } + + _open = true; + + return _open; +} + +bool SerialImpl::isOpen() const +{ + return _open; +} + +bool SerialImpl::close() +{ + + if (_serial_fd >= 0) { + ::close(_serial_fd); + } + + _serial_fd = -1; + _open = false; + + return true; +} + +ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) +{ + if (!_open) { + PX4_ERR("Cannot read from serial device until it has been opened"); + return -1; + } + + int ret = ::read(_serial_fd, buffer, buffer_size); + + if (ret < 0) { + PX4_DEBUG("%s read error %d", _port, ret); + + } + + return ret; +} + +ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +{ + if (!_open) { + PX4_ERR("Cannot readAtLeast from serial device until it has been opened"); + return -1; + } + + if (buffer_size < character_count) { + PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__); + return -1; + } + + const hrt_abstime start_time_us = hrt_absolute_time(); + int total_bytes_read = 0; + + while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) { + // Poll for incoming UART data. + pollfd fds[1]; + fds[0].fd = _serial_fd; + fds[0].events = POLLIN; + + hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us); + + if (remaining_time <= 0) { break; } + + int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time); + + if (ret > 0) { + if (fds[0].revents & POLLIN) { + const unsigned sleeptime = character_count * 1000000 / (_baudrate / 10); + px4_usleep(sleeptime); + + ret = read(&buffer[total_bytes_read], buffer_size - total_bytes_read); + + if (ret > 0) { + total_bytes_read += ret; + } + + } else { + PX4_ERR("Got a poll error"); + return -1; + } + } + } + + return total_bytes_read; +} + +ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) +{ + if (!_open) { + PX4_ERR("Cannot write to serial device until it has been opened"); + return -1; + } + + int written = ::write(_serial_fd, buffer, buffer_size); + ::fsync(_serial_fd); + + if (written < 0) { + PX4_ERR("%s write error %d", _port, written); + + } + + return written; +} + +const char *SerialImpl::getPort() const +{ + return _port; +} + +uint32_t SerialImpl::getBaudrate() const +{ + return _baudrate; +} + +bool SerialImpl::setBaudrate(uint32_t baudrate) +{ + if (! validateBaudrate(baudrate)) { + PX4_ERR("ERR: invalid baudrate: %u", baudrate); + return false; + } + + // check if already configured + if ((baudrate == _baudrate) && _open) { + return true; + } + + _baudrate = baudrate; + + // process baud rate change now if port is already open + if (_open) { + return configure(); + } + + return true; +} + +ByteSize SerialImpl::getBytesize() const +{ + return _bytesize; +} + +bool SerialImpl::setBytesize(ByteSize bytesize) +{ + return bytesize == ByteSize::EightBits; +} + +Parity SerialImpl::getParity() const +{ + return _parity; +} + +bool SerialImpl::setParity(Parity parity) +{ + return parity == Parity::None; +} + +StopBits SerialImpl::getStopbits() const +{ + return _stopbits; +} + +bool SerialImpl::setStopbits(StopBits stopbits) +{ + return stopbits == StopBits::One; +} + +FlowControl SerialImpl::getFlowcontrol() const +{ + return _flowcontrol; +} + +bool SerialImpl::setFlowcontrol(FlowControl flowcontrol) +{ + return flowcontrol == FlowControl::Disabled; +} + +} // namespace device diff --git a/platforms/qurt/CMakeLists.txt b/platforms/qurt/CMakeLists.txt index d85f3fcb7bff..0e9757a5d1a9 100644 --- a/platforms/qurt/CMakeLists.txt +++ b/platforms/qurt/CMakeLists.txt @@ -50,5 +50,4 @@ add_library(px4 SHARED target_link_libraries(px4 modules__muorb__slpi ${module_libraries} - px4_layer ) diff --git a/platforms/qurt/include/SerialImpl.hpp b/platforms/qurt/include/SerialImpl.hpp new file mode 100644 index 000000000000..1b98d3bb401b --- /dev/null +++ b/platforms/qurt/include/SerialImpl.hpp @@ -0,0 +1,108 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include + +#include + +using device::SerialConfig::ByteSize; +using device::SerialConfig::Parity; +using device::SerialConfig::StopBits; +using device::SerialConfig::FlowControl; + +namespace device +{ + +class SerialImpl +{ +public: + + SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, + FlowControl flowcontrol); + virtual ~SerialImpl(); + + bool open(); + bool isOpen() const; + + bool close(); + + ssize_t read(uint8_t *buffer, size_t buffer_size); + ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); + + ssize_t write(const void *buffer, size_t buffer_size); + + const char *getPort() const; + bool setPort(const char *port); + + uint32_t getBaudrate() const; + bool setBaudrate(uint32_t baudrate); + + ByteSize getBytesize() const; + bool setBytesize(ByteSize bytesize); + + Parity getParity() const; + bool setParity(Parity parity); + + StopBits getStopbits() const; + bool setStopbits(StopBits stopbits); + + FlowControl getFlowcontrol() const; + bool setFlowcontrol(FlowControl flowcontrol); + +private: + + int _serial_fd{-1}; + + bool _open{false}; + + char _port[32] {}; + + uint32_t _baudrate{0}; + + ByteSize _bytesize{ByteSize::EightBits}; + Parity _parity{Parity::None}; + StopBits _stopbits{StopBits::One}; + FlowControl _flowcontrol{FlowControl::Disabled}; + + bool validateBaudrate(uint32_t baudrate); + + // Mutex used to lock the read functions + //pthread_mutex_t read_mutex; + + // Mutex used to lock the write functions + //pthread_mutex_t write_mutex; +}; + +} // namespace device diff --git a/platforms/qurt/src/px4/CMakeLists.txt b/platforms/qurt/src/px4/CMakeLists.txt index e685b8d42acf..8a25322755a9 100644 --- a/platforms/qurt/src/px4/CMakeLists.txt +++ b/platforms/qurt/src/px4/CMakeLists.txt @@ -38,6 +38,7 @@ set(QURT_LAYER_SRCS px4_qurt_impl.cpp main.cpp qurt_log.cpp + SerialImpl.cpp ) add_library(px4_layer diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp new file mode 100644 index 000000000000..ec0fb73fce3a --- /dev/null +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -0,0 +1,326 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include // strncpy +#include +#include +#include + +namespace device +{ + +SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, + FlowControl flowcontrol) : + _baudrate(baudrate), + _bytesize(bytesize), + _parity(parity), + _stopbits(stopbits), + _flowcontrol(flowcontrol) +{ + if (port) { + strncpy(_port, port, sizeof(_port) - 1); + _port[sizeof(_port) - 1] = '\0'; + + } else { + _port[0] = 0; + } +} + +SerialImpl::~SerialImpl() +{ + if (isOpen()) { + close(); + } +} + +bool SerialImpl::validateBaudrate(uint32_t baudrate) +{ + if ((baudrate != 9600) && + (baudrate != 38400) && + (baudrate != 57600) && + (baudrate != 115200) && + (baudrate != 230400) && + (baudrate != 250000) && + (baudrate != 420000) && + (baudrate != 460800) && + (baudrate != 921600) && + (baudrate != 1000000) && + (baudrate != 1843200) && + (baudrate != 2000000)) { + return false; + } + + return true; +} + +bool SerialImpl::open() +{ + // There's no harm in calling open multiple times on the same port. + // In fact, that's the only way to change the baudrate + + _open = false; + _serial_fd = -1; + + if (! validateBaudrate(_baudrate)) { + PX4_ERR("Invalid baudrate: %u", _baudrate); + return false; + } + + if (_bytesize != ByteSize::EightBits) { + PX4_ERR("Qurt platform only supports ByteSize::EightBits"); + return false; + } + + if (_parity != Parity::None) { + PX4_ERR("Qurt platform only supports Parity::None"); + return false; + } + + if (_stopbits != StopBits::One) { + PX4_ERR("Qurt platform only supports StopBits::One"); + return false; + } + + if (_flowcontrol != FlowControl::Disabled) { + PX4_ERR("Qurt platform only supports FlowControl::Disabled"); + return false; + } + + // qurt_uart_open will check validity of port and baudrate + int serial_fd = qurt_uart_open(_port, _baudrate); + + if (serial_fd < 0) { + PX4_ERR("failed to open %s, fd returned: %d", _port, serial_fd); + return false; + + } else { + PX4_INFO("Successfully opened UART %s with baudrate %u", _port, _baudrate); + } + + _serial_fd = serial_fd; + _open = true; + + return _open; +} + +bool SerialImpl::isOpen() const +{ + return _open; +} + +bool SerialImpl::close() +{ + // No close defined for qurt uart yet + // if (_serial_fd >= 0) { + // qurt_uart_close(_serial_fd); + // } + + _serial_fd = -1; + _open = false; + + return true; +} + +ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) +{ + if (!_open) { + PX4_ERR("Cannot read from serial device until it has been opened"); + return -1; + } + + int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 500); + + if (ret_read < 0) { + PX4_DEBUG("%s read error %d", _port, ret_read); + + } + + return ret_read; +} + +ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +{ + if (!_open) { + PX4_ERR("Cannot readAtLeast from serial device until it has been opened"); + return -1; + } + + if (buffer_size < character_count) { + PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__); + return -1; + } + + const hrt_abstime start_time_us = hrt_absolute_time(); + int total_bytes_read = 0; + + while (total_bytes_read < (int) character_count) { + + if (timeout_us > 0) { + const uint64_t elapsed_us = hrt_elapsed_time(&start_time_us); + + if (elapsed_us >= timeout_us) { + // If there was a partial read but not enough to satisfy the minimum then they will be lost + // but this really should never happen when everything is working normally. + // PX4_WARN("%s timeout %d bytes read (%llu us elapsed)", __FUNCTION__, total_bytes_read, elapsed_us); + // Or, instead of returning an error, should we return the number of bytes read (assuming it is greater than zero)? + return total_bytes_read; + } + } + + int current_bytes_read = read(&buffer[total_bytes_read], buffer_size - total_bytes_read); + + if (current_bytes_read < 0) { + // Again, if there was a partial read but not enough to satisfy the minimum then they will be lost + // but this really should never happen when everything is working normally. + PX4_ERR("%s failed to read uart", __FUNCTION__); + // Or, instead of returning an error, should we return the number of bytes read (assuming it is greater than zero)? + return -1; + } + + // Current bytes read could be zero + total_bytes_read += current_bytes_read; + + // If we have at least reached our desired minimum number of characters + // then we can return now + if (total_bytes_read >= (int) character_count) { + return total_bytes_read; + } + + // Wait a set amount of time before trying again or the remaining time + // until the timeout if we are getting close + const uint64_t elapsed_us = hrt_elapsed_time(&start_time_us); + int64_t time_until_timeout = timeout_us - elapsed_us; + uint64_t time_to_sleep = 5000; + + if ((time_until_timeout >= 0) && + (time_until_timeout < (int64_t) time_to_sleep)) { + time_to_sleep = time_until_timeout; + } + + px4_usleep(time_to_sleep); + } + + return -1; +} + +ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) +{ + if (!_open) { + PX4_ERR("Cannot write to serial device until it has been opened"); + return -1; + } + + int ret_write = qurt_uart_write(_serial_fd, (const char *) buffer, buffer_size); + + if (ret_write < 0) { + PX4_ERR("%s write error %d", _port, ret_write); + + } + + return ret_write; +} + +const char *SerialImpl::getPort() const +{ + return _port; +} + +uint32_t SerialImpl::getBaudrate() const +{ + return _baudrate; +} + +bool SerialImpl::setBaudrate(uint32_t baudrate) +{ + if (! validateBaudrate(baudrate)) { + PX4_ERR("Invalid baudrate: %u", baudrate); + return false; + } + + // check if already configured + if (baudrate == _baudrate) { + return true; + } + + _baudrate = baudrate; + + // process baud rate change now if port is already open + if (_open) { + return open(); + } + + return true; +} + +ByteSize SerialImpl::getBytesize() const +{ + return _bytesize; +} + +bool SerialImpl::setBytesize(ByteSize bytesize) +{ + return bytesize == ByteSize::EightBits; +} + +Parity SerialImpl::getParity() const +{ + return _parity; +} + +bool SerialImpl::setParity(Parity parity) +{ + return parity == Parity::None; +} + +StopBits SerialImpl::getStopbits() const +{ + return _stopbits; +} + +bool SerialImpl::setStopbits(StopBits stopbits) +{ + return stopbits == StopBits::One; +} + +FlowControl SerialImpl::getFlowcontrol() const +{ + return _flowcontrol; +} + +bool SerialImpl::setFlowcontrol(FlowControl flowcontrol) +{ + return flowcontrol == FlowControl::Disabled; +} + +} // namespace device diff --git a/platforms/qurt/src/px4/drv_hrt.cpp b/platforms/qurt/src/px4/drv_hrt.cpp index 8bb9546a01db..2ef152083249 100644 --- a/platforms/qurt/src/px4/drv_hrt.cpp +++ b/platforms/qurt/src/px4/drv_hrt.cpp @@ -81,7 +81,7 @@ static void hrt_unlock() px4_sem_post(&_hrt_lock); } -int px4_clock_settime(clockid_t clk_id, struct timespec *tp) +int px4_clock_settime(clockid_t clk_id, const struct timespec *tp) { return 0; } diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index fcbd5a0c8384..766be323d719 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -45,7 +45,6 @@ #include #endif -#include #include #include @@ -57,6 +56,8 @@ #include #include #include +#include +#include #include #include #include @@ -81,6 +82,7 @@ #include #endif /* __PX4_LINUX */ +using namespace device; using namespace time_literals; #define TIMEOUT_1HZ 1300 //!< Timeout time in mS, 1000 mS (1Hz) + 300 mS delta for error @@ -169,7 +171,10 @@ class GPS : public ModuleBase, public device::Device void reset_if_scheduled(); private: - int _serial_fd{-1}; ///< serial interface to GPS +#ifdef __PX4_LINUX + int _spi_fd {-1}; ///< SPI interface to GPS +#endif + Serial *_uart = nullptr; ///< UART interface to GPS unsigned _baudrate{0}; ///< current baudrate const unsigned _configured_baudrate{0}; ///< configured baudrate (0=auto-detect) char _port[20] {}; ///< device / serial port path @@ -329,8 +334,11 @@ GPS::GPS(const char *path, gps_driver_mode_t mode, GPSHelper::Interface interfac char c = _port[strlen(_port) - 1]; // last digit of path (eg /dev/ttyS2) set_device_bus(c - 48); // sub 48 to convert char to integer +#ifdef __PX4_LINUX + } else if (_interface == GPSHelper::Interface::SPI) { set_device_bus_type(device::Device::DeviceBusType::DeviceBusType_SPI); +#endif } if (_mode == gps_driver_mode_t::None) { @@ -403,10 +411,23 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user) return num_read; } - case GPSCallbackType::writeDeviceData: - gps->dumpGpsData((uint8_t *)data1, (size_t)data2, gps_dump_comm_mode_t::Full, true); + case GPSCallbackType::writeDeviceData: { + gps->dumpGpsData((uint8_t *)data1, (size_t)data2, gps_dump_comm_mode_t::Full, true); + + int ret = 0; + + if (gps->_uart) { + ret = gps->_uart->write((void *) data1, (size_t) data2); + +#ifdef __PX4_LINUX + + } else if (gps->_spi_fd >= 0) { + ret = ::write(gps->_spi_fd, data1, (size_t)data2); +#endif + } - return ::write(gps->_serial_fd, data1, (size_t)data2); + return ret; + } case GPSCallbackType::setBaudrate: return gps->setBaudrate(data2); @@ -449,72 +470,64 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user) int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout) { + int ret = 0; + const unsigned character_count = 32; // minimum bytes that we want to read + const int max_timeout = 50; + int timeout_adjusted = math::min(max_timeout, timeout); + handleInjectDataTopic(); -#if !defined(__PX4_QURT) + if ((_interface == GPSHelper::Interface::UART) && (_uart)) { + ret = _uart->readAtLeast(buf, buf_length, character_count, timeout_adjusted); - /* For non QURT, use the usual polling. */ +// SPI is only supported on LInux +#if defined(__PX4_LINUX) - //Poll only for the serial data. In the same thread we also need to handle orb messages, - //so ideally we would poll on both, the serial fd and orb subscription. Unfortunately the - //two pollings use different underlying mechanisms (at least under posix), which makes this - //impossible. Instead we limit the maximum polling interval and regularly check for new orb - //messages. - //FIXME: add a unified poll() API - const int max_timeout = 50; + } else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) { - pollfd fds[1]; - fds[0].fd = _serial_fd; - fds[0].events = POLLIN; - - int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), math::min(max_timeout, timeout)); - - if (ret > 0) { - /* if we have new data from GPS, go handle it */ - if (fds[0].revents & POLLIN) { - /* - * We are here because poll says there is some data, so this - * won't block even on a blocking device. But don't read immediately - * by 1-2 bytes, wait for some more data to save expensive read() calls. - * If we have all requested data available, read it without waiting. - * If more bytes are available, we'll go back to poll() again. - */ - const unsigned character_count = 32; // minimum bytes that we want to read - unsigned baudrate = _baudrate == 0 ? 115200 : _baudrate; - const unsigned sleeptime = character_count * 1000000 / (baudrate / 10); + //Poll only for the SPI data. In the same thread we also need to handle orb messages, + //so ideally we would poll on both, the SPI fd and orb subscription. Unfortunately the + //two pollings use different underlying mechanisms (at least under posix), which makes this + //impossible. Instead we limit the maximum polling interval and regularly check for new orb + //messages. + //FIXME: add a unified poll() API -#ifdef __PX4_NUTTX - int err = 0; - int bytes_available = 0; - err = ::ioctl(_serial_fd, FIONREAD, (unsigned long)&bytes_available); + pollfd fds[1]; + fds[0].fd = _spi_fd; + fds[0].events = POLLIN; + + ret = poll(fds, sizeof(fds) / sizeof(fds[0]), timeout_adjusted); + + if (ret > 0) { + /* if we have new data from GPS, go handle it */ + if (fds[0].revents & POLLIN) { + /* + * We are here because poll says there is some data, so this + * won't block even on a blocking device. But don't read immediately + * by 1-2 bytes, wait for some more data to save expensive read() calls. + * If we have all requested data available, read it without waiting. + * If more bytes are available, we'll go back to poll() again. + */ + unsigned baudrate = _baudrate == 0 ? 115200 : _baudrate; + const unsigned sleeptime = character_count * 1000000 / (baudrate / 10); - if (err != 0 || bytes_available < (int)character_count) { px4_usleep(sleeptime); - } -#else - px4_usleep(sleeptime); -#endif + ret = ::read(_spi_fd, buf, buf_length); - ret = ::read(_serial_fd, buf, buf_length); + if (ret > 0) { + _num_bytes_read += ret; + } - if (ret > 0) { - _num_bytes_read += ret; + } else { + ret = -1; } - - } else { - ret = -1; } + +#endif } return ret; - -#else - /* For QURT, just use read for now, since this doesn't block, we need to slow it down - * just a bit. */ - px4_usleep(10000); - return ::read(_serial_fd, buf, buf_length); -#endif } void GPS::handleInjectDataTopic() @@ -583,105 +596,38 @@ bool GPS::injectData(uint8_t *data, size_t len) { dumpGpsData(data, len, gps_dump_comm_mode_t::Full, true); - size_t written = ::write(_serial_fd, data, len); - ::fsync(_serial_fd); - return written == len; -} - -int GPS::setBaudrate(unsigned baud) -{ - /* process baud rate */ - int speed; - - switch (baud) { - case 9600: speed = B9600; break; - - case 19200: speed = B19200; break; - - case 38400: speed = B38400; break; - - case 57600: speed = B57600; break; - - case 115200: speed = B115200; break; - - case 230400: speed = B230400; break; + size_t written = 0; -#ifndef B460800 -#define B460800 460800 -#endif + if ((_interface == GPSHelper::Interface::UART) && (_uart)) { + written = _uart->write((const void *) data, len); - case 460800: speed = B460800; break; +#ifdef __PX4_LINUX -#ifndef B921600 -#define B921600 921600 + } else if (_interface == GPSHelper::Interface::SPI) { + written = ::write(_spi_fd, data, len); + ::fsync(_spi_fd); #endif - - case 921600: speed = B921600; break; - - default: - PX4_ERR("ERR: unknown baudrate: %d", baud); - return -EINVAL; } - struct termios uart_config; - - int termios_state; - - /* fill the struct for the new configuration */ - tcgetattr(_serial_fd, &uart_config); - - /* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */ - - // - // Input flags - Turn off input processing - // - // convert break to null byte, no CR to NL translation, - // no NL to CR translation, don't mark parity errors or breaks - // no input parity check, don't strip high bit off, - // no XON/XOFF software flow control - // - uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | - INLCR | PARMRK | INPCK | ISTRIP | IXON); - // - // Output flags - Turn off output processing - // - // no CR to NL translation, no NL to CR-NL translation, - // no NL to CR translation, no column 0 CR suppression, - // no Ctrl-D suppression, no fill characters, no case mapping, - // no local output processing - // - // config.c_oflag &= ~(OCRNL | ONLCR | ONLRET | - // ONOCR | ONOEOT| OFILL | OLCUC | OPOST); - uart_config.c_oflag = 0; - - // - // No line processing - // - // echo off, echo newline off, canonical mode off, - // extended input processing off, signal chars off - // - uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG); - - /* no parity, one stop bit, disable flow control */ - uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS); - - /* set baud rate */ - if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { - GPS_ERR("ERR: %d (cfsetispeed)", termios_state); - return -1; - } + return written == len; +} - if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { - GPS_ERR("ERR: %d (cfsetospeed)", termios_state); - return -1; - } +int GPS::setBaudrate(unsigned baud) +{ + if (_interface == GPSHelper::Interface::UART) { + if ((_uart) && (_uart->setBaudrate(baud))) { + return 0; + } + +#ifdef __PX4_LINUX - if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) { - GPS_ERR("ERR: %d (tcsetattr)", termios_state); - return -1; + } else if (_interface == GPSHelper::Interface::SPI) { + // Can't set the baudrate on a SPI port but just return a success + return 0; +#endif } - return 0; + return -1; } void GPS::initializeCommunicationDump() @@ -840,31 +786,58 @@ GPS::run() _helper = nullptr; } - if (_serial_fd < 0) { - /* open the serial port */ - _serial_fd = ::open(_port, O_RDWR | O_NOCTTY); + if ((_interface == GPSHelper::Interface::UART) && (_uart == nullptr)) { + + // Create the UART port instance + _uart = new Serial(_port); + + if (_uart == nullptr) { + PX4_ERR("Error creating serial device %s", _port); + px4_sleep(1); + continue; + } + } + + if ((_interface == GPSHelper::Interface::UART) && (! _uart->isOpen())) { + // Configure the desired baudrate if one was specified by the user. + // Otherwise the default baudrate will be used. + if (_configured_baudrate) { + if (! _uart->setBaudrate(_configured_baudrate)) { + PX4_ERR("Error setting baudrate to %u on %s", _configured_baudrate, _port); + px4_sleep(1); + continue; + } + } - if (_serial_fd < 0) { - PX4_ERR("failed to open %s err: %d", _port, errno); + // Open the UART. If this is successful then the UART is ready to use. + if (! _uart->open()) { + PX4_ERR("Error opening serial device %s", _port); px4_sleep(1); continue; } #ifdef __PX4_LINUX - if (_interface == GPSHelper::Interface::SPI) { - int spi_speed = 1000000; // make sure the bus speed is not too high (required on RPi) - int status_value = ::ioctl(_serial_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed); + } else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd < 0)) { + _spi_fd = ::open(_port, O_RDWR | O_NOCTTY); - if (status_value < 0) { - PX4_ERR("SPI_IOC_WR_MAX_SPEED_HZ failed for %s (%d)", _port, errno); - } + if (_spi_fd < 0) { + PX4_ERR("failed to open SPI port %s err: %d", _port, errno); + px4_sleep(1); + continue; + } - status_value = ::ioctl(_serial_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed); + int spi_speed = 1000000; // make sure the bus speed is not too high (required on RPi) + int status_value = ::ioctl(_spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed); - if (status_value < 0) { - PX4_ERR("SPI_IOC_RD_MAX_SPEED_HZ failed for %s (%d)", _port, errno); - } + if (status_value < 0) { + PX4_ERR("SPI_IOC_WR_MAX_SPEED_HZ failed for %s (%d)", _port, errno); + } + + status_value = ::ioctl(_spi_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed); + + if (status_value < 0) { + PX4_ERR("SPI_IOC_RD_MAX_SPEED_HZ failed for %s (%d)", _port, errno); } #endif /* __PX4_LINUX */ @@ -1056,9 +1029,17 @@ GPS::run() } } - if (_serial_fd >= 0) { - ::close(_serial_fd); - _serial_fd = -1; + if ((_interface == GPSHelper::Interface::UART) && (_uart)) { + (void) _uart->close(); + delete _uart; + _uart = nullptr; + +#ifdef __PX4_LINUX + + } else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) { + ::close(_spi_fd); + _spi_fd = -1; +#endif } if (_mode_auto) { @@ -1477,12 +1458,12 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) break; case 'i': - if (!strcmp(myoptarg, "spi")) { - interface = GPSHelper::Interface::SPI; - - } else if (!strcmp(myoptarg, "uart")) { + if (!strcmp(myoptarg, "uart")) { interface = GPSHelper::Interface::UART; - +#ifdef __PX4_LINUX + } else if (!strcmp(myoptarg, "spi")) { + interface = GPSHelper::Interface::SPI; +#endif } else { PX4_ERR("unknown interface: %s", myoptarg); error_flag = true; @@ -1490,12 +1471,12 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) break; case 'j': - if (!strcmp(myoptarg, "spi")) { - interface_secondary = GPSHelper::Interface::SPI; - - } else if (!strcmp(myoptarg, "uart")) { + if (!strcmp(myoptarg, "uart")) { interface_secondary = GPSHelper::Interface::UART; - +#ifdef __PX4_LINUX + } else if (!strcmp(myoptarg, "spi")) { + interface_secondary = GPSHelper::Interface::SPI; +#endif } else { PX4_ERR("unknown interface for secondary: %s", myoptarg); error_flag = true; From c024ea396a6065e1281b82877b0b7ba5f94aa41d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 22 Mar 2024 15:17:03 -0400 Subject: [PATCH 029/652] boards/px4/fmu-v5x: remove legacy rover_pos_control to reduce flash usage --- boards/px4/fmu-v5x/default.px4board | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index a4c2baf0dc37..2bede96763c0 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -81,7 +81,6 @@ CONFIG_MODULES_NAVIGATOR=y CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y CONFIG_MODULES_PAYLOAD_DELIVERER=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y From 4a553938fb6bc7a853b83d175544fff26b404f68 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Fri, 22 Mar 2024 12:24:51 -0700 Subject: [PATCH 030/652] VOXL2: HRT updates for synchronization with Qurt time (#22881) - Added offset to Posix hrt time to account for synchronization with Qurt hrt time - Added new Kconfig to configure synchronization of HRT timestamps on VOXL2 - Moved voxl2 libfc sensor library submodule from muorb module to boards directory - Added check to make sure hrt_elapsed_time can never be negative --- .gitmodules | 2 +- Tools/astyle/files_to_check_code_style.sh | 2 +- boards/modalai/voxl2/cmake/init.cmake | 34 +++++++++++++++++++ .../modalai/voxl2/cmake/link_libraries.cmake | 2 +- .../modalai/voxl2}/libfc-sensor-api | 0 boards/modalai/voxl2/scripts/build-deps.sh | 5 ++- platforms/posix/src/px4/common/drv_hrt.cpp | 29 ++++++++++++++++ src/drivers/drv_hrt.h | 11 +++++- src/modules/muorb/apps/CMakeLists.txt | 2 +- src/modules/muorb/apps/Kconfig | 8 +++++ 10 files changed, 87 insertions(+), 8 deletions(-) create mode 100644 boards/modalai/voxl2/cmake/init.cmake rename {src/modules/muorb/apps => boards/modalai/voxl2}/libfc-sensor-api (100%) diff --git a/.gitmodules b/.gitmodules index e91cf2b63a14..e443da19a290 100644 --- a/.gitmodules +++ b/.gitmodules @@ -81,5 +81,5 @@ url = https://github.com/PX4/PX4-gazebo-models.git branch = main [submodule "boards/modalai/voxl2/libfc-sensor-api"] - path = src/modules/muorb/apps/libfc-sensor-api + path = boards/modalai/voxl2/libfc-sensor-api url = https://gitlab.com/voxl-public/voxl-sdk/core-libs/libfc-sensor-api.git diff --git a/Tools/astyle/files_to_check_code_style.sh b/Tools/astyle/files_to_check_code_style.sh index e0cc5693edb3..734d6f5323d5 100755 --- a/Tools/astyle/files_to_check_code_style.sh +++ b/Tools/astyle/files_to_check_code_style.sh @@ -30,5 +30,5 @@ exec find boards msg src platforms test \ -path src/lib/cdrstream/cyclonedds -prune -o \ -path src/lib/cdrstream/rosidl -prune -o \ -path src/modules/zenoh/zenoh-pico -prune -o \ - -path src/modules/muorb/apps/libfc-sensor-api -prune -o \ + -path boards/modalai/voxl2/libfc-sensor-api -prune -o \ -type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN diff --git a/boards/modalai/voxl2/cmake/init.cmake b/boards/modalai/voxl2/cmake/init.cmake new file mode 100644 index 000000000000..e5a4daad5f8b --- /dev/null +++ b/boards/modalai/voxl2/cmake/init.cmake @@ -0,0 +1,34 @@ +############################################################################ +# +# Copyright (c) 2024 ModalAI, Inc. 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_directories(${PX4_BOARD_DIR}/libfc-sensor-api/inc) \ No newline at end of file diff --git a/boards/modalai/voxl2/cmake/link_libraries.cmake b/boards/modalai/voxl2/cmake/link_libraries.cmake index f250f52e211b..e0b09beb7038 100644 --- a/boards/modalai/voxl2/cmake/link_libraries.cmake +++ b/boards/modalai/voxl2/cmake/link_libraries.cmake @@ -1,7 +1,7 @@ # Link against the public stub version of the proprietary fc sensor library target_link_libraries(px4 PRIVATE - ${PX4_SOURCE_DIR}/src//modules/muorb/apps/libfc-sensor-api/build/libfc_sensor.so + ${PX4_BOARD_DIR}/libfc-sensor-api/build/libfc_sensor.so px4_layer ${module_libraries} ) diff --git a/src/modules/muorb/apps/libfc-sensor-api b/boards/modalai/voxl2/libfc-sensor-api similarity index 100% rename from src/modules/muorb/apps/libfc-sensor-api rename to boards/modalai/voxl2/libfc-sensor-api diff --git a/boards/modalai/voxl2/scripts/build-deps.sh b/boards/modalai/voxl2/scripts/build-deps.sh index b76cd0d7fa79..fe7f85486888 100755 --- a/boards/modalai/voxl2/scripts/build-deps.sh +++ b/boards/modalai/voxl2/scripts/build-deps.sh @@ -1,10 +1,9 @@ #!/bin/bash -cd src/modules/muorb/apps/libfc-sensor-api +cd boards/modalai/voxl2/libfc-sensor-api rm -fR build mkdir build cd build CC=/home/4.1.0.4/tools/linaro64/bin/aarch64-linux-gnu-gcc cmake .. make -cd ../../../../../.. - +cd ../../../../.. diff --git a/platforms/posix/src/px4/common/drv_hrt.cpp b/platforms/posix/src/px4/common/drv_hrt.cpp index 9634511bf3fc..b510229bc0cf 100644 --- a/platforms/posix/src/px4/common/drv_hrt.cpp +++ b/platforms/posix/src/px4/common/drv_hrt.cpp @@ -51,6 +51,11 @@ #include #include "hrt_work.h" +// Voxl2 board specific API definitions to get time offset +#if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP) +#include "fc_sensor.h" +#endif + #if defined(ENABLE_LOCKSTEP_SCHEDULER) #include static LockstepScheduler lockstep_scheduler {true}; @@ -107,6 +112,29 @@ hrt_abstime hrt_absolute_time() #else // defined(ENABLE_LOCKSTEP_SCHEDULER) struct timespec ts; px4_clock_gettime(CLOCK_MONOTONIC, &ts); + +# if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP) + hrt_abstime temp_abstime = ts_to_abstime(&ts); + int apps_time_offset = fc_sensor_get_time_offset(); + + if (apps_time_offset < 0) { + hrt_abstime temp_offset = -apps_time_offset; + + if (temp_offset >= temp_abstime) { + temp_abstime = 0; + + } else { + temp_abstime -= temp_offset; + } + + } else { + temp_abstime += (hrt_abstime) apps_time_offset; + } + + ts.tv_sec = temp_abstime / 1000000; + ts.tv_nsec = (temp_abstime % 1000000) * 1000; +# endif // defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP) + return ts_to_abstime(&ts); #endif // defined(ENABLE_LOCKSTEP_SCHEDULER) } @@ -449,6 +477,7 @@ int px4_clock_gettime(clockid_t clk_id, struct timespec *tp) #endif // defined(ENABLE_LOCKSTEP_SCHEDULER) return system_clock_gettime(clk_id, tp); + } #if defined(ENABLE_LOCKSTEP_SCHEDULER) diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h index 3e295abfc949..bb62da0189c3 100644 --- a/src/drivers/drv_hrt.h +++ b/src/drivers/drv_hrt.h @@ -162,7 +162,16 @@ static inline void abstime_to_ts(struct timespec *ts, hrt_abstime abstime) */ static inline hrt_abstime hrt_elapsed_time(const hrt_abstime *then) { - return hrt_absolute_time() - *then; + hrt_abstime now = hrt_absolute_time(); + + // Cannot allow a negative elapsed time as this would appear + // to be a huge positive elapsed time when represented as an + // unsigned value! + if (*then > now) { + return 0; + } + + return now - *then; } /** diff --git a/src/modules/muorb/apps/CMakeLists.txt b/src/modules/muorb/apps/CMakeLists.txt index 5a608bec5301..532ada62413b 100644 --- a/src/modules/muorb/apps/CMakeLists.txt +++ b/src/modules/muorb/apps/CMakeLists.txt @@ -39,7 +39,7 @@ px4_add_module( INCLUDES ../test ../aggregator - libfc-sensor-api/inc + ${PX4_BOARD_DIR}/libfc-sensor-api/inc SRCS uORBAppsProtobufChannel.cpp muorb_main.cpp diff --git a/src/modules/muorb/apps/Kconfig b/src/modules/muorb/apps/Kconfig index 21969d591d13..f0afac8b6204 100644 --- a/src/modules/muorb/apps/Kconfig +++ b/src/modules/muorb/apps/Kconfig @@ -4,3 +4,11 @@ menuconfig MODULES_MUORB_APPS depends on PLATFORM_POSIX ---help--- Enable support for muorb apps + + + config MUORB_APPS_SYNC_TIMESTAMP + bool "Sync timestamp with external processor" + depends on MODULES_MUORB_APPS + default y + help + causes HRT timestamp to use an externally calculated offset for synchronization From bcbae86b9f869414866238a939232c5771e0f695 Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Fri, 22 Mar 2024 14:53:49 +0100 Subject: [PATCH 031/652] code: add more style options in `.editorconfig` --- .editorconfig | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/.editorconfig b/.editorconfig index 87496c115e9e..50a87fd83923 100644 --- a/.editorconfig +++ b/.editorconfig @@ -1,6 +1,14 @@ root = true -[*.{c,cpp,cc,h,hpp}] +[*] +insert_final_newline = false + +[{*.{c,cpp,cc,h,hpp},CMakeLists.txt,Kconfig}] indent_style = tab tab_width = 8 +# Not in the official standard, but supported by many editors max_line_length = 120 + +[*.yaml] +indent_style = space +indent_size = 2 From 999a71c4ddc53080875272fcef2c2f0c184d2777 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 26 Feb 2024 11:38:48 +0100 Subject: [PATCH 032/652] px4io: don't output on disabled PWM pins Same logic as on the FMU PWM updateOutputs() in PWMOut.cpp --- src/drivers/px4io/px4io.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index bd6b5d1f3192..e98a9c837d55 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -364,6 +364,13 @@ PX4IO::~PX4IO() bool PX4IO::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs, unsigned num_control_groups_updated) { + for (size_t i = 0; i < num_outputs; i++) { + if (!_mixing_output.isFunctionSet(i)) { + // do not run any signal on disabled channels + outputs[i] = 0; + } + } + if (!_test_fmu_fail) { /* output to the servos */ io_reg_set(PX4IO_PAGE_DIRECT_PWM, 0, outputs, num_outputs); From 1096384a38fa3c0bc5c991d6f7a9145bd8550f98 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 26 Feb 2024 12:00:55 +0100 Subject: [PATCH 033/652] px4iofirmware: don't switch to disarmed or failsafe value on disabled PWM outputs If the output is set to 0 then the FMU had this channel disabled/no function mapped to it. In that case we do not want to suddenly start outputing failsafe or disarmed signals. --- .../ark/fmu-v6x/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../extras/cubepilot_io-v2_default.bin | Bin 39920 -> 39928 bytes .../extras/cubepilot_io-v2_default.bin | Bin 39920 -> 39928 bytes .../durandal-v1/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../pix32v5/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../mro/x21-777/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes boards/mro/x21/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../px4/fmu-v2/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../px4/fmu-v3/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../fmu-v4pro/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../px4/fmu-v5/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../px4/fmu-v5x/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../px4/fmu-v6c/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes .../px4/fmu-v6x/extras/px4_io-v2_default.bin | Bin 40140 -> 40148 bytes src/modules/px4iofirmware/mixer.cpp | 12 ++++++++---- 15 files changed, 8 insertions(+), 4 deletions(-) diff --git a/boards/ark/fmu-v6x/extras/px4_io-v2_default.bin b/boards/ark/fmu-v6x/extras/px4_io-v2_default.bin index 957f0f13a12e8eb8a7979955f29ad98d82433933..5a0796406fc11c3476448b5284c5c519cb6a711d 100755 GIT binary patch delta 2593 zcmYjT3se;675?u&hnKLfl+_Kg%L;Zh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBh-2myJi92Aw81ym|lJ)#s570rr@ z?o|=dDq8p8K@^yBC|VX>b+zs8o}x>A?XK-<*GRjq1ELv-B>NBD=A7?-|NqT*@0~mM zzcUfKWn#CiJr5w7=7Rwi@wIRrAf3iB3$d+XA|ajcU>K!m-f6;?Au14i`J1laF*0(7 z{?YSi@a2!c^HKp`eC?EIIo#uWd^dyQ-UY&j^Tw%afLV00HUYNK-)kG7n%Dm(K>-c? zTKz46JU-O0-VIXt;}MYzq|iH2ci|j=$f$Kyw0%U_i+tPfvKY_#mk29?cp>wi?;2cT zJ~bw4u}w{U2=n>Cq&rGDO@CYx3Exv~n!kY=^9msP3rP-Jpi?HS5lKLE%K6l#qC7^f zpWHH;GQtA7DlOD?x2V)Lm>A&-txsDVkuy4}NvUh<4BIv7l&WbD>bvbk_`xm{4vKCK zGNDi;!jO{){o^2PqLA(f1=K&?2qv159tuiYnI56?a|{d;LtQ-Ew>v)WJ_y@sPx>YI z+hbuB#1K{v!gX4f5e=JZb4DN>rgt;+uHWNAM_8hJLx(b=UA@i{Ha30|nL;Bn{otR} zoEZr%v@)|)<9yp>Zc4s2CPu?*b>LJdEj`4Aw34lE6YBI;b~2ieqbnHe{< zblFevHO*dbf_T1pxjVo{+Lj#&+5Eq<>i{zO(i|=L<%ot7H(i1Nj3Ez%Ow0f?b|N#= z<`o)vmtJ47QuSO^a2D>dNTQlt-2VZ>ziIGFbMSvf7qg!8&2vct!NZ|6`{sG|lDRbTurZuZ>VjU)|*26-&c6ALFlNDP}TDqoY&avdDo%aW2#d}_%7ahkY1jbW#GXEHP71zDopy)Hf; z+tGd!)N0w0q8{0`*|)FIQbDWo{Hr%5tIJz0N4a0rR?GXzzJ0e|#j4fi7Y-ibnmV&O zU?$riQxVlJuWC3oXyY`7|zHqt71&{oJGjBJpzAY8-JUh0bBSFLIwj(&^6BosR7JF+adfp#1Sejh^ zG{DXX@G*U9C1EXJg<=s9;jIXIrF7Hj4qKE%WoooaMI;@LRWz<3(sTVe!dkGLZlkiD zRuyc5CG=&1W_H&HgcZBw+&i2P_tw_wEbq8j@?A-5y!??4Z&-|dYx`?o2se*wPYkp8 zEgG_ly+n9O7ZhH{qcvLS4|P;il!$SDQKI}U&OzIYeCdrMIlWg@q6lv$YzseoZ6u&$ z?RzH3rB~l8c9}aC#f{k*>R0UV*@AsYIK)Z^*FsIj576mX(hU#jKuK}+!~p1s7!=av zoF{j--G?Lk4FOEcxJ@%g!l(452{JZKAgnTi40rE(_Cg`#<`&3vbMr_Lmt&3=y}d|e zPCq(4(gbi1^MBg;OkDcyGcn~TP*ulgL+qrK{+F**`*#_nlRyG5am?j_(gI$!&QPMK zeWhARpifIP)HOlUEFW8gxG^gUI%l01dx6ebmjH5Fxy~rx(g6{)ecklnHP(%SH#uiL zh>u!YnzVrOE(JbbrwzvCoTVoOqabQu7wZ1&;+(dVG;)1ob+$d>%~>*P%R)YboQ7P7 zY_=y4dm|^>ya0t?tvU*Pa0Mr&q0P2{Yiu9cY%=V?y!8XcHz^qayK(3B?PeR8%B>Hle66T7-&P3ceoeeZj^O9Bdk9^XTIZeeeg`SQZR> z>CLi0sHWDkL2%>y-=73o-c@n^)({PwNY5URm1@CS&Uh&nf-yMlZe zc@gq+#0f+_=ATpjHVs&4%(hi3s*NH7Dl6Ku>ahr@=-|7( zwTjp(6{!|E1*aS~A`2dCJ$riABevQ4*sZ#r7U@GrWywG!+27E0|M>3r{l59;&b>GH z&P42%3Ei>|3qUko1qOJ7uZJFhOqwiD#I{Zz4ViqWT<+%i=1IboASw~>@mJK3RJ*21vH?*1QE2n z;5Yb=7A`fy0={{vJHUF{UKkDe{J#qK17z{#%d`+sAR5Xh=~4xd8!R9!#tN`vCaMhD zyxboa(4OT*ntzK*mSgXTB&JE_{v8N+X=srt^s%Ti=~+LEDiZ|8>1Oh?c=wXNJe*Gq zLfS98Wki=n8;c_J*Ih=VOjzzzvN~2K^t)KB@}0njVWoD-1uyzzQ6bdOg>NOpY`*3# z0MO976<1&pO)yp%L$cCcFErfJpH=cB+3o{v+(|dN z4RnW$PWwuiPJa+LL5fTJfC#Ic#L)4J8`D7bmO$7^lP&&+YEyNV{Fyi8iwgJsDJj^F z4v>&GZrdW?;o5in`ii+NwAvC_Q<>#k*~T4Ve|OusiY&jrt1ps#eJjr#c%N;$nBNJr znSq3@ah+|PRw=jX^lS0CH=Mr>i*b2YtSEDbI3^+pSsajs z_&m5WL`qu*A%q`v+P`+fZ1q3{TWB=@p0xZwny^(axReRjMVe-@lBYLH z?vqP6ju>BSF?Yx9wv7ZE7HiF6Y%E8FRuSf6uL(?4D7M4c=UtW37Jzq8pSW{i%)m9N z{%T_)gI+U!Ge{!N-3-SqL4F&l~i9E=y@6kMyYyR3>dU&pM(>oB z)=YGOiKrpLtYkgdQytS-qTdiCKR0gIj*+M-eP%(%m<7VPMUv-Twf7$@1ckz4Q7BfD zx)8}PG{uQiyh(Jy09GDm0o)CN_b%QS7d^Z$ro9hT(|P$BxGoixbl19AMO7z6(!Z>m8CpEJQJ6|v z1`psmOH+~tUfHF@wRG9#;|i9uhM@|h^7Y~FuO{WPpP=*BH`Ww6Qb$gaQF|fs$H@7} z`;pC#tmjjaO^)P|cH|7lqUVQ^Q_=T8PIP2GS0X1ME0E`*uSJf-{B-1K2k4VWK1B5) zIueIqfwU~55$tRRRtxFF4SnztZLSCf zj{dD87qxM!BTAARx*4g{mJ1Olshh2DB zZ>xz;!&g;)tAH=5u}T|o3xAUlg#V|6Nkptc970?|{KVH))j+BSKgsJ5e@5(|M0Bml zhmhYu{z1}+!&qNIj_Fd&@MIf0X5K5uqxhrC$5_UW+7HmwEh~Vh&0Chi4c@V3p&WkY zY#86v(DE@&M zuaBR)&oPVDvt_Kqo+GL{VtOTYoSOD%VIeKuqX$pgut%#Y`G_zFvk5aFH@*iZw$ZLV zRy@xe_h!Qfw0G~kX+6hYB_^2^thP*@onRfcXYuY_H50J#UBYxBtcYI36~r|}JED_6 zd*m1c@6v^hCZ-?1nS>A>)gOJ0wl;2NI5dvDGG0Hic_N{M|0TXY@i|2NVDR diff --git a/boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin b/boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin index 4d29f3a0415562d157333f3a3e4cf7b3dc991db0..b7fcd9dab24cf4eea06e4c40a6eca8b885ade3bf 100755 GIT binary patch delta 2465 zcmXw53se(V8oqxf3B#)rBL`v@Nr=1zgvfE#MJo>-2myJi92Aw81ym|lJ)#s570rr@ z?o|=dDq8p8K@^yBC|VX>b+zs8o}x>A?XK-<*GRjq1ELv-B>NBD=A7?-|NqT*@0~mM zzcUfKWn#CiJr5w7=7Rwi@wIRrAf3iB3$d+XA|ajcU>K!m-f6;?Au14i`J1laF*0(7 z{?YSi@a2!c^HKp`eC?EIIo#uWd^dyQ-UY&j^Tw%afLV00HUYNK-)kG7n%Dm(K>-c? zTKz46JU-O0-VIXt;}MYzq|iH2ci|j=$f$Kyw0%U_i+tPfvKY_#mk29?cp>wi?;2cT zJ~bw4u}w{U2=n>Cq&rGDO@CYx3Exv~n!kY=^9msP3rP-Jpi?HS5lKLE%K6l#qC7^f zpWHH;GQtA7DlOD?x2V)Lm>A&-txsDVkuy4}NvUh<4BIv7l&WbD>bvbk_`xm{4vKCK zGNDi;!jO{){o^2PqLA(f1=K&?2qv159tuiYnI56?a|{d;LtQ-Ew>v)WJ_y@sPx>YI z+hbuB#1K{v!gX4f5e=JZb4DN>rgt;+uHWNAM_8hJLx(b=UA@i{Ha30|nL;Bn{otR} zoEZr%v@)|)<9yp>Zc4s2CPu?*b>LJdEj`4Aw34lE6YBI;b~2ieqbnHe{< zblFevHO*dbf_T1pxjVo{+Lj#&+5Eq<>i{zO(i|=L<%ot7H(i1Nj3Ez%Ow0f?b|N#= z<`o)vmtJ47QuSO^a2D>dNTQlt-2VZ>ziIGFbMSvf7qg!8&2vct!NZ|6`{sG|lDRbTurZuZ>VjU)|*26-&c6ALFlNDP}TDqoY&avdDo%aW2#d}_%7ahkY1jbW#GXEHP71zDopy)Hf; z+tGd!)N0w0q8{0`*|)FIQbDWo{Hr%5tIJz0N4a0rR?GXzzJ0e|#j4fi7Y-ibnmV&O zU?$riQxVlJuWC3oXyY`7|zHqt71&{oJGjBJpzAY8-JUh0bBSFLIwj(&^6BosR7JF+adfp#1Sejh^ zG{DXX@G*U9C1EXJg<=s9;jIXIrF7Hj4qKE%WoooaMI;@LRWz<3(sTVe!dkGLZlkiD zRuyc5CG=&1W_H&HgcZBw+&i2P_tw_wEbq8j@?A-5y!??4Z&-|dYx`?o2se*wPYkp8 zEgG_ly+n9O7ZhH{qcvLS4|P;il!$SDQKI}U&OzIYeCdrMIlWg@q6lv$YzseoZ6u&$ z?RzH3rB~l8c9}aC#f{k*>R0UV*@AsYIK)Z^*FsIj576mX(hU#jKuK}+!~p1s7!=av zoF{j--G?Lk4FOEcxJ@%g!l(452{JZKAgnTi40rE(_Cg`#<`&3vbMr_Lmt&3=y}d|e zPCq(4(gbi1^MBg;OkDcyGcn~TP*ulgL+qrK{+F**`*#_nlRyG5am?j_(gI$!&QPMK zeWhARpifIP)HOlUEFW8gxG^gUI%l01dx6ebmjH5Fxy~rx(g6{)ecklnHP(%SH#uiL zh>u!YnzVrOE(JbbrwzvCoTVoOqabQu7wZ1&;+(dVG;)1ob+$d>%~>*P%R)YboQ7P7 zY_=y4dm|^>ya0t?tvU*Pa0Mr&q0P2{Yiu9cY%=V?y!8XcHz^qayK(3B?PeR8%B>Hle66T7-&P3ceoeeZj^O9Bdk9^XTIZeeeg`SQZR> z>CLi0sHWDkL2%>y-=73o-c@n^)({PwNY5URm1@CS&Uh&nf-yMlZe zc@gq+#0f+_=ATpjHVs&4%(hi3s*NH7Dl6Ku>ahr@=-|7( zwTjp(6{!|E1*aS~A`2dCJ$riABevQ4*sZ#r7U@GrWywG!+27E0|M>3r{l59;&b>GH z&P42%3Ei>|3qUko1qOJ7uZJFhOqwiD#I{Zz4ViqWT<+%i=1IboASw~>@mJK3RJ*21vH?*1QE2n z;5Yb=7A`fy0={{vJHUF{UKkDe{J#qK17z{#%d`+sAR5Xh=~4xd8!R9!#tN`vCaMhD zyxboa(4OT*ntzK*mSgXTB&JE_{v8N+X=srt^s%Ti=~+LEDiZ|8>1Oh?c=wXNJe*Gq zLfS98Wki=n8;c_J*Ih=VOjzzzvN~2K^t)KB@}0njVWoD-1uyzzQ6bdOg>NOpY`*3# z0MO976<1&pO)yp%L$cCcFErfJpH=cB+3o{v+(|dN z4RnW$PWwuiPJa+LL5fTJfC#Ic#L)4J8`D7bmO$7^lP&&+YEyNV{Fyi8iwgJsDJj^F z4v>&GZrdW?;o5in`ii+NwAvC_Q<>#k*~T4Ve|OusiY&jrt1ps#eJjr#c%N;$nBNJr znSq3@ah+|PRw=jX^lS0CH=Mr>i*b2YtSEDbI3^+pSsajs z_&m5WL`qu*A%q`v+P`+fZ1q3{TWB=@p0xZwny^(axReRjMVe-@lBYLH z?vqP6ju>BSF?Yx9wv7ZE7HiF6Y%E8FRuSf6uL(?4D7M4c=UtW37Jzq8pSW{i%)m9N z{%T_)gI+U!Ge{!N-3-SqL4F&l~i9E=y@6kMyYyR3>dU&pM(>oB z)=YGOiKrpLtYkgdQytS-qTdiCKR0gIj*+M-eP%(%m<7VPMUv-Twf7$@1ckz4Q7BfD zx)8}PG{uQiyh(Jy09GDm0o)CN_b%QS7d^Z$ro9hT(|P$BxGoixbl19AMO7z6(!Z>m8CpEJQJ6|v z1`psmOH+~tUfHF@wRG9#;|i9uhM@|h^7Y~FuO{WPpP=*BH`Ww6Qb$gaQF|fs$H@7} z`;pC#tmjjaO^)P|cH|7lqUVQ^Q_=T8PIP2GS0X1ME0E`*uSJf-{B-1K2k4VWK1B5) zIueIqfwU~55$tRRRtxFF4SnztZLSCf zj{dD87qxM!BTAARx*4g{mJ1Olshh2DB zZ>xz;!&g;)tAH=5u}T|o3xAUlg#V|6Nkptc970?|{KVH))j+BSKgsJ5e@5(|M0Bml zhmhYu{z1}+!&qNIj_Fd&@MIf0X5K5uqxhrC$5_UW+7HmwEh~Vh&0Chi4c@V3p&WkY zY#86v(DE@&M zuaBR)&oPVDvt_Kqo+GL{VtOTYoSOD%VIeKuqX$pgut%#Y`G_zFvk5aFH@*iZw$ZLV zRy@xe_h!Qfw0G~kX+6hYB_^2^thP*@onRfcXYuY_H50J#UBYxBtcYI36~r|}JED_6 zd*m1c@6v^hCZ-?1nS>A>)gOJ0wl;2NI5dvDGG0Hic_N{M|0TXY@i|2NVDR diff --git a/boards/holybro/durandal-v1/extras/px4_io-v2_default.bin b/boards/holybro/durandal-v1/extras/px4_io-v2_default.bin index 957f0f13a12e8eb8a7979955f29ad98d82433933..5a0796406fc11c3476448b5284c5c519cb6a711d 100755 GIT binary patch delta 2593 zcmYjT3se;675?u&hnKLfl+_Kg%L;Zh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBhZh7N$~G)XxZuT{!un9jE@gGM=5B1&?gsI|B|9p|s$M8qO$RK{myw5up4=~W! z6eC_UQf`2O4@teC0Z;mPVKih@qdmy7!08uE%*Rt*Vu)KIT#-od(ez^(izQWp$~^wm zc&Zdy=nDH(kLQxc^joV^2&4z>rMA5e-v*7Tp)F#E?-5-?IqG*th%o7uLU<^7)+vN8 z2?Vo51aN_H#dY4OqJ@t=m1;^X-}kFvecHZxOxK6=CSC*K3!0p{1$NPMnc?71?`KBp zmb!ZTiRHCp3pzL&ly%nQOYGz;hM2C=@3ZV)SDX^K~;((DkZqqW%q z9#7DjIM0^|v^6^r$NlTb+QT57h*h(+1G(#!v zUs(k!Y3Zseh^GUqs%CzacDwCbzoK~O3mv!Qkycro;nmZ^9n~m%!F15-65n#0%)h~< zL)^xDM5uKU%bCX-riL~b1O@K2_TV&j;6%60%e~&hE!E`qws7^D#l72X+vxoQf3IJs z>xXu1F?1Di6%-1Cwr@_;m$h)U>}$1!+n8qPI{zY3uP-~f{}9{Iwx|`Nn4W}+xYicV zs8;rx%*FWZ{jMU;K14R_1(SMN>iDZJaVNH;(7HS=R#JFD91{_YEcGZt{qJ@6lj5d6 z2<7`+;w~3NdG|!HS!qkGKShV(-PTx1Ptfcw|LG+@NGZ703GMYbBXXo~KP-{Vfwm&< zt~9$*FZlT$!3y+{$Te574n^%?B0`}9%(GH!B;w~1=em-tYLiPWcFE2~tqB#D_Im0r zH0DMv3}b&LDU2|K2$v)#QtYvC$F6D^+Sd6{NHLUv@cRx6cT@XAZ-i|cD{E$} ztQtG89Wna$BJMlQ&0Z2RWueg?#>R3)Xr`N2`_D0=+c@TQIW1g+_KRL7IKcW6uW6-agfh0Y#^BqiSjmIL$4HHM`vTnIjE(1>x$Qo-2fet{eoS^`miU? z1hB-sAy|28RJ`FJ(KKL1Nh`Jy7;E0M%AB;k!W+d^^d;($KT}i{oNixDAx}0faH79a3 z=EKh9;S!w^(JOPym}0=l4;7g| z9aAP^q(w#M`Y~m@216G1QnULjVU^e9-ty~IrdE+!57Xq zBlpyaBL@(!?&*B!mne^(L%jSso~}eV`|O3TYKKKW_PlMAO1$Ymf6)R{X!*ve@DqA$ zV+iQz`HlT>ls~=67l5OkWwAbKqh=P*q1FDW4)JX|QkI|}8kKK6e~`l)ANlJ&4`O=B zTQ^@!>%MjF)m}-!JhipRr zJK{Y=9p=q+^p_KHp9EB_z!SZ^A`kNUuPf##;VSR5wGsmEImz_Nx7Xoofe7YN`_TQ^ z64oK+(8kIGu!cr&OAgxbxjd7ni6j;~J0H$Ubc&N#ZWLZ}$Sw(w^Nx zkVT*Go(nfAr>I4hz!IGL_Ghi+Byb1r8{DSCc5ItLD)bC@Y+Nx8!k>f TgdZ2vaRZb8`vJ!2Ji6(B4JJEu delta 2746 zcmX|DdsGzH9lpPv+1}}ww@#$5v`NM0CaSoF&FabPU9h1D4M6_YN1A4 zV?GD)v^d>TGY(AR!K7pcO!R!pXYjJP*J=#VHXbM3Ch@~(7BWG>?-Nc12}Tx!erpMU zU~0`X;Ek70~LoqcvqAj_e;22^)mhY8geH!V4LSkAAj}|?ruoKLucOA^?4Hn~Gqs#f+%n-vNXsjzUmGRT=Zq{Z`*9qjrNr{h5DV1>yK}g{rku#jAbm=6=Wm29^ppA1A&lOd zpA_<(cW{VU9y>OoV;hZL&=qh72l zFPRi@8=YA>6UZIfSrP@;=ocl)@DBBrR7J**wb)w<&JAgR3O?+8u9U^lEg&_BjSIg5 z*hH6*8c+5X%#BK;ne4Y^t4xJk8lR}lD?%l6LS#iCflYVrZ^h4 zEYW=5XR~Rf9bPSO;x*DwJ|43MFYpPNrTG{sgH|nD1nsncSvD*cndJcREY+^)hdTP% z3NuvDp%sm=l-8_lgfu$5vT-&oxPJQbkfvhm{Se{#AN0(=BEvwt(5hnw!StHVD^Ky6 z%zJU`5TEfTk@k9trQ=5(x0ALxqobN^1GtPmxX`C_7F}r<7V8!bwhM=K&kfew>*+0L zxM5Ra*n=$_Bl^mPKTs%(Zm2B?t8Ewd@sHJZ;iZCzzH|4p!oq6b-m{-?IlZtGW^n@< zb*Y{0f>Fy1n#?cayZ3m@1;+!jK1?!cm*j_D^2%GWA5PoS0;{4iKq{9QgRBf_;zDos z50Q$KE?g{^SKj7@Spfry{34szZ1kF5I~ax4C;O|8c`QPU{x5@E z%u}|DE|Pfa(sbMyL>g1TtW$?F-z(o63$-0~kv?^6sfW#a0mTdtftdTpbNN>50{O z7!Tp|61A>r){?gfw^{66lME;izi5Lgbaq9BUU8@J9{C(?tB4NTtoD8;WT}_IGCELk z1)Xh`pWrpIysDzX-vBz2h9rlU59E(`OyY_8cQMSVG5M;SBu(sdNE*%|5l%OgjC5_e zafg*y*6C!~6{Imv)fd@Qm5IS5xpV-tK!*edOZ4^AHifrfPc`5reRf8g%@ zkmfBG^$d~N_ju-mn5tD`2+gdHhHSdBdVygUf6_(bPP)>w-lgZNb3se>HCFbOPMAr5 zQ!_2T+_g>$CnsHdaGw1`!jac@X>l%nGBd{VLU#g23ADLpy5Y&7eDV?6Q**c>ae`Y$$@`WR_Pxa1n5(4|OA08vQ2)C>mE%29lJq07ln0q|A504{1L_Uf< zg1j5~zgQlQ{DUX^;fKiIdkRPXi2N<;fyn>%Z3X_rl;Q@2@ z!vh$ljy~q|=-@E##}dbbv-90@+~{LI0$YE^i?Tb@Ii z^%-HxnA*hL5doVxcIGCYuwik*`YUYuK3wBnfyDGCt~nh?OotE$5U(RX!m`VV{~?TT zOcUK6^_V~z*6tg3$reXo8m zRMOe6=FY4AR9)Q#A|hUW$yM8bnZgu^By(d z>Q!s1d9m2{Y8n$Mv=Od8^I#@9TQ+ww&WC_d=ViAT)U=M7ls?8z)m@*#TX}fHCx7H) zr)sY$vOwwfd0?Pdw?{)Mb#Kpv>ok2wEX2^2I~G77?c5QM|3g=Iq+6$q&fv{_CEgg{ z`t%(sy_Ni^JY)2ME2S%t59gaZfQM5=GAgPIPI=@nXl}DP>G&v9$tFsd6c-_kopCbu ztxjS&JH%LP^Rf>SZf_Cc=HLMh#MTUSe{(ndirR%D{6#!0%*Nk_0U;dzCAx%qE~@`! z!ll1LxMvaBh Date: Mon, 26 Feb 2024 12:04:54 +0100 Subject: [PATCH 034/652] mixer_module: send a last sample out after all outputs were disabled This matters for PWM when the last output gets disabled on either FMU or IO it would just keep on running. Also when rebooting with a parameters reset or new airframe with no mapped outputs it would previously keep outputting PWM with the disarmed value of the new airframe e.g. 1000us which is a safety hazard because servos could break the physical limit of the model or miscalibrated ESCs spinning motors. --- src/lib/mixer_module/mixer_module.cpp | 5 ++++- src/lib/mixer_module/mixer_module.hpp | 1 + src/lib/mixer_module/mixer_module_tests.cpp | 8 ++++++-- 3 files changed, 11 insertions(+), 3 deletions(-) diff --git a/src/lib/mixer_module/mixer_module.cpp b/src/lib/mixer_module/mixer_module.cpp index dc5f791af22e..ee75bcf9fa0e 100644 --- a/src/lib/mixer_module/mixer_module.cpp +++ b/src/lib/mixer_module/mixer_module.cpp @@ -455,7 +455,8 @@ bool MixingOutput::update() } } - if (!all_disabled) { + // Send output if any function mapped or one last disabling sample + if (!all_disabled || !_was_all_disabled) { if (!_armed.armed && !_armed.manual_lockdown) { _actuator_test.overrideValues(outputs, _max_num_outputs); } @@ -463,6 +464,8 @@ bool MixingOutput::update() limitAndUpdateOutputs(outputs, has_updates); } + _was_all_disabled = all_disabled; + return true; } diff --git a/src/lib/mixer_module/mixer_module.hpp b/src/lib/mixer_module/mixer_module.hpp index c791feb10333..3deaa54aa42f 100644 --- a/src/lib/mixer_module/mixer_module.hpp +++ b/src/lib/mixer_module/mixer_module.hpp @@ -288,6 +288,7 @@ class MixingOutput : public ModuleParams hrt_abstime _lowrate_schedule_interval{300_ms}; ActuatorTest _actuator_test{_function_assignment}; uint32_t _reversible_mask{0}; ///< per-output bits. If set, the output is configured to be reversible (motors only) + bool _was_all_disabled{false}; uORB::SubscriptionCallbackWorkItem *_subscription_callback{nullptr}; ///< current scheduling callback diff --git a/src/lib/mixer_module/mixer_module_tests.cpp b/src/lib/mixer_module/mixer_module_tests.cpp index ef48f3e3f217..3901a1c85de9 100644 --- a/src/lib/mixer_module/mixer_module_tests.cpp +++ b/src/lib/mixer_module/mixer_module_tests.cpp @@ -191,11 +191,15 @@ TEST_F(MixerModuleTest, basic) mixing_output.setAllMaxValues(MAX_VALUE); EXPECT_EQ(test_module.num_updates, 0); - // all functions disabled: not expected to get an update + // all functions disabled: expect to get one single update to process disabling the output signal mixing_output.update(); mixing_output.updateSubscriptions(false); mixing_output.update(); - EXPECT_EQ(test_module.num_updates, 0); + EXPECT_EQ(test_module.num_updates, 1); + mixing_output.update(); + mixing_output.updateSubscriptions(false); + mixing_output.update(); + EXPECT_EQ(test_module.num_updates, 1); test_module.reset(); // configure motor, ensure all still disarmed From fa1885af238e94c089941d789f514901f0a8562e Mon Sep 17 00:00:00 2001 From: enesavcu Date: Tue, 26 Mar 2024 18:11:32 +0300 Subject: [PATCH 035/652] Signal generator (#22666) Add option to generate sine chirp signals for fixed-wing system identification --- .../fw_autotune_attitude_control.cpp | 50 ++++++++++++++---- .../fw_autotune_attitude_control.hpp | 14 ++++- .../fw_autotune_attitude_control_params.c | 51 +++++++++++++++++++ 3 files changed, 104 insertions(+), 11 deletions(-) diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp index 7f6e5b9c10c8..5e63924d3b57 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp @@ -620,22 +620,52 @@ void FwAutotuneAttitudeControl::saveGainsToParams() const Vector3f FwAutotuneAttitudeControl::getIdentificationSignal() { - if (_steps_counter > _max_steps) { - _signal_sign = (_signal_sign == 1) ? 0 : 1; - _steps_counter = 0; - if (_max_steps > 1) { - _max_steps--; - } else { - _max_steps = 5; + const hrt_abstime now = hrt_absolute_time(); + const float t = static_cast(now - _state_start_time) * 1e-6f; + float signal = 0.0f; + + switch (_param_fw_sysid_signal_type.get()) { + case static_cast(SignalType::kStep): { + if (_steps_counter > _max_steps) { + _signal_sign = (_signal_sign == 1) ? 0 : 1; + _steps_counter = 0; + + if (_max_steps > 1) { + _max_steps--; + + } else { + _max_steps = 5; + } + } + + _steps_counter++; + signal = float(_signal_sign); } - } + break; + + case static_cast(SignalType::kLinearSineSweep): { - _steps_counter++; + signal = signal_generator::getLinearSineSweep(_param_fw_at_sysid_f0.get(), + _param_fw_at_sysid_f1.get(), + _param_fw_sysid_time.get(), t); + } + break; + + case static_cast(SignalType::kLogSineSweep): { + signal = signal_generator::getLogSineSweep(_param_fw_at_sysid_f0.get(), _param_fw_at_sysid_f1.get(), + _param_fw_sysid_time.get(), t); + } + break; + + default: + signal = 0.f; + break; + } - const float signal = float(_signal_sign) * _param_fw_at_sysid_amp.get(); + signal *= _param_fw_at_sysid_amp.get(); Vector3f rate_sp{}; float signal_scaled = 0.f; diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp index 9be5f5559664..4350724eed43 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp @@ -44,6 +44,7 @@ #include #include #include +#include #include #include #include @@ -64,6 +65,12 @@ using namespace time_literals; +enum class SignalType : uint8_t { + kStep = 0, + kLinearSineSweep, + kLogSineSweep +}; + class FwAutotuneAttitudeControl : public ModuleBase, public ModuleParams, public px4::WorkItem { @@ -204,7 +211,12 @@ class FwAutotuneAttitudeControl : public ModuleBase, (ParamFloat) _param_fw_yr_p, (ParamFloat) _param_fw_yr_i, (ParamFloat) _param_fw_yr_ff, - (ParamFloat) _param_fw_y_rmax + (ParamFloat) _param_fw_y_rmax, + + (ParamFloat) _param_fw_at_sysid_f0, + (ParamFloat) _param_fw_at_sysid_f1, + (ParamFloat) _param_fw_sysid_time, + (ParamInt) _param_fw_sysid_signal_type ) static constexpr float _publishing_dt_s = 100e-3f; diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c index 13609dbbb187..eb10036631b6 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c @@ -121,3 +121,54 @@ PARAM_DEFINE_INT32(FW_AT_AXES, 3); * @group Autotune */ PARAM_DEFINE_INT32(FW_AT_MAN_AUX, 0); + +/** + * Start frequency of the injected signal + * + * Can be set lower or higher than the end frequency + * + * @min 0.1 + * @max 30.0 + * @decimal 1 + * @unit Hz + * @group Autotune + */ +PARAM_DEFINE_FLOAT(FW_AT_SYSID_F0, 1.f); + +/** + * End frequency of the injected signal + * + * Can be set lower or higher than the start frequency + * + * @min 0.1 + * @max 30.0 + * @decimal 1 + * @unit Hz + * @group Autotune + */ +PARAM_DEFINE_FLOAT(FW_AT_SYSID_F1, 20.f); + +/** + * Maneuver time for each axis + * + * Duration of the input signal sent on each axis during system identification + * + * @min 5 + * @max 120 + * @decimal 0 + * @unit s + * @group Autotune + */ +PARAM_DEFINE_FLOAT(FW_AT_SYSID_TIME, 10.f); + +/** + * Input signal type + * + * Type of signal used during system identification to excite the system. + * + * @value 0 Step + * @value 1 Linear sine sweep + * @value 2 Logarithmic sine sweep + * @group Autotune + */ +PARAM_DEFINE_INT32(FW_AT_SYSID_TYPE, 0); From 8ade2e5f2d220f3999930d87392ebcd7bb0c4f57 Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Tue, 26 Mar 2024 16:28:22 -0700 Subject: [PATCH 036/652] Add SYS_AUTOSTART touch in voxl-px4-start --- boards/modalai/voxl2/target/voxl-px4-start | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/boards/modalai/voxl2/target/voxl-px4-start b/boards/modalai/voxl2/target/voxl-px4-start index 5a9149f225a2..4b0c132cfcfc 100755 --- a/boards/modalai/voxl2/target/voxl-px4-start +++ b/boards/modalai/voxl2/target/voxl-px4-start @@ -106,8 +106,10 @@ qshell rgbled_ncp5623c start -X -b 1 -f 400 -a 56 # We do not change the value of SYS_AUTOCONFIG but if it does not # show up as used then it is not reported to QGC and we get a -# missing parameter error. +# missing parameter error. Also, we don't use SYS_AUTOSTART but QGC +# complains about it as well. param touch SYS_AUTOCONFIG +param touch SYS_AUTOSTART # ESC driver if [ "$ESC" == "VOXL_ESC" ]; then From 3aac8f36e666a880a800a4a64aba8a8b1c46d4dc Mon Sep 17 00:00:00 2001 From: jamming Date: Wed, 27 Mar 2024 07:49:11 +0800 Subject: [PATCH 037/652] boards/holybro/kakuteh7: fix icm42688p IMU - the mass-produced kakuteH7 did not use ICM20689 IMU --- boards/holybro/kakuteh7/src/spi.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/holybro/kakuteh7/src/spi.cpp b/boards/holybro/kakuteh7/src/spi.cpp index 1ff5b7f35c1c..e0f4db0edd6e 100644 --- a/boards/holybro/kakuteh7/src/spi.cpp +++ b/boards/holybro/kakuteh7/src/spi.cpp @@ -43,7 +43,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}), }), initSPIBus(SPI::Bus::SPI4, { - initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}), initSPIDevice(DRV_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}), initSPIDevice(DRV_IMU_DEVTYPE_BMI270, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}), }), From 749f88b62b57f5e855ac3434351d1abee7317eba Mon Sep 17 00:00:00 2001 From: "murata,katsutoshi" Date: Wed, 27 Mar 2024 08:50:57 +0900 Subject: [PATCH 038/652] ekf2: gps control lazily check yaw_failure() only after in_air --- src/modules/ekf2/EKF/gps_control.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/gps_control.cpp index 03cf0a326f28..8e5e0bff91b4 100644 --- a/src/modules/ekf2/EKF/gps_control.cpp +++ b/src/modules/ekf2/EKF/gps_control.cpp @@ -123,8 +123,8 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) bool do_vel_pos_reset = shouldResetGpsFusion(); - if (isYawFailure() - && _control_status.flags.in_air + if (_control_status.flags.in_air + && isYawFailure() && isTimedOut(_time_last_hor_vel_fuse, _params.EKFGSF_reset_delay) && (_time_last_hor_vel_fuse > _time_last_on_ground_us)) { do_vel_pos_reset = tryYawEmergencyReset(); From 868a884131b580279fad5a50309b9768c2bab16f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 27 Mar 2024 16:29:56 +1300 Subject: [PATCH 039/652] fw_att_control: bitwise and should be logical and (#22933) Signed-off-by: Julian Oes --- src/modules/fw_att_control/FixedwingAttitudeControl.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp index 7de353c8f977..be4aaf9b23e4 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp @@ -92,7 +92,7 @@ FixedwingAttitudeControl::vehicle_manual_poll(const float yaw_body) // Always copy the new manual setpoint, even if it wasn't updated, to fill the actuators with valid values if (_manual_control_setpoint_sub.copy(&_manual_control_setpoint)) { - if (!_vcontrol_mode.flag_control_climb_rate_enabled & _vcontrol_mode.flag_control_attitude_enabled) { + if (!_vcontrol_mode.flag_control_climb_rate_enabled && _vcontrol_mode.flag_control_attitude_enabled) { // STABILIZED mode generate the attitude setpoint from manual user inputs @@ -479,4 +479,4 @@ fw_att_control is the fixed wing attitude controller. extern "C" __EXPORT int fw_att_control_main(int argc, char *argv[]) { return FixedwingAttitudeControl::main(argc, argv); -} +} \ No newline at end of file From 4c5f084445c5054b028e31f577f5d5a8cdd2cab2 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 27 Mar 2024 16:22:53 +0100 Subject: [PATCH 040/652] Battery parameters: clarify empty, full voltage description --- src/lib/battery/module.yaml | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/lib/battery/module.yaml b/src/lib/battery/module.yaml index 44f379002870..27723a7a4b63 100644 --- a/src/lib/battery/module.yaml +++ b/src/lib/battery/module.yaml @@ -7,12 +7,12 @@ parameters: definitions: BAT${i}_V_EMPTY: description: - short: Empty cell voltage (5C load) + short: Empty cell voltage long: | - Defines the voltage where a single cell of battery 1 is considered empty. - The voltage should be chosen before the steep dropoff to 2.8V. A typical - lithium battery can only be discharged down to 10% before it drops off - to a voltage level damaging the cells. + Defines the voltage where a single cell of the battery is considered empty. + The voltage should be chosen above the steep dropoff at 3.5V. A typical + lithium battery can only be discharged under high load down to 10% before + it drops off to a voltage level damaging the cells. type: float unit: V @@ -25,10 +25,10 @@ parameters: BAT${i}_V_CHARGED: description: - short: Full cell voltage (5C load) + short: Full cell voltage long: | - Defines the voltage where a single cell of battery 1 is considered full - under a mild load. This will never be the nominal voltage of 4.2V + Defines the voltage where a single cell of the battery is considered full. + For a more accurate estimate set this below the nominal voltage of e.g. 4.2V type: float unit: V @@ -44,7 +44,7 @@ parameters: short: Voltage drop per cell on full throttle long: | This implicitly defines the internal resistance - to maximum current ratio for battery 1 and assumes linearity. + to maximum current ratio for the battery and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT${i}_R_INTERNAL is set. From 6e86862b6a7d24b35ae1fd284602412e640824f7 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 27 Mar 2024 17:02:01 +0100 Subject: [PATCH 041/652] boards: unify comments for voltage deviders --- boards/diatone/mamba-f405-mk2/src/board_config.h | 3 +-- boards/matek/h743-mini/src/board_config.h | 4 +--- boards/matek/h743/src/board_config.h | 4 +--- boards/sky-drones/smartap-airlink/src/board_config.h | 2 +- 4 files changed, 4 insertions(+), 9 deletions(-) diff --git a/boards/diatone/mamba-f405-mk2/src/board_config.h b/boards/diatone/mamba-f405-mk2/src/board_config.h index 7c2b17d84db4..3c5f0e9830b9 100644 --- a/boards/diatone/mamba-f405-mk2/src/board_config.h +++ b/boards/diatone/mamba-f405-mk2/src/board_config.h @@ -74,8 +74,7 @@ #define ADC_BATTERY_CURRENT_CHANNEL 13 #define ADC_RC_RSSI_CHANNEL 12 -/* Define Battery 1 Voltage Divider and A per V - */ +/* Define Battery Voltage Divider and A per V */ #define BOARD_BATTERY1_V_DIV (11.12f) #define BOARD_BATTERY1_A_PER_V (31.f) diff --git a/boards/matek/h743-mini/src/board_config.h b/boards/matek/h743-mini/src/board_config.h index 151d6b59c5e5..e47444085a4e 100644 --- a/boards/matek/h743-mini/src/board_config.h +++ b/boards/matek/h743-mini/src/board_config.h @@ -102,9 +102,7 @@ (1 << ADC_RSSI_IN_CHANNEL)) -/* Define Battery 1 Voltage Divider and A per V - */ - +/* Define Battery Voltage Divider and A per V */ #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ #define BOARD_BATTERY1_A_PER_V (40.0f) #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ diff --git a/boards/matek/h743/src/board_config.h b/boards/matek/h743/src/board_config.h index 151d6b59c5e5..e47444085a4e 100644 --- a/boards/matek/h743/src/board_config.h +++ b/boards/matek/h743/src/board_config.h @@ -102,9 +102,7 @@ (1 << ADC_RSSI_IN_CHANNEL)) -/* Define Battery 1 Voltage Divider and A per V - */ - +/* Define Battery Voltage Divider and A per V */ #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ #define BOARD_BATTERY1_A_PER_V (40.0f) #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ diff --git a/boards/sky-drones/smartap-airlink/src/board_config.h b/boards/sky-drones/smartap-airlink/src/board_config.h index 5b957e0694cc..158fece58c8a 100644 --- a/boards/sky-drones/smartap-airlink/src/board_config.h +++ b/boards/sky-drones/smartap-airlink/src/board_config.h @@ -196,7 +196,7 @@ */ #define DIRECT_PWM_OUTPUT_CHANNELS 8 -/* Define Battery 1 g Divider and A per V. */ +/* Define Battery Voltage Divider and A per V */ #define BOARD_BATTERY_V_DIV (13.653333333f) #define BOARD_BATTERY_A_PER_V (36.367515152f) From 3099eac2bae8365547f7bddbee305161f212d008 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 25 Mar 2024 06:17:30 -0700 Subject: [PATCH 042/652] NuttX with pr-h7-serial-logic-error backport --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 693b9e782535..61958c53056b 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 693b9e782535f12e6a4ab657c7a0c3bd92b45fb1 +Subproject commit 61958c53056b5c3fb828f18a097de57d9bed0fda From 0f9531a526525d83096cd65bacd20bf28d210127 Mon Sep 17 00:00:00 2001 From: Claudio Micheli Date: Mon, 18 Mar 2024 19:16:40 +0100 Subject: [PATCH 043/652] commander: improve failsafe messaging Signed-off-by: Claudio Micheli --- .../checks/rcAndDataLinkCheck.cpp | 2 +- src/modules/commander/failsafe/framework.cpp | 16 ++++++++-------- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcAndDataLinkCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/rcAndDataLinkCheck.cpp index 660a792f857a..9f09c2a645e4 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/rcAndDataLinkCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/rcAndDataLinkCheck.cpp @@ -51,7 +51,7 @@ void RcAndDataLinkChecks::checkAndReport(const Context &context, Report &reporte if (!reporter.failsafeFlags().manual_control_signal_lost && _last_valid_manual_control_setpoint > 0) { - events::send(events::ID("commander_rc_lost"), {events::Log::Critical, events::LogInternal::Info}, + events::send(events::ID("commander_rc_lost"), {events::Log::Info, events::LogInternal::Info}, "Manual control lost"); } diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 16a3678d81b5..5d581caea859 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -195,7 +195,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_generic_hold"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe, triggering {2} in {3} seconds", mavlink_mode, failsafe_action, + "Failsafe activated: switching to {2} in {3} seconds", mavlink_mode, failsafe_action, (uint16_t) delay_s); } else { @@ -204,11 +204,11 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_hold"), {events::Log::Critical, events::LogInternal::Warning}, - "{4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action, + "{4}: switching to {2} in {3} seconds", mavlink_mode, failsafe_action, (uint16_t) delay_s, failsafe_cause); } - mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated, entering Hold for %i seconds\t", delay_s); + mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated: entering Hold for %i seconds\t", delay_s); } else { // no delay failsafe_action_t failsafe_action = (failsafe_action_t)action; @@ -222,16 +222,16 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_generic_warn"), {events::Log::Warning, events::LogInternal::Warning}, - "Failsafe warning triggered", mavlink_mode); + "Failsafe warning:", mavlink_mode); } else { /* EVENT * @type append_health_and_arming_messages */ - events::send( + events::send( events::ID("commander_failsafe_enter_generic"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe, triggering {2}", mavlink_mode, failsafe_action); + "Failsafe activated: Autopilot disengaged", mavlink_mode); } } else { @@ -262,7 +262,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_warn"), {events::Log::Warning, events::LogInternal::Warning}, - "Failsafe warning triggered due to {2}", mavlink_mode, failsafe_cause); + "Failsafe warning: {2}", mavlink_mode, failsafe_cause); } @@ -272,7 +272,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter"), {events::Log::Critical, events::LogInternal::Warning}, - "{3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause); + "{3}: switching to {2}", mavlink_mode, failsafe_action, failsafe_cause); } } From 416b6a35a478482fe021b9261e15911338598d09 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 27 Mar 2024 19:23:32 +0100 Subject: [PATCH 044/652] failsafe framework: inform about failsafe action --- src/modules/commander/failsafe/framework.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 5d581caea859..9f88f85f3e8e 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -228,10 +228,10 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action /* EVENT * @type append_health_and_arming_messages */ - events::send( + events::send( events::ID("commander_failsafe_enter_generic"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe activated: Autopilot disengaged", mavlink_mode); + "Failsafe activated: Autopilot disengaged, switching to {2}", mavlink_mode, failsafe_action); } } else { From ccdf0603931e513fb96f3f5b8a4240e51b7c3122 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Mon, 1 Apr 2024 09:27:59 -0700 Subject: [PATCH 045/652] Additions to the Serial UART API (#22953) - Added an empty constructor, setPort, and validatePort functions for Serial API - Changed GPS to not allocate Serial object dynamically - Moved access check on serial port name into the Serial API - Improved the Qurt platform validatePort Serial function to implement a more rigorous check. Added safety check to the setPort Serial function to make sure it isn't called after the port has been already opened. --- platforms/common/Serial.cpp | 14 +++++++ .../include/px4_platform_common/Serial.hpp | 3 ++ platforms/nuttx/src/px4/common/SerialImpl.cpp | 31 ++++++++++++-- .../src/px4/common/include/SerialImpl.hpp | 2 + platforms/posix/include/SerialImpl.hpp | 2 + platforms/posix/src/px4/common/SerialImpl.cpp | 31 ++++++++++++-- platforms/qurt/include/SerialImpl.hpp | 1 + platforms/qurt/src/px4/SerialImpl.cpp | 31 ++++++++++++-- src/drivers/gps/gps.cpp | 42 ++++++++----------- src/lib/drivers/device/qurt/uart.c | 21 ++++++++-- src/lib/drivers/device/qurt/uart.h | 1 + 11 files changed, 142 insertions(+), 37 deletions(-) diff --git a/platforms/common/Serial.cpp b/platforms/common/Serial.cpp index 2f93a66a6ebf..28e2d5986bd6 100644 --- a/platforms/common/Serial.cpp +++ b/platforms/common/Serial.cpp @@ -36,6 +36,10 @@ namespace device { +Serial::Serial() : + _impl(nullptr, 57600, ByteSize::EightBits, Parity::None, StopBits::One, FlowControl::Disabled) {} + + Serial::Serial(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits, FlowControl flowcontrol) : _impl(port, baudrate, bytesize, parity, stopbits, flowcontrol) @@ -135,4 +139,14 @@ const char *Serial::getPort() const return _impl.getPort(); } +bool Serial::validatePort(const char *port) +{ + return SerialImpl::validatePort(port); +} + +bool Serial::setPort(const char *port) +{ + return _impl.setPort(port); +} + } // namespace device diff --git a/platforms/common/include/px4_platform_common/Serial.hpp b/platforms/common/include/px4_platform_common/Serial.hpp index ce02b5ac6308..b38ae93f0ac2 100644 --- a/platforms/common/include/px4_platform_common/Serial.hpp +++ b/platforms/common/include/px4_platform_common/Serial.hpp @@ -48,6 +48,7 @@ namespace device __EXPORT class Serial { public: + Serial(); Serial(const char *port, uint32_t baudrate = 57600, ByteSize bytesize = ByteSize::EightBits, Parity parity = Parity::None, StopBits stopbits = StopBits::One, FlowControl flowcontrol = FlowControl::Disabled); @@ -83,6 +84,8 @@ class Serial FlowControl getFlowcontrol() const; bool setFlowcontrol(FlowControl flowcontrol); + static bool validatePort(const char *port); + bool setPort(const char *port); const char *getPort() const; private: diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index 7490dd604cc4..c5b659334443 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -53,9 +53,8 @@ SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, P _stopbits(stopbits), _flowcontrol(flowcontrol) { - if (port) { - strncpy(_port, port, sizeof(_port) - 1); - _port[sizeof(_port) - 1] = '\0'; + if (validatePort(port)) { + setPort(port); } else { _port[0] = 0; @@ -192,6 +191,11 @@ bool SerialImpl::open() return true; } + if (!validatePort(_port)) { + PX4_ERR("Invalid port %s", _port); + return false; + } + // Open the serial port int serial_fd = ::open(_port, O_RDWR | O_NOCTTY); @@ -324,6 +328,27 @@ const char *SerialImpl::getPort() const return _port; } +bool SerialImpl::validatePort(const char *port) +{ + return (port && (access(port, R_OK | W_OK) == 0)); +} + +bool SerialImpl::setPort(const char *port) +{ + if (_open) { + PX4_ERR("Cannot set port after port has already been opened"); + return false; + } + + if (validatePort(port)) { + strncpy(_port, port, sizeof(_port) - 1); + _port[sizeof(_port) - 1] = '\0'; + return true; + } + + return false; +} + uint32_t SerialImpl::getBaudrate() const { return _baudrate; diff --git a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp index 58d41bf759c9..28d838354ec0 100644 --- a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp +++ b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp @@ -65,6 +65,8 @@ class SerialImpl ssize_t write(const void *buffer, size_t buffer_size); const char *getPort() const; + static bool validatePort(const char *port); + bool setPort(const char *port); uint32_t getBaudrate() const; bool setBaudrate(uint32_t baudrate); diff --git a/platforms/posix/include/SerialImpl.hpp b/platforms/posix/include/SerialImpl.hpp index efc95d7d517a..d5688834e314 100644 --- a/platforms/posix/include/SerialImpl.hpp +++ b/platforms/posix/include/SerialImpl.hpp @@ -65,6 +65,8 @@ class SerialImpl ssize_t write(const void *buffer, size_t buffer_size); const char *getPort() const; + static bool validatePort(const char *port); + bool setPort(const char *port); uint32_t getBaudrate() const; bool setBaudrate(uint32_t baudrate); diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 79e3422aedf2..739796e6a172 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -51,9 +51,8 @@ SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, P _stopbits(stopbits), _flowcontrol(flowcontrol) { - if (port) { - strncpy(_port, port, sizeof(_port) - 1); - _port[sizeof(_port) - 1] = '\0'; + if (validatePort(port)) { + setPort(port); } else { _port[0] = 0; @@ -190,6 +189,11 @@ bool SerialImpl::open() return true; } + if (!validatePort(_port)) { + PX4_ERR("Invalid port %s", _port); + return false; + } + // Open the serial port int serial_fd = ::open(_port, O_RDWR | O_NOCTTY); @@ -317,6 +321,27 @@ const char *SerialImpl::getPort() const return _port; } +bool SerialImpl::validatePort(const char *port) +{ + return (port && (access(port, R_OK | W_OK) == 0)); +} + +bool SerialImpl::setPort(const char *port) +{ + if (_open) { + PX4_ERR("Cannot set port after port has already been opened"); + return false; + } + + if (validatePort(port)) { + strncpy(_port, port, sizeof(_port) - 1); + _port[sizeof(_port) - 1] = '\0'; + return true; + } + + return false; +} + uint32_t SerialImpl::getBaudrate() const { return _baudrate; diff --git a/platforms/qurt/include/SerialImpl.hpp b/platforms/qurt/include/SerialImpl.hpp index 1b98d3bb401b..91bbde046454 100644 --- a/platforms/qurt/include/SerialImpl.hpp +++ b/platforms/qurt/include/SerialImpl.hpp @@ -65,6 +65,7 @@ class SerialImpl const char *getPort() const; bool setPort(const char *port); + static bool validatePort(const char *port); uint32_t getBaudrate() const; bool setBaudrate(uint32_t baudrate); diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp index ec0fb73fce3a..287064b760ad 100644 --- a/platforms/qurt/src/px4/SerialImpl.cpp +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -48,9 +48,8 @@ SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, P _stopbits(stopbits), _flowcontrol(flowcontrol) { - if (port) { - strncpy(_port, port, sizeof(_port) - 1); - _port[sizeof(_port) - 1] = '\0'; + if (validatePort(port)) { + setPort(port); } else { _port[0] = 0; @@ -117,6 +116,11 @@ bool SerialImpl::open() return false; } + if (!validatePort(_port)) { + PX4_ERR("Invalid port %s", _port); + return false; + } + // qurt_uart_open will check validity of port and baudrate int serial_fd = qurt_uart_open(_port, _baudrate); @@ -256,6 +260,27 @@ const char *SerialImpl::getPort() const return _port; } +bool SerialImpl::validatePort(const char *port) +{ + return (qurt_uart_get_port(port) >= 0); +} + +bool SerialImpl::setPort(const char *port) +{ + if (_open) { + PX4_ERR("Cannot set port after port has already been opened"); + return false; + } + + if (validatePort(port)) { + strncpy(_port, port, sizeof(_port) - 1); + _port[sizeof(_port) - 1] = '\0'; + return true; + } + + return false; +} + uint32_t SerialImpl::getBaudrate() const { return _baudrate; diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 766be323d719..aa8b8d7543f5 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -174,7 +174,7 @@ class GPS : public ModuleBase, public device::Device #ifdef __PX4_LINUX int _spi_fd {-1}; ///< SPI interface to GPS #endif - Serial *_uart = nullptr; ///< UART interface to GPS + Serial _uart {}; ///< UART interface to GPS unsigned _baudrate{0}; ///< current baudrate const unsigned _configured_baudrate{0}; ///< configured baudrate (0=auto-detect) char _port[20] {}; ///< device / serial port path @@ -416,8 +416,8 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user) int ret = 0; - if (gps->_uart) { - ret = gps->_uart->write((void *) data1, (size_t) data2); + if (gps->_interface == GPSHelper::Interface::UART) { + ret = gps->_uart.write((void *) data1, (size_t) data2); #ifdef __PX4_LINUX @@ -477,8 +477,8 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout) handleInjectDataTopic(); - if ((_interface == GPSHelper::Interface::UART) && (_uart)) { - ret = _uart->readAtLeast(buf, buf_length, character_count, timeout_adjusted); + if (_interface == GPSHelper::Interface::UART) { + ret = _uart.readAtLeast(buf, buf_length, character_count, timeout_adjusted); // SPI is only supported on LInux #if defined(__PX4_LINUX) @@ -598,8 +598,8 @@ bool GPS::injectData(uint8_t *data, size_t len) size_t written = 0; - if ((_interface == GPSHelper::Interface::UART) && (_uart)) { - written = _uart->write((const void *) data, len); + if (_interface == GPSHelper::Interface::UART) { + written = _uart.write((const void *) data, len); #ifdef __PX4_LINUX @@ -615,7 +615,7 @@ bool GPS::injectData(uint8_t *data, size_t len) int GPS::setBaudrate(unsigned baud) { if (_interface == GPSHelper::Interface::UART) { - if ((_uart) && (_uart->setBaudrate(baud))) { + if (_uart.setBaudrate(baud)) { return 0; } @@ -786,23 +786,19 @@ GPS::run() _helper = nullptr; } - if ((_interface == GPSHelper::Interface::UART) && (_uart == nullptr)) { + if ((_interface == GPSHelper::Interface::UART) && (! _uart.isOpen())) { - // Create the UART port instance - _uart = new Serial(_port); - - if (_uart == nullptr) { - PX4_ERR("Error creating serial device %s", _port); + // Configure UART port + if (!_uart.setPort(_port)) { + PX4_ERR("Error configuring serial device on port %s", _port); px4_sleep(1); continue; } - } - if ((_interface == GPSHelper::Interface::UART) && (! _uart->isOpen())) { // Configure the desired baudrate if one was specified by the user. // Otherwise the default baudrate will be used. if (_configured_baudrate) { - if (! _uart->setBaudrate(_configured_baudrate)) { + if (! _uart.setBaudrate(_configured_baudrate)) { PX4_ERR("Error setting baudrate to %u on %s", _configured_baudrate, _port); px4_sleep(1); continue; @@ -810,7 +806,7 @@ GPS::run() } // Open the UART. If this is successful then the UART is ready to use. - if (! _uart->open()) { + if (! _uart.open()) { PX4_ERR("Error opening serial device %s", _port); px4_sleep(1); continue; @@ -1029,10 +1025,8 @@ GPS::run() } } - if ((_interface == GPSHelper::Interface::UART) && (_uart)) { - (void) _uart->close(); - delete _uart; - _uart = nullptr; + if (_interface == GPSHelper::Interface::UART) { + (void) _uart.close(); #ifdef __PX4_LINUX @@ -1528,7 +1522,7 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) GPS *gps = nullptr; if (instance == Instance::Main) { - if (device_name && (access(device_name, R_OK|W_OK) == 0)) { + if (Serial::validatePort(device_name)) { gps = new GPS(device_name, mode, interface, instance, baudrate_main); } else { @@ -1551,7 +1545,7 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) } } } else { // secondary instance - if (device_name_secondary && (access(device_name_secondary, R_OK|W_OK) == 0)) { + if (Serial::validatePort(device_name_secondary)) { gps = new GPS(device_name_secondary, mode, interface_secondary, instance, baudrate_secondary); } else { diff --git a/src/lib/drivers/device/qurt/uart.c b/src/lib/drivers/device/qurt/uart.c index 798d20534443..ca1d0f66c740 100644 --- a/src/lib/drivers/device/qurt/uart.c +++ b/src/lib/drivers/device/qurt/uart.c @@ -25,19 +25,32 @@ void configure_uart_callbacks(open_uart_func_t open_func, } } -int qurt_uart_open(const char *dev, speed_t speed) +int qurt_uart_get_port(const char *dev) { - if (_callbacks_configured) { + if (dev != NULL) { // Convert device string into a uart port number char *endptr = NULL; - uint8_t port_number = (uint8_t) strtol(dev, &endptr, 10); + int port_number = strtol(dev, &endptr, 10); if ((port_number == 0) && (endptr == dev)) { PX4_ERR("Could not convert %s into a valid uart port number", dev); return -1; + + } else { + return port_number; } + } + + return -1; +} + +int qurt_uart_open(const char *dev, speed_t speed) +{ + int port_number = qurt_uart_get_port(dev); + + if (_callbacks_configured && (port_number >= 0)) { - return _open_uart(port_number, speed); + return _open_uart((uint8_t) port_number, speed); } else { PX4_ERR("Cannot open uart until callbacks have been configured"); diff --git a/src/lib/drivers/device/qurt/uart.h b/src/lib/drivers/device/qurt/uart.h index 03055961898f..d1632fe6a2c8 100644 --- a/src/lib/drivers/device/qurt/uart.h +++ b/src/lib/drivers/device/qurt/uart.h @@ -7,6 +7,7 @@ extern "C" { #include #include +int qurt_uart_get_port(const char *dev); int qurt_uart_open(const char *dev, speed_t speed); int qurt_uart_write(int fd, const char *buf, size_t len); int qurt_uart_read(int fd, char *buf, size_t len, uint32_t timeout_us); From 71b074b23491f7e9f310a9ba6d0ae50908a91461 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Mon, 1 Apr 2024 15:33:37 -0700 Subject: [PATCH 046/652] Qurt termios decoy (#22954) * Added decoy termios support to Qurt so that ghst parser in RC library can be used. No termios is actually needed but has to be there for the parser to work --- boards/modalai/voxl2-slpi/src/CMakeLists.txt | 2 +- platforms/qurt/include/termios.h | 343 +++++++++++++++++-- platforms/qurt/unresolved_symbols.c | 19 + 3 files changed, 332 insertions(+), 32 deletions(-) diff --git a/boards/modalai/voxl2-slpi/src/CMakeLists.txt b/boards/modalai/voxl2-slpi/src/CMakeLists.txt index bb35ef068a33..6ccb1facf6c5 100644 --- a/boards/modalai/voxl2-slpi/src/CMakeLists.txt +++ b/boards/modalai/voxl2-slpi/src/CMakeLists.txt @@ -47,7 +47,7 @@ add_library(drivers_board add_subdirectory(${PX4_BOARD_DIR}/src/drivers/rc_controller) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/mavlink_rc_in) # add_subdirectory(${PX4_BOARD_DIR}/src/drivers/spektrum_rc) -# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc) +add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl) # add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_sbus) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/elrs_led) diff --git a/platforms/qurt/include/termios.h b/platforms/qurt/include/termios.h index d36d80ee9388..2e59ca1815bb 100644 --- a/platforms/qurt/include/termios.h +++ b/platforms/qurt/include/termios.h @@ -1,37 +1,318 @@ /**************************************************************************** + * include/termios.h * - * Copyright (C) 2022 ModalAI, Inc. 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. + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __INCLUDE_TERMIOS_H +#define __INCLUDE_TERMIOS_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions ****************************************************************************/ -// This file prevents a missing header file error but since Qurt doesn't support -// termios the actual code will still need to be changed for Qurt +/* Terminal input modes (c_iflag in the termios structure) */ + +#define IGNBRK (1 << 0) /* Bit 0: Ignore break condition */ +#define BRKINT (1 << 1) /* Bit 1: Signal interrupt on break */ +#define IGNPAR (1 << 2) /* Bit 2: Ignore characters with parity errors */ +#define PARMRK (1 << 3) /* Bit 3: Mark parity errors */ +#define INPCK (1 << 4) /* Bit 4: Enable input parity check */ +#define ISTRIP (1 << 5) /* Bit 5: Strip character */ +#define INLCR (1 << 6) /* Bit 6: Map NL to CR on input */ +#define IGNCR (1 << 7) /* Bit 7: Ignore CR */ +#define ICRNL (1 << 8) /* Bit 8: Map CR to NL on input */ +#define IUCLC (1 << 9) /* Bit 9: Map upper-case to lower-case on input (LEGACY) */ +#define IXON (1 << 10) /* Bit 10: Enable start/stop output control */ +#define IXANY (1 << 11) /* Bit 11: Enable any character to restart output */ +#define IXOFF (1 << 12) /* Bit 12: Enable start/stop input control */ + +/* Terminal output modes (c_oflag in the termios structure) */ + +#define OPOST (1 << 0) /* Bit 0: Post-process output */ +#define OLCUC (1 << 1) /* Bit 1: Map lower-case to upper-case on output (LEGACY) */ +#define ONLCR (1 << 2) /* Bit 2: Map NL to CR-NL on output */ +#define OCRNL (1 << 3) /* Bit 3: Map CR to NL on output */ +#define ONOCR (1 << 4) /* Bit 4: No CR output at column 0 */ +#define ONLRET (1 << 5) /* Bit 5: NL performs CR function */ +#define OFILL (1 << 6) /* Bit 6: Use fill characters for delay */ +#define NLDLY (1 << 8) /* Bit 8: Select newline delays: */ +# define NL0 (0 << 8) /* Newline character type 0 */ +# define NL1 (1 << 8) /* Newline character type 1 */ +#define CRDLY (3 << 9) /* Bits 9-10: Select carriage-return delays: */ +# define CR0 (0 << 9) /* Carriage-return delay type 0 */ +# define CR1 (1 << 9) /* Carriage-return delay type 1 */ +# define CR2 (2 << 9) /* Carriage-return delay type 2 */ +# define CR3 (3 << 9) /* Carriage-return delay type 3 */ +#define TABDLY (3 << 11) /* Bits 11-12: Select horizontal-tab delays: */ +# define TAB0 (0 << 11) /* Horizontal-tab delay type 0 */ +# define TAB1 (1 << 11) /* Horizontal-tab delay type 1 */ +# define TAB2 (2 << 11) /* Horizontal-tab delay type 2 */ +# define TAB3 (3 << 11) /* Expand tabs to spaces */ +#define BSDLY (1 << 13) /* Bit 13: Select backspace delays: */ +# define BS0 (0 << 13) /* Backspace-delay type 0 */ +# define BS1 (1 << 13) /* Backspace-delay type 1 */ +#define VTDLY (1 << 14) /* Bit 14: Select vertical-tab delays: */ +# define VT0 (0 << 14) /* Vertical-tab delay type 0 */ +# define VT1 (1 << 14) /* Vertical-tab delay type 1 */ +#define FFDLY (1 << 15) /* Bit 15: Select form-feed delays: */ +# define FF0 (0 << 15) /* Form-feed delay type 0 */ +# define FF1 (1 << 15) /* Form-feed delay type 1 */ + +/* Control Modes (c_cflag in the termios structure) */ + +#define CSIZE (3 << 4) /* Bits 4-5: Character size: */ +# define CS5 (0 << 4) /* 5 bits */ +# define CS6 (1 << 4) /* 6 bits */ +# define CS7 (2 << 4) /* 7 bits */ +# define CS8 (3 << 4) /* 8 bits */ +#define CSTOPB (1 << 6) /* Bit 6: Send two stop bits, else one */ +#define CREAD (1 << 7) /* Bit 7: Enable receiver */ +#define PARENB (1 << 8) /* Bit 8: Parity enable */ +#define PARODD (1 << 9) /* Bit 9: Odd parity, else even */ +#define HUPCL (1 << 10) /* Bit 10: Hang up on last close */ +#define CLOCAL (1 << 11) /* Bit 11: Ignore modem status lines */ +#define CCTS_OFLOW (1 << 29) /* Bit 29: CTS flow control of output */ +#define CRTS_IFLOW (1u << 31) /* Bit 31: RTS flow control of input */ +#define CRTSCTS (CCTS_OFLOW | CRTS_IFLOW) + +/* Local Modes (c_lflag in the termios structure) */ + +#define ISIG (1 << 0) /* Bit 0: Enable signals */ +#define ICANON (1 << 1) /* Bit 1: Canonical input (erase and kill processing) */ +#define XCASE (1 << 2) /* Bit 2: Canonical upper/lower presentation (LEGACY) */ +#define ECHO (1 << 3) /* Bit 3: Enable echo */ +#define ECHOE (1 << 4) /* Bit 4: Echo erase character as error correcting backspace */ +#define ECHOK (1 << 5) /* Bit 5: Echo KILL */ +#define ECHONL (1 << 6) /* Bit 6: Echo NL */ +#define NOFLSH (1 << 7) /* Bit 7: Disable flush after interrupt or quit */ +#define TOSTOP (1 << 8) /* Bit 8: Send SIGTTOU for background output */ +#define IEXTEN (1 << 15) /* Bit 15: Enable extended input character processing */ + +/* The following are subscript names for the termios c_cc array. + * + * Common characters: VINTR, VQUIT, VSTART, VSTOP, VSUSP + * + * VINTR: Interrupt character (Default ETX, Control-C) + * VQUIT: Quit character (Default FS, Control-\) + * VSTART: Start character (Default DC1, Control-Q) + * VSTOP: Stop character (Default DC3, Control-S) + * VSUSP: Suspend character (Default SUB, Control-Z) + * + * Canonical mode: Adds VEOF, VEOL, VERASE, VKILL + * + * VEOL: End-of-file character (Default SUB, Control-Z) + * VEOF: End-of-line character (Default NUL) + * VERASE: Erase character (Default DEL or BS, Control-H) + * VKILL: Kill character (Default NAK or BS, Control-U) + * + * Non-canonical mode: Adds VMIN, VTIME + * + * VMIN: Minimum number of characters for non-canonical read + * VTIME: Timeout in deciseconds for non-canonical read + */ + +#define VINTR 0 /* Bit 0: INTR character */ +#define VQUIT 1 /* Bit 1: QUIT character */ +#define VERASE 2 /* Bit 2: ERASE character (canonical mode) */ +#define VKILL 3 /* Bit 3: KILL character (canonical mode) */ +#define VEOF 4 /* Bit 4: EOF character (canonical mode) */ +#define VTIME 5 /* Bit 5: TIME value (non-canonical mode) */ +#define VMIN 6 /* Bit 6: MIN value (non-canonical mode) */ +#define VSTART 8 /* Bit 8: START character */ +#define VSTOP 9 /* Bit 9: STOP character */ +#define VSUSP 10 /* Bit 10: SUSP character */ +#define VEOL 11 /* Bit 11: EOL character (canonical mode) */ +#define NCCS 12 /* Bit 12: Size of the array c_cc for control characters */ + +/* Baud Rate Selection. These are instances of type speed_t. Values of + * 38400 and below are specified by POSIX; values above 38400 are sometimes + * referred to as extended values and most values appear in most termios.h + * implementations. + */ + +#define B0 0000000 /* Hang up */ +#define B50 0000001 /* 50 baud */ +#define B75 0000002 /* 75 baud */ +#define B110 0000003 /* 110 baud */ +#define B134 0000004 /* 134.5 baud */ +#define B150 0000005 /* 150 baud */ +#define B200 0000006 /* 200 baud */ +#define B300 0000007 /* 300 baud */ +#define B600 0000010 /* 600 baud */ +#define B1200 0000011 /* 1,200 baud */ +#define B1800 0000012 /* 1,800 baud */ +#define B2400 0000013 /* 2,400 baud */ +#define B4800 0000014 /* 4,800 baud */ +#define B9600 0000015 /* 9,600 baud */ +#define B19200 0000016 /* 19,200 baud */ +#define B38400 0000017 /* 38,400 baud */ + +#define B57600 0010001 /* 57,600 baud */ +#define B115200 0010002 /* 115,200 baud */ +#define B230400 0010003 /* 230,400 baud */ +#define B460800 0010004 /* 460,800 baud */ +#define B500000 0010005 /* 500,000 baud */ +#define B576000 0010006 /* 576,000 baud */ +#define B921600 0010007 /* 921,600 baud */ +#define B1000000 0010010 /* 1,000,000 baud */ +#define B1152000 0010011 /* 1,152,000 baud */ +#define B1500000 0010012 /* 1,500,000 baud */ +#define B2000000 0010013 /* 2,000,000 baud */ +#define B2500000 0010014 /* 2,500,000 baud */ +#define B3000000 0010015 /* 3,000,000 baud */ +#define B3500000 0010016 /* 3,500,000 baud */ +#define B4000000 0010017 /* 4,000,000 baud */ + +/* Attribute Selection (used with tcsetattr()) */ + +#define TCSANOW 0 /* Change attributes immediately */ +#define TCSADRAIN 1 /* Change attributes when output has drained */ +#define TCSAFLUSH 2 /* Change attributes when output has drained; + * also flush pending input */ + +/* Line Control (used with tcflush()) */ + +#define TCIFLUSH 0 /* Flush pending input */ +#define TCOFLUSH 1 /* Flush untransmitted output */ +#define TCIOFLUSH 2 /* Flush both pending input and untransmitted + * output */ + +/* Constants for use with tcflow() */ + +#define TCOOFF 0 /* Suspend output */ +#define TCOON 1 /* Restart output */ +#define TCIOFF 2 /* Transmit a STOP character, intended to + * suspend input data */ +#define TCION 3 /* Transmit a START character, intended to + * restart input data */ + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +/* Baud rate selection */ + +typedef unsigned long speed_t; /* Used for terminal baud rates */ + +/* Types used within the termios structure */ + +typedef unsigned int tcflag_t; /* Used for terminal modes */ +typedef unsigned char cc_t; /* Used for terminal special characters */ + +/* The termios structure */ + +struct termios { + /* Exposed fields defined by POSIX */ + + tcflag_t c_iflag; /* Input modes */ + tcflag_t c_oflag; /* Output modes */ + tcflag_t c_cflag; /* Control modes */ + tcflag_t c_lflag; /* Local modes */ + cc_t c_cc[NCCS]; /* Control chars */ + + /* Implementation specific fields. For portability reasons, these fields + * should not be accessed directly, but rather through only through the + * cf[set|get][o|i]speed() POSIX interfaces. + */ + + speed_t c_speed; /* Input/output speed (non-POSIX) */ +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/* The cfgetspeed() function is a non-POSIX function will extract the baud + * from the termios structure to which the termiosp argument points. NuttX + * does not control input/output baud independently. Both must be the same. + * The POSIX standard interfaces, cfigetispeed() and cfigetospeed() are + * supported by simply defining them to be cfgetspeed(). + * The return value is baud value(9600). + */ + +speed_t cfgetspeed(const struct termios *termiosp); +#define cfgetispeed(termiosp) cfgetspeed(termiosp) +#define cfgetospeed(termiosp) cfgetspeed(termiosp) + +/* The cfsetspeed() function is a non-POSIX function that sets the baud + * stored in the structure pointed to by termiosp to speed. NuttX does + * not control input/output baud independently. Both must be the same. + * The POSIX standard interfaces, cfigetispeed() and cfigetospeed() are + * supported by simply defining them to be cfsetspeed(). + * Speed could be baud value(9600) or could be baud mask(B9600). + */ + +int cfsetspeed(struct termios *termiosp, speed_t speed); +#define cfsetispeed(termiosp,speed) cfsetspeed(termiosp,speed) +#define cfsetospeed(termiosp,speed) cfsetspeed(termiosp,speed) + +/* The cfmakeraw() function is a non-POSIX function that sets the terminal + * to something like the "raw" mode. + */ + +void cfmakeraw(struct termios *termiosp); + +/* Wait for transmission of output */ + +int tcdrain(int fd); + +/* Suspend or restart the transmission or reception of data */ + +int tcflow(int fd, int action); + +/* Flush non-transmitted output data, non-read input data or both */ + +int tcflush(int fd, int cmd); + +/* Get the parameters associated with the terminal */ + +int tcgetattr(int fd, struct termios *termiosp); + +/* Get process group ID for session leader for controlling terminal */ + +pid_t tcgetsid(int fd); + +/* Send a "break" for a specific duration */ + +int tcsendbreak(int fd, int duration); + +/* Set the parameters associated with the terminal */ + +int tcsetattr(int fd, int options, const struct termios *termiosp); + +#undef EXTERN +#ifdef __cplusplus +} +#endif -typedef unsigned int speed_t; +#endif /* __INCLUDE_TERMIOS_H */ diff --git a/platforms/qurt/unresolved_symbols.c b/platforms/qurt/unresolved_symbols.c index 0d5ef43d5882..820ea1f4c40b 100644 --- a/platforms/qurt/unresolved_symbols.c +++ b/platforms/qurt/unresolved_symbols.c @@ -2,6 +2,7 @@ #include #include #include +#include __attribute__((visibility("default"))) void free(void *ptr) { @@ -31,3 +32,21 @@ __attribute__((visibility("default"))) int nanosleep(const struct timespec *req, PX4_ERR("Undefined nanosleep called"); return -1; } + +__attribute__((visibility("default"))) int tcgetattr(int fd, struct termios *termiosp) +{ + PX4_ERR("Undefined tcgetattr called"); + return -1; +} + +__attribute__((visibility("default"))) int cfsetspeed(struct termios *termiosp, speed_t speed) +{ + PX4_ERR("Undefined cfsetspeed called"); + return -1; +} + +__attribute__((visibility("default"))) int tcsetattr(int fd, int options, const struct termios *termiosp) +{ + PX4_ERR("Undefined tcsetattr called"); + return -1; +} From 0283dc245939b6e0217a69bb8a4b10552c7f0fd9 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 2 Apr 2024 13:46:53 +1300 Subject: [PATCH 047/652] gps: fix Septentrino serial read (#22936) For Septententrino we seem to sometimes fill the buffer pretty full. If we ask for too much, readAtLeast will fail completely and make the GPS discovery logic fall over. Therefore, let's not ask for too much and just read what we can given the available buffer. Signed-off-by: Julian Oes --- src/drivers/gps/gps.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index aa8b8d7543f5..fe6f82ec7fbc 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -471,14 +471,14 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user) int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout) { int ret = 0; - const unsigned character_count = 32; // minimum bytes that we want to read + const size_t character_count = 32; // minimum bytes that we want to read const int max_timeout = 50; int timeout_adjusted = math::min(max_timeout, timeout); handleInjectDataTopic(); if (_interface == GPSHelper::Interface::UART) { - ret = _uart.readAtLeast(buf, buf_length, character_count, timeout_adjusted); + ret = _uart.readAtLeast(buf, buf_length, math::min(character_count, buf_length), timeout_adjusted); // SPI is only supported on LInux #if defined(__PX4_LINUX) @@ -1560,4 +1560,4 @@ int gps_main(int argc, char *argv[]) { return GPS::main(argc, argv); -} +} \ No newline at end of file From 461b146ba8bea4ec3da70d2eb85734272852f93c Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 20:44:57 +0200 Subject: [PATCH 048/652] drivers: barometer: ms5837 fix compilation error Fixes MS5837.cpp:343:29: error: 'T' was not declared in this scope by using last temperature instead --- src/drivers/barometer/invensense/icp10100/Kconfig | 5 ----- src/drivers/barometer/invensense/icp10111/Kconfig | 6 ------ src/drivers/barometer/ms5837/MS5837.cpp | 2 +- 3 files changed, 1 insertion(+), 12 deletions(-) delete mode 100644 src/drivers/barometer/invensense/icp10100/Kconfig delete mode 100644 src/drivers/barometer/invensense/icp10111/Kconfig diff --git a/src/drivers/barometer/invensense/icp10100/Kconfig b/src/drivers/barometer/invensense/icp10100/Kconfig deleted file mode 100644 index 2f883bccd420..000000000000 --- a/src/drivers/barometer/invensense/icp10100/Kconfig +++ /dev/null @@ -1,5 +0,0 @@ -menuconfig DRIVERS_BAROMETER_INVENSENSE_ICP10100 - bool "icp10100" - default n - ---help--- - Enable support for icp10100 diff --git a/src/drivers/barometer/invensense/icp10111/Kconfig b/src/drivers/barometer/invensense/icp10111/Kconfig deleted file mode 100644 index 1681c07d3831..000000000000 --- a/src/drivers/barometer/invensense/icp10111/Kconfig +++ /dev/null @@ -1,6 +0,0 @@ -menuconfig DRIVERS_BAROMETER_INVENSENSE_ICP10111 - bool "icp10100" - default n - ---help--- - Enable support for icp10111 - diff --git a/src/drivers/barometer/ms5837/MS5837.cpp b/src/drivers/barometer/ms5837/MS5837.cpp index 7041d886d937..00382070dedf 100644 --- a/src/drivers/barometer/ms5837/MS5837.cpp +++ b/src/drivers/barometer/ms5837/MS5837.cpp @@ -340,7 +340,7 @@ int MS5837::_collect() sensor_baro.timestamp_sample = timestamp_sample; sensor_baro.device_id = get_device_id(); sensor_baro.pressure = P; - sensor_baro.temperature = T; + sensor_baro.temperature = _last_temperature; sensor_baro.error_count = perf_event_count(_comms_errors); sensor_baro.timestamp = hrt_absolute_time(); _sensor_baro_pub.publish(sensor_baro); From daee37d377197d3469fd45512f1aacaeca391dd9 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 20:57:32 +0200 Subject: [PATCH 049/652] drivers: tap_esc: fix Werror=maybe-uninitialized compilation --- src/drivers/tap_esc/tap_esc_uploader.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/drivers/tap_esc/tap_esc_uploader.cpp b/src/drivers/tap_esc/tap_esc_uploader.cpp index 03b3b84c5056..350e366b7347 100644 --- a/src/drivers/tap_esc/tap_esc_uploader.cpp +++ b/src/drivers/tap_esc/tap_esc_uploader.cpp @@ -163,7 +163,7 @@ int TAP_ESC_UPLOADER::upload_id(uint8_t esc_id, int32_t fw_size) /****************************************** * second: get device bootloader revision ******************************************/ - uint32_t bl_rev; + uint32_t bl_rev = 0; ret = get_device_info(esc_id, PROTO_GET_DEVICE, PROTO_DEVICE_BL_REV, bl_rev); if (ret == OK) { @@ -390,7 +390,7 @@ int TAP_ESC_UPLOADER::checkcrc(const char *filenames[]) return -EIO; } - uint32_t temp_revision; + uint32_t temp_revision = 0; /* get device bootloader revision */ ret = get_device_info(esc_id, PROTO_GET_DEVICE, PROTO_DEVICE_BL_REV, temp_revision); @@ -1098,7 +1098,7 @@ int TAP_ESC_UPLOADER::verify_crc(uint8_t esc_id, size_t fw_size_local) uint32_t sum = 0; uint32_t bytes_read = 0; uint32_t crc = 0; - uint32_t fw_size_remote; + uint32_t fw_size_remote = 0; uint8_t fill_blank = 0xff; file_buf = new uint8_t[PROG_MULTI_MAX]; From 54f044c04ab6bf26db69f518b004f38433581212 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:16:32 +0200 Subject: [PATCH 050/652] examples: matlab_csv_serial: fix compilation Update uORB definition and sprintf float formatting --- src/examples/matlab_csv_serial/matlab_csv_serial.c | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c index 0ef2ab28af70..b7ccbd014335 100644 --- a/src/examples/matlab_csv_serial/matlab_csv_serial.c +++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c @@ -41,6 +41,7 @@ */ #include +#include #include #include #include @@ -48,7 +49,6 @@ #include #include #include -#include #include #include #include @@ -60,6 +60,9 @@ #include #include +#include +#include + __EXPORT int matlab_csv_serial_main(int argc, char *argv[]); static bool thread_should_exit = false; /**< Daemon exit flag */ static bool thread_running = false; /**< Daemon status flag */ @@ -221,9 +224,9 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(sensor_gyro), gyro1_sub, &gyro1); // write out on accel 0, but collect for all other sensors as they have updates - dprintf(serial_fd, "%llu,%d,%d,%d,%d,%d,%d\n", accel0.timestamp, (int)accel0.x_raw, (int)accel0.y_raw, - (int)accel0.z_raw, - (int)accel1.x_raw, (int)accel1.y_raw, (int)accel1.z_raw); + dprintf(serial_fd, "%"PRId64",%d,%d,%d,%d,%d,%d\n", accel0.timestamp, (int)accel0.x, (int)accel0.y, + (int)accel0.z, + (int)accel1.x, (int)accel1.y, (int)accel1.z); } } From 05badb5d761c53162b8daa055200439eba38f2a2 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:17:16 +0200 Subject: [PATCH 051/652] systemcmds: microbench: %s doesn't except nullptr use "null" instead --- src/systemcmds/microbench/microbench_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/microbench/microbench_main.cpp b/src/systemcmds/microbench/microbench_main.cpp index f56dbd6a2c68..56e441cc0936 100644 --- a/src/systemcmds/microbench/microbench_main.cpp +++ b/src/systemcmds/microbench/microbench_main.cpp @@ -69,7 +69,7 @@ const struct { {"microbench_matrix", test_microbench_matrix, 0}, {"microbench_uorb", test_microbench_uorb, 0}, - {nullptr, nullptr, 0} + {"null", nullptr, 0} }; #define NMICROBENCHMARKS (sizeof(microbenchmarks) / sizeof(microbenchmarks[0])) From 0c5b25efc52fd2fef22adb7e46d463cfac88d768 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:18:16 +0200 Subject: [PATCH 052/652] systemcmds: reflect: write return needs to be used for werror checks --- src/systemcmds/reflect/reflect.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/systemcmds/reflect/reflect.c b/src/systemcmds/reflect/reflect.c index 4ef393682deb..c74ae06a887e 100644 --- a/src/systemcmds/reflect/reflect.c +++ b/src/systemcmds/reflect/reflect.c @@ -121,7 +121,9 @@ reflect_main(int argc, char *argv[]) } if (n > 0) { - write(1, buf, n); + if (write(1, buf, n) < 0) { + return -1; + } } total += n; From 650ea6ef4aa29bafc9a923269c09cca26f2cf1ca Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:18:49 +0200 Subject: [PATCH 053/652] drivers: transponder: don't free pre-allocated memory --- src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp b/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp index 379f651be9f5..b11f13f237ba 100644 --- a/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp +++ b/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp @@ -52,8 +52,6 @@ SagetechMXS::SagetechMXS(const char *port) : SagetechMXS::~SagetechMXS() { - free((char *)_port); - if (!(_fd < 0)) { close(_fd); } From 4889ac0ebbdf6e3445b6e57f217e08fc88bd574c Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:19:27 +0200 Subject: [PATCH 054/652] drivers: uavcan: fix werror uninitialized error --- src/drivers/uavcan/uavcan_servers.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/uavcan/uavcan_servers.cpp b/src/drivers/uavcan/uavcan_servers.cpp index fa4b2aab10de..3d35ea523ed5 100644 --- a/src/drivers/uavcan/uavcan_servers.cpp +++ b/src/drivers/uavcan/uavcan_servers.cpp @@ -180,7 +180,7 @@ void UavcanServers::migrateFWFromRoot(const char *sd_path, const char *sd_root_p while ((dev_dirent = readdir(sd_root_dir)) != nullptr) { - uavcan_posix::FirmwareVersionChecker::AppDescriptor descriptor; + uavcan_posix::FirmwareVersionChecker::AppDescriptor descriptor{0}; // Looking for all uavcan.bin files. From 127d74f2e10e66c49053f5d018db86b9caf3d8ae Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:20:06 +0200 Subject: [PATCH 055/652] drivers: vector: Fix PX4 SITL x86 compilation --- src/drivers/ins/vectornav/libvnc/include/vn/util.h | 4 ++++ src/drivers/ins/vectornav/libvnc/src/vn/protocol/spi.c | 2 -- src/drivers/ins/vectornav/libvnc/src/vn/xplat/event.c | 2 ++ src/drivers/ins/vectornav/libvnc/src/vn/xplat/time.c | 2 ++ 4 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/drivers/ins/vectornav/libvnc/include/vn/util.h b/src/drivers/ins/vectornav/libvnc/include/vn/util.h index 02388f41f08a..6da16dfd1c31 100644 --- a/src/drivers/ins/vectornav/libvnc/include/vn/util.h +++ b/src/drivers/ins/vectornav/libvnc/include/vn/util.h @@ -11,6 +11,10 @@ #include "vn/util/export.h" #include "vn/types.h" +#ifndef UNUSED +#define UNUSED(x) (void)(sizeof(x)) +#endif + #ifdef __cplusplus extern "C" { #endif diff --git a/src/drivers/ins/vectornav/libvnc/src/vn/protocol/spi.c b/src/drivers/ins/vectornav/libvnc/src/vn/protocol/spi.c index d162a2f9aa73..fefce9ba515b 100644 --- a/src/drivers/ins/vectornav/libvnc/src/vn/protocol/spi.c +++ b/src/drivers/ins/vectornav/libvnc/src/vn/protocol/spi.c @@ -2,8 +2,6 @@ #include #include "vn/util.h" -//#define UNUSED(x) (void)(sizeof(x)) - VnError VnSpi_genGenericCommand( char cmdId, char* buffer, diff --git a/src/drivers/ins/vectornav/libvnc/src/vn/xplat/event.c b/src/drivers/ins/vectornav/libvnc/src/vn/xplat/event.c index 958315b0421c..996fa4cd1baf 100644 --- a/src/drivers/ins/vectornav/libvnc/src/vn/xplat/event.c +++ b/src/drivers/ins/vectornav/libvnc/src/vn/xplat/event.c @@ -1,7 +1,9 @@ /* Enable IEEE Std 1003.1b-1993 functionality required for clock_gettime. */ #if defined(__linux__) || defined(__NUTTX__) /* Works for Ubuntu 15.10 */ +#ifndef _POSIX_C_SOURCE #define _POSIX_C_SOURCE 199309L +#endif #elif defined __CYGWIN__ /* Works for Cygwin 2.4.0 64-bit */ #define _POSIX_TIMERS 1 diff --git a/src/drivers/ins/vectornav/libvnc/src/vn/xplat/time.c b/src/drivers/ins/vectornav/libvnc/src/vn/xplat/time.c index f06d415de0c7..9548f8c65341 100644 --- a/src/drivers/ins/vectornav/libvnc/src/vn/xplat/time.c +++ b/src/drivers/ins/vectornav/libvnc/src/vn/xplat/time.c @@ -1,7 +1,9 @@ /* Enable IEEE Std 1003.1b-1993 functionality required for clock_gettime. */ #if defined(__linux__) || defined(__NUTTX__) /* Works for Ubuntu 15.10 */ +#ifndef _POSIX_C_SOURCE #define _POSIX_C_SOURCE 199309L +#endif #elif defined __CYGWIN__ /* Works for Cygwin 2.4.0 64-bit */ #define _POSIX_TIMERS 1 From fe8a5eae9936e5b35a6e5d006d1bfea9bb26191f Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:20:38 +0200 Subject: [PATCH 056/652] drivers: bmi088_i2c: Enforce I2C driver can only be used when SPI version isn't selected Solves multiple references compilation errors --- src/drivers/imu/bosch/bmi088_i2c/Kconfig | 1 + 1 file changed, 1 insertion(+) diff --git a/src/drivers/imu/bosch/bmi088_i2c/Kconfig b/src/drivers/imu/bosch/bmi088_i2c/Kconfig index b4e48f2da9e8..763070403088 100644 --- a/src/drivers/imu/bosch/bmi088_i2c/Kconfig +++ b/src/drivers/imu/bosch/bmi088_i2c/Kconfig @@ -1,5 +1,6 @@ menuconfig DRIVERS_IMU_BOSCH_BMI088_I2C bool "bosch bmi088_i2c" default n + depends on !DRIVERS_IMU_BOSCH_BMI088 ---help--- Enable support for bosch bmi088_i2c From d5b66cac2c85412ac5e4ca8b5acbb37e9730734b Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:21:42 +0200 Subject: [PATCH 057/652] drivers: cyphal: Fix ARM/x86 printf werror portability error --- src/drivers/cyphal/Subscribers/uORB/uorb_subscriber.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/cyphal/Subscribers/uORB/uorb_subscriber.hpp b/src/drivers/cyphal/Subscribers/uORB/uorb_subscriber.hpp index a80edf292d75..63498e8c676f 100644 --- a/src/drivers/cyphal/Subscribers/uORB/uorb_subscriber.hpp +++ b/src/drivers/cyphal/Subscribers/uORB/uorb_subscriber.hpp @@ -85,7 +85,7 @@ class uORB_over_UAVCAN_Subscriber : public UavcanDynamicPortSubscriber _uorb_pub.publish(*data); } else { - PX4_ERR("uORB over UAVCAN %s payload size mismatch got %d expected %d", + PX4_ERR("uORB over UAVCAN %s payload size mismatch got %zu expected %zu", _subj_sub._subject_name, receive.payload_size, get_payload_size(data)); } }; From 8817f59108d68fd60c0279fc4b7d86035223b8d4 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:24:02 +0200 Subject: [PATCH 058/652] v6x-rt: Split ITCM static and auto-generated functions --- .../scripts/itcm_functions_includes.ld | 72 ------------------- .../scripts/itcm_static_functions.ld | 72 +++++++++++++++++++ .../fmu-v6xrt/nuttx-config/scripts/script.ld | 1 + platforms/nuttx/CMakeLists.txt | 2 +- 4 files changed, 74 insertions(+), 73 deletions(-) create mode 100644 boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld 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 5951ceed7742..60a76f97e1b9 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 @@ -1,65 +1,3 @@ -/* Static */ -*(.text.arm_ack_irq) -*(.text.arm_doirq) -*(.text.arm_svcall) -*(.text.arm_switchcontext) -*(.text.board_autoled_on) -*(.text.clock_timer) -*(.text.exception_common) -*(.text.hrt_absolute_time) -*(.text.hrt_tim_isr) -*(.text.imxrt_configwaitints) -*(.text.imxrt_dma_callback) -*(.text.imxrt_dmach_interrupt) -*(.text.imxrt_dmaterminate) -*(.text.imxrt_edma_interrupt) -*(.text.imxrt_endwait) -*(.text.imxrt_gpio3_16_31_interrupt) -*(.text.imxrt_interrupt) -*(.text.imxrt_lpi2c_isr) -*(.text.imxrt_recvdma) -*(.text.imxrt_tcd_free) -*(.text.imxrt_timerisr) -*(.text.imxrt_usbinterrupt) -*(.text.irq_dispatch) -*(.text.memcpy) -*(.text.nxsched_add_blocked) -*(.text.nxsched_add_prioritized) -*(.text.nxsched_add_readytorun) -*(.text.nxsched_get_files) -*(.text.nxsched_get_tcb) -*(.text.nxsched_merge_pending) -*(.text.nxsched_process_timer) -*(.text.nxsched_remove_blocked) -*(.text.nxsched_remove_readytorun) -*(.text.nxsched_resume_scheduler) -*(.text.nxsched_suspend_scheduler) -*(.text.nxsem_add_holder) -*(.text.nxsem_add_holder_tcb) -*(.text.nxsem_clockwait) -*(.text.nxsem_foreachholder) -*(.text.nxsem_freecount0holder) -*(.text.nxsem_freeholder) -*(.text.nxsem_post) -*(.text.nxsem_release_holder) -*(.text.nxsem_restore_baseprio) -*(.text.nxsem_tickwait) -*(.text.nxsem_timeout) -*(.text.nxsem_trywait) -*(.text.nxsem_wait) -*(.text.nxsem_wait_uninterruptible) -*(.text.nxsig_timedwait) -*(.text.sched_lock) -*(.text.sched_note_resume) -*(.text.sched_note_suspend) -*(.text.sched_unlock) -*(.text.sq_addafter) -*(.text.sq_addlast) -*(.text.sq_rem) -*(.text.sq_remafter) -*(.text.sq_remfirst) -*(.text.uart_connected) -*(.text.wd_timer) /* Auto-generated */ *(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) *(.text._ZN13MavlinkStream6updateERKy) @@ -70,11 +8,9 @@ *(.text._ZN22MulticopterRateControl3RunEv.part.0) *(.text._ZN7Mavlink9task_mainEiPPc) *(.text._ZN7sensors22VehicleAngularVelocity3RunEv) -*(.text.memset) *(.text._ZN4uORB12Subscription9subscribeEv.part.0) *(.text._ZN4uORB7Manager13orb_data_copyEPvS1_Rjb) *(.text._ZN4uORB10DeviceNode5writeEP4filePKcj) -*(.text.strcmp) *(.text._ZN4uORB10DeviceNode7publishEPK12orb_metadataPvPKv) *(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah) *(.text._Z12get_orb_meta6ORB_ID) @@ -82,15 +18,12 @@ *(.text._ZN3px49WorkQueue3RunEv) *(.text._ZN9ICM42688P11ProcessGyroERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh) *(.text._ZN4EKF23RunEv) -*(.text.imxrt_lpspi_exchange) -*(.text.imxrt_dmach_xfrsetup) *(.text._ZN7sensors10VehicleIMU7PublishEv) *(.text._ZN4math17WelfordMeanVectorIfLj3EE6updateERKN6matrix6VectorIfLj3EEE) *(.text._ZN7sensors10VehicleIMU10UpdateGyroEv) *(.text._ZN9ICM42688P8FIFOReadERKyh) *(.text._ZN3Ekf20controlGravityFusionERKN9estimator9imuSampleE) *(.text._ZN16PX4Accelerometer10updateFIFOER19sensor_accel_fifo_s) -*(.text.up_block_task) *(.text._ZN7sensors22VehicleAngularVelocity19CalibrateAndPublishERKyRKN6matrix7Vector3IfEES7_) *(.text._ZN4uORB12Subscription10advertisedEv) *(.text._ZNK15AttitudeControl6updateERKN6matrix10QuaternionIfEE) @@ -99,7 +32,6 @@ *(.text._ZN4uORB12Subscription6updateEPv) *(.text._ZN12PX4Gyroscope10updateFIFOER18sensor_gyro_fifo_s) *(.text._ZN7sensors10VehicleIMU3RunEv) -*(.text.up_unblock_task) *(.text.__aeabi_l2f) *(.text._ZN39ControlAllocationSequentialDesaturation23computeDesaturationGainERKN6matrix6VectorIfLj16EEES4_) *(.text.pthread_mutex_timedlock) @@ -121,16 +53,12 @@ *(.text._ZN9ICM42688P7RunImplEv) *(.text._ZN4uORB12Subscription9subscribeEv) *(.text.param_get) -*(.text._do_memcpy) *(.text._ZN7sensors22VehicleAngularVelocity21SensorSelectionUpdateERKyb) *(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE) -*(.text.wd_start) -*(.text.hrt_call_enter) *(.text._ZN4EKF220PublishLocalPositionERKy) *(.text._mav_finalize_message_chan_send) *(.text._ZN3Ekf19fixCovarianceErrorsEb) *(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb) -*(.text.ioctl) *(.text._ZN6events12SendProtocol6updateERKy) *(.text._ZN6device3SPI8transferEPhS1_j) *(.text._ZN27MavlinkStreamDistanceSensor4sendEv) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld new file mode 100644 index 000000000000..5d9cd8de738b --- /dev/null +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld @@ -0,0 +1,72 @@ +/* Static */ +*(.text.arm_ack_irq) +*(.text.arm_doirq) +*(.text.arm_svcall) +*(.text.arm_switchcontext) +*(.text.board_autoled_on) +*(.text.clock_timer) +*(.text.exception_common) +*(.text.hrt_absolute_time) +*(.text.hrt_call_enter) +*(.text.hrt_tim_isr) +*(.text.imxrt_configwaitints) +*(.text.imxrt_dma_callback) +*(.text.imxrt_dmach_interrupt) +*(.text.imxrt_dmach_xfrsetup) +*(.text.imxrt_dmaterminate) +*(.text.imxrt_edma_interrupt) +*(.text.imxrt_endwait) +*(.text.imxrt_gpio3_16_31_interrupt) +*(.text.imxrt_interrupt) +*(.text.imxrt_lpi2c_isr) +*(.text.imxrt_lpspi_exchange) +*(.text.imxrt_recvdma) +*(.text.imxrt_tcd_free) +*(.text.imxrt_timerisr) +*(.text.imxrt_usbinterrupt) +*(.text.irq_dispatch) +*(.text.ioctl) +*(.text.memcpy) +*(.text.memset) +*(.text.nxsched_add_blocked) +*(.text.nxsched_add_prioritized) +*(.text.nxsched_add_readytorun) +*(.text.nxsched_get_files) +*(.text.nxsched_get_tcb) +*(.text.nxsched_merge_pending) +*(.text.nxsched_process_timer) +*(.text.nxsched_remove_blocked) +*(.text.nxsched_remove_readytorun) +*(.text.nxsched_resume_scheduler) +*(.text.nxsched_suspend_scheduler) +*(.text.nxsem_add_holder) +*(.text.nxsem_add_holder_tcb) +*(.text.nxsem_clockwait) +*(.text.nxsem_foreachholder) +*(.text.nxsem_freecount0holder) +*(.text.nxsem_freeholder) +*(.text.nxsem_post) +*(.text.nxsem_release_holder) +*(.text.nxsem_restore_baseprio) +*(.text.nxsem_tickwait) +*(.text.nxsem_timeout) +*(.text.nxsem_trywait) +*(.text.nxsem_wait) +*(.text.nxsem_wait_uninterruptible) +*(.text.nxsig_timedwait) +*(.text.sched_lock) +*(.text.sched_note_resume) +*(.text.sched_note_suspend) +*(.text.sched_unlock) +*(.text.strcmp) +*(.text.sq_addafter) +*(.text.sq_addlast) +*(.text.sq_rem) +*(.text.sq_remafter) +*(.text.sq_remfirst) +*(.text.uart_connected) +*(.text.up_block_task) +*(.text.up_unblock_task) +*(.text.wd_timer) +*(.text.wd_start) +*(.text._do_memcpy) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld index dc05748b6adf..70d861f30ab2 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld @@ -83,6 +83,7 @@ SECTIONS _sitcmfuncs = ABSOLUTE(.); FILL(0xFF) . = 0x40 ; + INCLUDE "itcm_static_functions.ld" INCLUDE "itcm_functions_includes.ld" . = ALIGN(8); _eitcmfuncs = ABSOLUTE(.); diff --git a/platforms/nuttx/CMakeLists.txt b/platforms/nuttx/CMakeLists.txt index 1ab6cdfe00f4..cd8385827e85 100644 --- a/platforms/nuttx/CMakeLists.txt +++ b/platforms/nuttx/CMakeLists.txt @@ -266,7 +266,7 @@ else() -fno-exceptions -fno-rtti -Wl,--script=${NUTTX_CONFIG_DIR_CYG}/scripts/${SCRIPT_PREFIX}script.ld - -L${NUTTX_CONFIG_DIR_CYG}/scripts/${SCRIPT_PREFIX} + -L${NUTTX_CONFIG_DIR_CYG}/scripts -Wl,-Map=${PX4_CONFIG}.map -Wl,--warn-common -Wl,--gc-sections From f082de5db7e37df39cad89b4ad9890a889db0ea5 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:25:45 +0200 Subject: [PATCH 059/652] kconfig: Add dependencies --- src/drivers/linux_pwm_out/Kconfig | 1 + src/drivers/px4io/Kconfig | 1 + src/drivers/uavcan/Kconfig | 1 + src/drivers/uavcannode/Kconfig | 1 + src/modules/simulation/Kconfig | 1 + src/systemcmds/bl_update/Kconfig | 1 + src/systemcmds/hardfault_log/Kconfig | 1 + src/systemcmds/io_bypass_control/Kconfig | 1 + src/systemcmds/mft/Kconfig | 1 + src/systemcmds/mtd/Kconfig | 1 + src/systemcmds/netman/Kconfig | 1 + src/systemcmds/nshterm/Kconfig | 1 + 12 files changed, 12 insertions(+) diff --git a/src/drivers/linux_pwm_out/Kconfig b/src/drivers/linux_pwm_out/Kconfig index d5728454da9e..ac7b54b2045a 100644 --- a/src/drivers/linux_pwm_out/Kconfig +++ b/src/drivers/linux_pwm_out/Kconfig @@ -1,5 +1,6 @@ menuconfig DRIVERS_LINUX_PWM_OUT bool "linux_pwm_out" default n + depends on PLATFORM_POSIX && !BOARD_TESTING ---help--- Enable support for linux_pwm_out diff --git a/src/drivers/px4io/Kconfig b/src/drivers/px4io/Kconfig index dd9b402249fa..16b114948578 100644 --- a/src/drivers/px4io/Kconfig +++ b/src/drivers/px4io/Kconfig @@ -1,5 +1,6 @@ menuconfig DRIVERS_PX4IO bool "px4io" default n + depends on platform_nuttx ---help--- Enable support for px4io diff --git a/src/drivers/uavcan/Kconfig b/src/drivers/uavcan/Kconfig index 1d91acb6221e..015894eb6ed0 100644 --- a/src/drivers/uavcan/Kconfig +++ b/src/drivers/uavcan/Kconfig @@ -1,6 +1,7 @@ menuconfig DRIVERS_UAVCAN bool "uavcan" default n + depends on PLATFORM_NUTTX ---help--- Enable support for uavcan diff --git a/src/drivers/uavcannode/Kconfig b/src/drivers/uavcannode/Kconfig index d20c2baf0624..9aa7073a5b0f 100644 --- a/src/drivers/uavcannode/Kconfig +++ b/src/drivers/uavcannode/Kconfig @@ -1,6 +1,7 @@ menuconfig DRIVERS_UAVCANNODE bool "uavcannode" default n + depends on BOARD_ROMFSROOT != "px4fmu_common" ---help--- Enable support for uavcannode diff --git a/src/modules/simulation/Kconfig b/src/modules/simulation/Kconfig index 569ab38c6ade..a417092ed94b 100644 --- a/src/modules/simulation/Kconfig +++ b/src/modules/simulation/Kconfig @@ -2,6 +2,7 @@ menu "Simulation" menuconfig COMMON_SIMULATION bool "Common simulation modules" default n + depends on PLATFORM_POSIX select MODULES_SIMULATION_BATTERY_SIMULATOR select MODULES_SIMULATION_PWM_OUT_SIM select MODULES_SIMULATION_SENSOR_AIRSPEED_SIM diff --git a/src/systemcmds/bl_update/Kconfig b/src/systemcmds/bl_update/Kconfig index f84e2f923efe..59e072f5b53c 100644 --- a/src/systemcmds/bl_update/Kconfig +++ b/src/systemcmds/bl_update/Kconfig @@ -1,6 +1,7 @@ menuconfig SYSTEMCMDS_BL_UPDATE bool "bl_update" default n + depends on PLATFORM_NUTTX ---help--- Enable support for bl_update diff --git a/src/systemcmds/hardfault_log/Kconfig b/src/systemcmds/hardfault_log/Kconfig index 50cfca75fca2..2c3908ed0de2 100644 --- a/src/systemcmds/hardfault_log/Kconfig +++ b/src/systemcmds/hardfault_log/Kconfig @@ -1,6 +1,7 @@ menuconfig SYSTEMCMDS_HARDFAULT_LOG bool "hardfault_log" default n + depends on PLATFORM_NUTTX ---help--- Enable support for hardfault_log diff --git a/src/systemcmds/io_bypass_control/Kconfig b/src/systemcmds/io_bypass_control/Kconfig index 4a50afd948ba..16c89bd13021 100644 --- a/src/systemcmds/io_bypass_control/Kconfig +++ b/src/systemcmds/io_bypass_control/Kconfig @@ -1,6 +1,7 @@ menuconfig SYSTEMCMDS_IO_BYPASS_CONTROL bool "IO Bypass control deamon" default n + depends on PLATFORM_NUTTX ---help--- Simple daemon that listens uORB actuator_outputs to control PWM output Useful for full offboard control using RTPS. diff --git a/src/systemcmds/mft/Kconfig b/src/systemcmds/mft/Kconfig index a104b1fd0dd3..554c9199fbfd 100644 --- a/src/systemcmds/mft/Kconfig +++ b/src/systemcmds/mft/Kconfig @@ -1,5 +1,6 @@ menuconfig SYSTEMCMDS_MFT bool "mft" default n + depends on PLATFORM_NUTTX ---help--- Enable support for mft diff --git a/src/systemcmds/mtd/Kconfig b/src/systemcmds/mtd/Kconfig index 661e8ee7f68e..dd01cfc3d21f 100644 --- a/src/systemcmds/mtd/Kconfig +++ b/src/systemcmds/mtd/Kconfig @@ -1,6 +1,7 @@ menuconfig SYSTEMCMDS_MTD bool "mtd" default n + depends on PLATFORM_NUTTX ---help--- Enable support for mtd diff --git a/src/systemcmds/netman/Kconfig b/src/systemcmds/netman/Kconfig index d2d122339793..60fa395f45ac 100644 --- a/src/systemcmds/netman/Kconfig +++ b/src/systemcmds/netman/Kconfig @@ -1,6 +1,7 @@ menuconfig SYSTEMCMDS_NETMAN bool "netman" default n + depends on PLATFORM_NUTTX ---help--- Enable support for netman diff --git a/src/systemcmds/nshterm/Kconfig b/src/systemcmds/nshterm/Kconfig index f9d20b0bfb72..3745b7bf238b 100644 --- a/src/systemcmds/nshterm/Kconfig +++ b/src/systemcmds/nshterm/Kconfig @@ -1,6 +1,7 @@ menuconfig SYSTEMCMDS_NSHTERM bool "nshterm" default n + depends on PLATFORM_NUTTX ---help--- Enable support for nshterm From 791d7894c82a2e112bbd18397087cb98adf1ab85 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:26:16 +0200 Subject: [PATCH 060/652] modules: zenoh: remove broken serial config and update topics --- src/modules/zenoh/Kconfig | 6 ------ src/modules/zenoh/Kconfig.topics | 35 ++++++++++++++++++++++++++++++++ 2 files changed, 35 insertions(+), 6 deletions(-) diff --git a/src/modules/zenoh/Kconfig b/src/modules/zenoh/Kconfig index d868dae392a0..904c03e2891d 100644 --- a/src/modules/zenoh/Kconfig +++ b/src/modules/zenoh/Kconfig @@ -12,12 +12,6 @@ if MODULES_ZENOH help Path to store network, publishers and subscribers configuration - config ZENOH_SERIAL - bool "Zenoh serial transport" - default n - help - Enables transport over serial (Not yet supported on NuttX/Linux) - config ZENOH_DEBUG int "Zenoh debug level" default 0 diff --git a/src/modules/zenoh/Kconfig.topics b/src/modules/zenoh/Kconfig.topics index 14866f5ebff6..58e5e522cda7 100644 --- a/src/modules/zenoh/Kconfig.topics +++ b/src/modules/zenoh/Kconfig.topics @@ -85,6 +85,10 @@ menu "Zenoh publishers/subscribers" bool "camera_trigger" default n + config ZENOH_PUBSUB_CAN_INTERFACE_STATUS + bool "can_interface_status" + default n + config ZENOH_PUBSUB_CELLULAR_STATUS bool "cellular_status" default n @@ -249,6 +253,10 @@ menu "Zenoh publishers/subscribers" bool "geofence_result" default n + config ZENOH_PUBSUB_GEOFENCE_STATUS + bool "geofence_status" + default n + config ZENOH_PUBSUB_GIMBAL_CONTROLS bool "gimbal_controls" default n @@ -465,6 +473,22 @@ menu "Zenoh publishers/subscribers" bool "orbit_status" default n + config ZENOH_PUBSUB_PARAMETER_RESET_REQUEST + bool "parameter_reset_request" + default n + + config ZENOH_PUBSUB_PARAMETER_SET_USED_REQUEST + bool "parameter_set_used_request" + default n + + config ZENOH_PUBSUB_PARAMETER_SET_VALUE_REQUEST + bool "parameter_set_value_request" + default n + + config ZENOH_PUBSUB_PARAMETER_SET_VALUE_RESPONSE + bool "parameter_set_value_response" + default n + config ZENOH_PUBSUB_PARAMETER_UPDATE bool "parameter_update" default n @@ -545,6 +569,10 @@ menu "Zenoh publishers/subscribers" bool "rpm" default n + config ZENOH_PUBSUB_RTL_STATUS + bool "rtl_status" + default n + config ZENOH_PUBSUB_RTL_TIME_ESTIMATE bool "rtl_time_estimate" default n @@ -851,6 +879,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_CAMERA_CAPTURE select ZENOH_PUBSUB_CAMERA_STATUS select ZENOH_PUBSUB_CAMERA_TRIGGER + select ZENOH_PUBSUB_CAN_INTERFACE_STATUS select ZENOH_PUBSUB_CELLULAR_STATUS select ZENOH_PUBSUB_COLLISION_CONSTRAINTS select ZENOH_PUBSUB_COLLISION_REPORT @@ -892,6 +921,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_FOLLOW_TARGET_STATUS select ZENOH_PUBSUB_GENERATOR_STATUS select ZENOH_PUBSUB_GEOFENCE_RESULT + select ZENOH_PUBSUB_GEOFENCE_STATUS select ZENOH_PUBSUB_GIMBAL_CONTROLS select ZENOH_PUBSUB_GIMBAL_DEVICE_ATTITUDE_STATUS select ZENOH_PUBSUB_GIMBAL_DEVICE_INFORMATION @@ -946,6 +976,10 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_ORB_TEST_LARGE select ZENOH_PUBSUB_ORB_TEST_MEDIUM select ZENOH_PUBSUB_ORBIT_STATUS + select ZENOH_PUBSUB_PARAMETER_RESET_REQUEST + select ZENOH_PUBSUB_PARAMETER_SET_USED_REQUEST + select ZENOH_PUBSUB_PARAMETER_SET_VALUE_REQUEST + select ZENOH_PUBSUB_PARAMETER_SET_VALUE_RESPONSE select ZENOH_PUBSUB_PARAMETER_UPDATE select ZENOH_PUBSUB_PING select ZENOH_PUBSUB_POSITION_CONTROLLER_LANDING_STATUS @@ -966,6 +1000,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REPLY select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REQUEST select ZENOH_PUBSUB_RPM + select ZENOH_PUBSUB_RTL_STATUS select ZENOH_PUBSUB_RTL_TIME_ESTIMATE select ZENOH_PUBSUB_SATELLITE_INFO select ZENOH_PUBSUB_SENSOR_ACCEL From a9ba0acb2abbfc1cd8272f99d655fbc9cda55349 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 31 Mar 2024 21:32:17 +0200 Subject: [PATCH 061/652] cmake: all allyes target for better CI coverage Currently only v6x-rt and SITL are supported But targets with label allyes will try to enable all kconfig symbols --- Tools/kconfig/allyesconfig.py | 126 +++++++++++ boards/px4/fmu-v6xrt/allyes.px4board | 1 + .../nuttx-config/scripts/allyes-script.ld | 197 ++++++++++++++++++ boards/px4/sitl/allyes.px4board | 0 cmake/kconfig.cmake | 12 +- 5 files changed, 335 insertions(+), 1 deletion(-) create mode 100644 Tools/kconfig/allyesconfig.py create mode 100644 boards/px4/fmu-v6xrt/allyes.px4board create mode 100644 boards/px4/fmu-v6xrt/nuttx-config/scripts/allyes-script.ld create mode 100644 boards/px4/sitl/allyes.px4board diff --git a/Tools/kconfig/allyesconfig.py b/Tools/kconfig/allyesconfig.py new file mode 100644 index 000000000000..889b659195ed --- /dev/null +++ b/Tools/kconfig/allyesconfig.py @@ -0,0 +1,126 @@ +#!/usr/bin/env python3 + +# Copyright (c) 2018-2019, Ulf Magnusson +# SPDX-License-Identifier: ISC + +""" +Writes a configuration file where as many symbols as possible are set to 'y'. + +The default output filename is '.config'. A different filename can be passed +in the KCONFIG_CONFIG environment variable. + +Usage for the Linux kernel: + + $ make [ARCH=] scriptconfig SCRIPT=Kconfiglib/allyesconfig.py +""" +import kconfiglib +import os + + +exception_list = [ + 'DRIVERS_BOOTLOADERS', # Only used for bootloader target + 'MODULES_PX4IOFIRMWARE', # Only needed for PX4IO firmware itself, maybe fix through dependencies + 'BOARD_LTO', # Experimental + 'BOARD_TESTING', # Don't build test suite + 'BOARD_CONSTRAINED_FLASH', # only used to reduce flash size + 'BOARD_NO_HELP', # only used to reduce flash size + 'BOARD_CONSTRAINED_MEMORY', # only used to reduce flash size + 'BOARD_EXTERNAL_METADATA', # only used to reduce flash size + 'BOARD_CRYPTO', # Specialized use + 'BOARD_PROTECTED', # Experimental for MPU use + 'DRIVERS_LIGHTS_RGBLED_PWM', # Only on specific boards, needs dependency fixing + 'DRIVERS_LIGHTS_NEOPIXEL', # Only on specific boards, needs dependency fixing + 'DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL', # Only on specific boards, needs dependency fixing + 'PARAM_PRIMARY', # Plainly broken + 'PARAM_REMOTE', # Plainly broken + 'DRIVERS_ACTUATORS_VOXL_ESC', # Dependency need fixing, requires VOXL_ESC_DEFAULT_XXX + 'DRIVERS_VOXL2_IO', # Dependency need fixing, requires VOXL2_IO_DEFAULT_XX + 'DRIVERS_BAROMETER_TCBP001TA', # Requires hardcoded PX4_SPI_BUS_BARO mapping + 'DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50', # Requires hardcoded PX4_SPI_BUS_BARO mapping + 'DRIVERS_DISTANCE_SENSOR_SRF05', # Requires hardcoded GPIO_ULTRASOUND + 'DRIVERS_PPS_CAPTURE', # Requires PPS GPIO config + 'DRIVERS_PWM_INPUT', # Requires PWM config + 'DRIVERS_TEST_PPM', # PIN config not portable + 'DRIVERS_TATTU_CAN', # Broken needs fixing + 'MODULES_REPLAY', # Fails on NuttX targets maybe force POSIX dependency? + 'SYSTEMCMDS_HIST', # This module can only be used on boards that enable BOARD_ENABLE_LOG_HISTORY + 'SYSTEMCMDS_GPIO', # PIN config not portable + 'SYSTEMCMDS_SHUTDOWN', # Needs dependency checking + 'EXAMPLES_DYN_HELLO', # NuttX doesn't support dynamic linking + 'SYSTEMCMDS_DYN', # NuttX doesn't support dynamic linking + 'DRIVERS_RPI_RC_IN', # RPI specific driver + 'SYSTEMCMDS_I2C_LAUNCHER', # undefined reference to `system', + 'MODULES_MUORB_APPS', # Weird QURT/Posix package doesn't work on x86 px4 sitl + 'MODULES_SIMULATION_SIMULATOR_SIH', # Causes compile errors +] + +exception_list_sitl = [ + 'DRIVERS_BAROMETER', # Fails I2C dependencies + 'COMMON_BAROMETERS', # Fails I2C dependencies + 'DRIVERS_ADC_BOARD_ADC', # Fails HW dependencies, I think this only works on NuttX + 'DRIVERS_CAMERA_CAPTURE', # GPIO config failure + 'DRIVERS_DSHOT', # No Posix driver, I think this only works on NuttX + 'DRIVERS_PWM_OUT', # No Posix driver, I think this only works on NuttX + 'COMMON', # Fails I2C dependencies + 'DRIVERS', # Fails I2C dependencies + 'SYSTEMCMDS_REBOOT', # Sitl can't reboot + 'MODULES_BATTERY_STATUS', # Sitl doesn't provide a power brick + 'SYSTEMCMDS_SERIAL_PASSTHRU', # Not supported in SITL + 'SYSTEMCMDS_SERIAL_TEST', # Not supported in SITL + 'SYSTEMCMDS_SD_STRESS', # Not supported in SITL + 'SYSTEMCMDS_SD_BENCH', # Not supported in SITL + 'SYSTEMCMDS_I2CDETECT', # Not supported in SITL + 'SYSTEMCMDS_DMESG', # Not supported in SITL + 'SYSTEMCMDS_USB_CONNECTED', # Not supported in SITL +] + +def main(): + kconf = kconfiglib.standard_kconfig(__doc__) + + + if 'BASE_DEFCONFIG' in os.environ: + kconf.load_config(os.environ['BASE_DEFCONFIG']) + + if 'MODEL' in os.environ: + if os.environ['MODEL'] == 'sitl': + for sym in kconf.unique_defined_syms: + if sym.name.startswith(tuple(exception_list_sitl)): + exception_list.append(sym.name) + + + # See allnoconfig.py + kconf.warn = False + + # Try to set all symbols to 'y'. Dependencies might truncate the value down + # later, but this will at least give the highest possible value. + # + # Assigning 0/1/2 to non-bool/tristate symbols has no effect (int/hex + # symbols still take a string, because they preserve formatting). + for sym in kconf.unique_defined_syms: + # Set choice symbols to 'm'. This value will be ignored for choices in + # 'y' mode (the "normal" mode), which will instead just get their + # default selection, but will set all symbols in m-mode choices to 'm', + # which is as high as they can go. + # + # Here's a convoluted example of how you might get an m-mode choice + # even during allyesconfig: + # + # choice + # tristate "weird choice" + # depends on m + if sym.name not in exception_list: + sym.set_value(1 if sym.choice else 2) + + # Set all choices to the highest possible mode + for choice in kconf.unique_choices: + choice.set_value(2) + + kconf.warn = True + + kconf.load_allconfig("allyes.config") + + print(kconf.write_config()) + + +if __name__ == "__main__": + main() diff --git a/boards/px4/fmu-v6xrt/allyes.px4board b/boards/px4/fmu-v6xrt/allyes.px4board new file mode 100644 index 000000000000..5f1bc9ab3d59 --- /dev/null +++ b/boards/px4/fmu-v6xrt/allyes.px4board @@ -0,0 +1 @@ +CONFIG_BOARD_LINKER_PREFIX="allyes" diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/allyes-script.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/allyes-script.ld new file mode 100644 index 000000000000..2d4167f13819 --- /dev/null +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/allyes-script.ld @@ -0,0 +1,197 @@ +/**************************************************************************** + * boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* Specify the memory areas */ + + /* Reallocate + * Final Configuration is + * No DTCM + * 512k OCRAM M7 (FlexRAM) (2038:0000-203f:ffff) + * 128k OCRAMM7 FlexRAM ECC (2036:0000-2037:ffff) + * 64k OCRAM2 ECC parity (2035:0000-2035:ffff) + * 64k OCRAM1 ECC parity (2034:0000-2034:ffff) + * 512k FlexRAM OCRAM2 (202C:0000-2033:ffff) + * 512k FlexRAM OCRAM1 (2024:0000-202B:ffff) + * 256k System OCRAM M4 (2020:0000-2023:ffff) + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x30020000, LENGTH = 4M-128K /* We have 64M but we do not want to wait to program it all */ + sram (rwx) : ORIGIN = 0x20240000, LENGTH = 2M-256k-512k + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 256K /* TODO FlexRAM partition */ + dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 256K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +EXTERN(g_flash_config) +EXTERN(g_image_vector_table) +EXTERN(g_boot_data) +EXTERN(board_get_manifest) +EXTERN(_bootdelay_signature) +EXTERN(imxrt_flexspi_initialize) + +ENTRY(__start) + +SECTIONS +{ + /* Image Vector Table and Boot Data for booting from external flash */ + + .boot_hdr : ALIGN(4) + { + FILL(0xff) + . = 0x400 ; + __boot_hdr_start__ = ABSOLUTE(.) ; + KEEP(*(.boot_hdr.conf)) + . = 0x1000 ; + KEEP(*(.boot_hdr.ivt)) + . = 0x1020 ; + KEEP(*(.boot_hdr.boot_data)) + . = 0x1030 ; + KEEP(*(.boot_hdr.dcd_data)) + __boot_hdr_end__ = ABSOLUTE(.) ; + . = 0x2000 ; + } >flash + + .vectors : + { + KEEP(*(.vectors)) + *(.text .text.__start) + } >flash + + .itcmfunc : + { + . = ALIGN(8); + _sitcmfuncs = ABSOLUTE(.); + FILL(0xFF) + . = 0x40 ; + INCLUDE "itcm_static_functions.ld" + . = ALIGN(8); + _eitcmfuncs = ABSOLUTE(.); + } > itcm AT > flash + + _fitcmfuncs = LOADADDR(.itcmfunc); + + /* The RAM vector table (if present) should lie at the beginning of SRAM */ + + .ram_vectors (COPY) : { + *(.ram_vectors) + } > dtcm + + .text : ALIGN(4) + { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + . = ALIGN(4096); + _etext = ABSOLUTE(.); + _srodata = ABSOLUTE(.); + *(.rodata .rodata.*) + . = ALIGN(4096); + _erodata = ABSOLUTE(.); + } > flash + + .init_section : + { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + .ARM.exidx : + { + __exidx_start = ABSOLUTE(.); + *(.ARM.exidx*) + __exidx_end = ABSOLUTE(.); + } > flash + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + . = ALIGN(4); + _edata = ABSOLUTE(.); + } > sram AT > flash + + .ramfunc ALIGN(4): + { + _sramfuncs = ABSOLUTE(.); + *(.ramfunc .ramfunc.*) + _eramfuncs = ABSOLUTE(.); + } > sram AT > flash + + _framfuncs = LOADADDR(.ramfunc); + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + _boot_loadaddr = ORIGIN(flash); + _boot_size = LENGTH(flash); + _ram_size = LENGTH(sram); + _sdtcm = ORIGIN(dtcm); + _edtcm = ORIGIN(dtcm) + LENGTH(dtcm); +} diff --git a/boards/px4/sitl/allyes.px4board b/boards/px4/sitl/allyes.px4board new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/cmake/kconfig.cmake b/cmake/kconfig.cmake index eb418bf6cc8c..7eaaa00d676c 100644 --- a/cmake/kconfig.cmake +++ b/cmake/kconfig.cmake @@ -25,6 +25,7 @@ set(COMMON_KCONFIG_ENV_SETTINGS TOOLCHAIN=${CMAKE_TOOLCHAIN_FILE} ARCHITECTURE=${CMAKE_SYSTEM_PROCESSOR} ROMFSROOT=${config_romfs_root} + BASE_DEFCONFIG=${BOARD_CONFIG} ) set(config_user_list) @@ -52,6 +53,15 @@ if(EXISTS ${BOARD_DEFCONFIG}) ) endif() + if(${LABEL} MATCHES "allyes") + message(AUTHOR_WARNING "allyes build: allyes is for CI coverage and not for use in production") + execute_process( + COMMAND ${CMAKE_COMMAND} -E env ${COMMON_KCONFIG_ENV_SETTINGS} + ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/kconfig/allyesconfig.py + WORKING_DIRECTORY ${PX4_SOURCE_DIR} + ) + endif() + # Generate header file for C/C++ preprocessor execute_process( COMMAND ${CMAKE_COMMAND} -E env ${COMMON_KCONFIG_ENV_SETTINGS} @@ -438,7 +448,7 @@ if(${LABEL} MATCHES "default" OR ${LABEL} MATCHES "bootloader" OR ${LABEL} MATCH COMMAND_EXPAND_LISTS ) -else() +elseif(NOT ${LABEL} MATCHES "allyes") # All other configs except allyes which isn't configurable add_custom_target(boardconfig ${CMAKE_COMMAND} -E env ${COMMON_KCONFIG_ENV_SETTINGS} ${MENUCONFIG_PATH} Kconfig COMMAND ${CMAKE_COMMAND} -E env ${COMMON_KCONFIG_ENV_SETTINGS} ${SAVEDEFCONFIG_PATH} From 8e6102651166191cafc59ed6b74a7b493a4e0a3f Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Mon, 1 Apr 2024 19:09:13 -0700 Subject: [PATCH 062/652] Port CRSF RC driver to new Serial UART API (#22917) * Added implementations of Rx Tx swap and single wire for new UART API needed by CRSF driver * Added inverted mode to Serial interface API --- boards/modalai/voxl2-slpi/default.px4board | 1 + platforms/common/Serial.cpp | 33 ++++++ .../include/px4_platform_common/Serial.hpp | 11 ++ platforms/nuttx/src/px4/common/SerialImpl.cpp | 83 ++++++++++++++ .../src/px4/common/include/SerialImpl.hpp | 14 +++ .../src/px4/common/px4_protected_layers.cmake | 1 + platforms/posix/include/SerialImpl.hpp | 15 +++ platforms/posix/src/px4/common/SerialImpl.cpp | 82 ++++++++++++++ platforms/qurt/include/SerialImpl.hpp | 11 ++ platforms/qurt/src/px4/SerialImpl.cpp | 37 +++++++ src/drivers/rc/crsf_rc/CMakeLists.txt | 2 - src/drivers/rc/crsf_rc/CrsfParser.cpp | 35 +++--- src/drivers/rc/crsf_rc/CrsfRc.cpp | 103 +++++++++--------- src/drivers/rc/crsf_rc/CrsfRc.hpp | 6 +- 14 files changed, 361 insertions(+), 73 deletions(-) diff --git a/boards/modalai/voxl2-slpi/default.px4board b/boards/modalai/voxl2-slpi/default.px4board index b6ce6133fcdf..477ed59e73e5 100644 --- a/boards/modalai/voxl2-slpi/default.px4board +++ b/boards/modalai/voxl2-slpi/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y +CONFIG_DRIVERS_RC_CRSF_RC=y CONFIG_DRIVERS_QSHELL_QURT=y CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_CONTROL_ALLOCATOR=y diff --git a/platforms/common/Serial.cpp b/platforms/common/Serial.cpp index 28e2d5986bd6..9c957fde3747 100644 --- a/platforms/common/Serial.cpp +++ b/platforms/common/Serial.cpp @@ -84,6 +84,11 @@ ssize_t Serial::write(const void *buffer, size_t buffer_size) return _impl.write(buffer, buffer_size); } +void Serial::flush() +{ + return _impl.flush(); +} + uint32_t Serial::getBaudrate() const { return _impl.getBaudrate(); @@ -134,6 +139,34 @@ bool Serial::setFlowcontrol(FlowControl flowcontrol) return _impl.setFlowcontrol(flowcontrol); } +bool Serial::getSingleWireMode() const +{ + return _impl.getSingleWireMode(); +} +bool Serial::setSingleWireMode() +{ + return _impl.setSingleWireMode(); +} + +bool Serial::getSwapRxTxMode() const +{ + return _impl.getSwapRxTxMode(); +} +bool Serial::setSwapRxTxMode() +{ + return _impl.setSwapRxTxMode(); +} + +bool Serial::getInvertedMode() const +{ + return _impl.getInvertedMode(); +} + +bool Serial::setInvertedMode(bool enable) +{ + return _impl.setInvertedMode(enable); +} + const char *Serial::getPort() const { return _impl.getPort(); diff --git a/platforms/common/include/px4_platform_common/Serial.hpp b/platforms/common/include/px4_platform_common/Serial.hpp index b38ae93f0ac2..3a9b8b06663d 100644 --- a/platforms/common/include/px4_platform_common/Serial.hpp +++ b/platforms/common/include/px4_platform_common/Serial.hpp @@ -65,6 +65,8 @@ class Serial ssize_t write(const void *buffer, size_t buffer_size); + void flush(); + // If port is already open then the following configuration functions // will reconfigure the port. If the port is not yet open then they will // simply store the configuration in preparation for the port to be opened. @@ -84,6 +86,15 @@ class Serial FlowControl getFlowcontrol() const; bool setFlowcontrol(FlowControl flowcontrol); + bool getSingleWireMode() const; + bool setSingleWireMode(); + + bool getSwapRxTxMode() const; + bool setSwapRxTxMode(); + + bool getInvertedMode() const; + bool setInvertedMode(bool enable); + static bool validatePort(const char *port); bool setPort(const char *port); const char *getPort() const; diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index c5b659334443..2a09b2ae3521 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -214,6 +214,17 @@ bool SerialImpl::open() _open = true; + // Do pin operations after port has been opened + if (_single_wire_mode) { + setSingleWireMode(); + } + + if (_swap_rx_tx_mode) { + setSwapRxTxMode(); + } + + setInvertedMode(_inverted_mode); + return _open; } @@ -323,6 +334,13 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) return written; } +void SerialImpl::flush() +{ + if (_open) { + tcflush(_serial_fd, TCIOFLUSH); + } +} + const char *SerialImpl::getPort() const { return _port; @@ -416,4 +434,69 @@ bool SerialImpl::setFlowcontrol(FlowControl flowcontrol) return flowcontrol == FlowControl::Disabled; } +bool SerialImpl::getSingleWireMode() const +{ + return _single_wire_mode; +} + +bool SerialImpl::setSingleWireMode() +{ +#if defined(TIOCSSINGLEWIRE) + + if (_open) { + ioctl(_serial_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); + } + + _single_wire_mode = true; + return true; +#else + return false; +#endif // TIOCSSINGLEWIRE +} + +bool SerialImpl::getSwapRxTxMode() const +{ + return _swap_rx_tx_mode; +} + +bool SerialImpl::setSwapRxTxMode() +{ +#if defined(TIOCSSWAP) + + if (_open) { + ioctl(_serial_fd, TIOCSSWAP, SER_SWAP_ENABLED); + } + + _swap_rx_tx_mode = true; + return true; +#else + return false; +#endif // TIOCSSWAP +} + +bool SerialImpl::getInvertedMode() const +{ + return _inverted_mode; +} + +bool SerialImpl::setInvertedMode(bool enable) +{ +#if defined(TIOCSINVERT) + + if (_open) { + if (enable) { + ioctl(_serial_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX); + + } else { + ioctl(_serial_fd, TIOCSINVERT, 0); + } + } + + _inverted_mode = enable; + return true; +#else + return _inverted_mode == enable; +#endif // TIOCSINVERT +} + } // namespace device diff --git a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp index 28d838354ec0..f92deba5ed3e 100644 --- a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp +++ b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp @@ -64,6 +64,8 @@ class SerialImpl ssize_t write(const void *buffer, size_t buffer_size); + void flush(); + const char *getPort() const; static bool validatePort(const char *port); bool setPort(const char *port); @@ -83,6 +85,15 @@ class SerialImpl FlowControl getFlowcontrol() const; bool setFlowcontrol(FlowControl flowcontrol); + bool getSingleWireMode() const; + bool setSingleWireMode(); + + bool getSwapRxTxMode() const; + bool setSwapRxTxMode(); + + bool getInvertedMode() const; + bool setInvertedMode(bool enable); + private: int _serial_fd{-1}; @@ -101,6 +112,9 @@ class SerialImpl bool validateBaudrate(uint32_t baudrate); bool configure(); + bool _single_wire_mode{false}; + bool _swap_rx_tx_mode{false}; + bool _inverted_mode{false}; }; } // namespace device diff --git a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake index a1c6ebc39175..c55fe568d390 100644 --- a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake +++ b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake @@ -46,6 +46,7 @@ target_link_libraries(px4_layer add_library(px4_kernel_layer ${KERNEL_SRCS} + SerialImpl.cpp ) target_link_libraries(px4_kernel_layer diff --git a/platforms/posix/include/SerialImpl.hpp b/platforms/posix/include/SerialImpl.hpp index d5688834e314..f92deba5ed3e 100644 --- a/platforms/posix/include/SerialImpl.hpp +++ b/platforms/posix/include/SerialImpl.hpp @@ -64,6 +64,8 @@ class SerialImpl ssize_t write(const void *buffer, size_t buffer_size); + void flush(); + const char *getPort() const; static bool validatePort(const char *port); bool setPort(const char *port); @@ -83,6 +85,15 @@ class SerialImpl FlowControl getFlowcontrol() const; bool setFlowcontrol(FlowControl flowcontrol); + bool getSingleWireMode() const; + bool setSingleWireMode(); + + bool getSwapRxTxMode() const; + bool setSwapRxTxMode(); + + bool getInvertedMode() const; + bool setInvertedMode(bool enable); + private: int _serial_fd{-1}; @@ -100,6 +111,10 @@ class SerialImpl bool validateBaudrate(uint32_t baudrate); bool configure(); + + bool _single_wire_mode{false}; + bool _swap_rx_tx_mode{false}; + bool _inverted_mode{false}; }; } // namespace device diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 739796e6a172..4c84e0078feb 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -212,6 +212,16 @@ bool SerialImpl::open() _open = true; + if (_single_wire_mode) { + setSingleWireMode(); + } + + if (_swap_rx_tx_mode) { + setSwapRxTxMode(); + } + + setInvertedMode(_inverted_mode); + return _open; } @@ -316,6 +326,13 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) return written; } +void SerialImpl::flush() +{ + if (_open) { + tcflush(_serial_fd, TCIOFLUSH); + } +} + const char *SerialImpl::getPort() const { return _port; @@ -409,4 +426,69 @@ bool SerialImpl::setFlowcontrol(FlowControl flowcontrol) return flowcontrol == FlowControl::Disabled; } +bool SerialImpl::getSingleWireMode() const +{ + return _single_wire_mode; +} + +bool SerialImpl::setSingleWireMode() +{ +#if defined(TIOCSSINGLEWIRE) + + if (_open) { + ioctl(_serial_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); + } + + _single_wire_mode = true; + return true; +#else + return false; +#endif // TIOCSSINGLEWIRE +} + +bool SerialImpl::getSwapRxTxMode() const +{ + return _swap_rx_tx_mode; +} + +bool SerialImpl::setSwapRxTxMode() +{ +#if defined(TIOCSSWAP) + + if (_open) { + ioctl(_serial_fd, TIOCSSWAP, SER_SWAP_ENABLED); + } + + _swap_rx_tx_mode = true; + return true; +#else + return false; +#endif // TIOCSSWAP +} + +bool SerialImpl::getInvertedMode() const +{ + return _inverted_mode; +} + +bool SerialImpl::setInvertedMode(bool enable) +{ +#if defined(TIOCSINVERT) + + if (_open) { + if (enable) { + ioctl(_serial_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX); + + } else { + ioctl(_serial_fd, TIOCSINVERT, 0); + } + } + + _inverted_mode = enable; + return true; +#else + return _inverted_mode == enable; +#endif // TIOCSINVERT +} + } // namespace device diff --git a/platforms/qurt/include/SerialImpl.hpp b/platforms/qurt/include/SerialImpl.hpp index 91bbde046454..39c3d63553d5 100644 --- a/platforms/qurt/include/SerialImpl.hpp +++ b/platforms/qurt/include/SerialImpl.hpp @@ -63,6 +63,8 @@ class SerialImpl ssize_t write(const void *buffer, size_t buffer_size); + void flush(); + const char *getPort() const; bool setPort(const char *port); static bool validatePort(const char *port); @@ -82,6 +84,15 @@ class SerialImpl FlowControl getFlowcontrol() const; bool setFlowcontrol(FlowControl flowcontrol); + bool getSingleWireMode() const; + bool setSingleWireMode(); + + bool getSwapRxTxMode() const; + bool setSwapRxTxMode(); + + bool getInvertedMode() const; + bool setInvertedMode(bool enable); + private: int _serial_fd{-1}; diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp index 287064b760ad..1d0c20f00025 100644 --- a/platforms/qurt/src/px4/SerialImpl.cpp +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -255,6 +255,11 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) return ret_write; } +void SerialImpl::flush() +{ + // TODO: Flush not implemented yet on Qurt +} + const char *SerialImpl::getPort() const { return _port; @@ -348,4 +353,36 @@ bool SerialImpl::setFlowcontrol(FlowControl flowcontrol) return flowcontrol == FlowControl::Disabled; } +bool SerialImpl::getSingleWireMode() const +{ + return false; +} + +bool SerialImpl::setSingleWireMode() +{ + // Qurt platform does not support single wire mode + return false; +} + +bool SerialImpl::getSwapRxTxMode() const +{ + return false; +} + +bool SerialImpl::setSwapRxTxMode() +{ + // Qurt platform does not support swap rx tx mode + return false; +} + +bool SerialImpl::setInvertedMode(bool enable) +{ + // Qurt platform does not support inverted mode + return false == enable; +} +bool SerialImpl::getInvertedMode() const +{ + return false; +} + } // namespace device diff --git a/src/drivers/rc/crsf_rc/CMakeLists.txt b/src/drivers/rc/crsf_rc/CMakeLists.txt index ceb75310799a..a3ebb1a1ae87 100644 --- a/src/drivers/rc/crsf_rc/CMakeLists.txt +++ b/src/drivers/rc/crsf_rc/CMakeLists.txt @@ -46,6 +46,4 @@ px4_add_module( MODULE_CONFIG module.yaml - DEPENDS - rc ) diff --git a/src/drivers/rc/crsf_rc/CrsfParser.cpp b/src/drivers/rc/crsf_rc/CrsfParser.cpp index aa499db9f562..a81fe930f517 100644 --- a/src/drivers/rc/crsf_rc/CrsfParser.cpp +++ b/src/drivers/rc/crsf_rc/CrsfParser.cpp @@ -161,6 +161,8 @@ static float MapF(const float x, const float in_min, const float in_max, const f return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; } +#define CONSTRAIN_CHAN(x) ConstrainF(x, CRSF_CHANNEL_VALUE_MIN, CRSF_CHANNEL_VALUE_MAX) + static bool ProcessChannelData(const uint8_t *data, const uint32_t size, CrsfPacket_t *const new_packet) { uint32_t raw_channels[CRSF_CHANNEL_COUNT]; @@ -169,25 +171,24 @@ static bool ProcessChannelData(const uint8_t *data, const uint32_t size, CrsfPac new_packet->message_type = CRSF_MESSAGE_TYPE_RC_CHANNELS; // Decode channel data - raw_channels[0] = (data[0] | data[1] << 8) & 0x07FF; - raw_channels[1] = (data[1] >> 3 | data[2] << 5) & 0x07FF; - raw_channels[2] = (data[2] >> 6 | data[3] << 2 | data[4] << 10) & 0x07FF; - raw_channels[3] = (data[4] >> 1 | data[5] << 7) & 0x07FF; - raw_channels[4] = (data[5] >> 4 | data[6] << 4) & 0x07FF; - raw_channels[5] = (data[6] >> 7 | data[7] << 1 | data[8] << 9) & 0x07FF; - raw_channels[6] = (data[8] >> 2 | data[9] << 6) & 0x07FF; - raw_channels[7] = (data[9] >> 5 | data[10] << 3) & 0x07FF; - raw_channels[8] = (data[11] | data[12] << 8) & 0x07FF; - raw_channels[9] = (data[12] >> 3 | data[13] << 5) & 0x07FF; - raw_channels[10] = (data[13] >> 6 | data[14] << 2 | data[15] << 10) & 0x07FF; - raw_channels[11] = (data[15] >> 1 | data[16] << 7) & 0x07FF; - raw_channels[12] = (data[16] >> 4 | data[17] << 4) & 0x07FF; - raw_channels[13] = (data[17] >> 7 | data[18] << 1 | data[19] << 9) & 0x07FF; - raw_channels[14] = (data[19] >> 2 | data[20] << 6) & 0x07FF; - raw_channels[15] = (data[20] >> 5 | data[21] << 3) & 0x07FF; + raw_channels[0] = CONSTRAIN_CHAN((data[0] | data[1] << 8) & 0x07FF); + raw_channels[1] = CONSTRAIN_CHAN((data[1] >> 3 | data[2] << 5) & 0x07FF); + raw_channels[2] = CONSTRAIN_CHAN((data[2] >> 6 | data[3] << 2 | data[4] << 10) & 0x07FF); + raw_channels[3] = CONSTRAIN_CHAN((data[4] >> 1 | data[5] << 7) & 0x07FF); + raw_channels[4] = CONSTRAIN_CHAN((data[5] >> 4 | data[6] << 4) & 0x07FF); + raw_channels[5] = CONSTRAIN_CHAN((data[6] >> 7 | data[7] << 1 | data[8] << 9) & 0x07FF); + raw_channels[6] = CONSTRAIN_CHAN((data[8] >> 2 | data[9] << 6) & 0x07FF); + raw_channels[7] = CONSTRAIN_CHAN((data[9] >> 5 | data[10] << 3) & 0x07FF); + raw_channels[8] = CONSTRAIN_CHAN((data[11] | data[12] << 8) & 0x07FF); + raw_channels[9] = CONSTRAIN_CHAN((data[12] >> 3 | data[13] << 5) & 0x07FF); + raw_channels[10] = CONSTRAIN_CHAN((data[13] >> 6 | data[14] << 2 | data[15] << 10) & 0x07FF); + raw_channels[11] = CONSTRAIN_CHAN((data[15] >> 1 | data[16] << 7) & 0x07FF); + raw_channels[12] = CONSTRAIN_CHAN((data[16] >> 4 | data[17] << 4) & 0x07FF); + raw_channels[13] = CONSTRAIN_CHAN((data[17] >> 7 | data[18] << 1 | data[19] << 9) & 0x07FF); + raw_channels[14] = CONSTRAIN_CHAN((data[19] >> 2 | data[20] << 6) & 0x07FF); + raw_channels[15] = CONSTRAIN_CHAN((data[20] >> 5 | data[21] << 3) & 0x07FF); for (i = 0; i < CRSF_CHANNEL_COUNT; i++) { - raw_channels[i] = ConstrainF(raw_channels[i], CRSF_CHANNEL_VALUE_MIN, CRSF_CHANNEL_VALUE_MAX); new_packet->channel_data.channels[i] = MapF((float)raw_channels[i], CRSF_CHANNEL_VALUE_MIN, CRSF_CHANNEL_VALUE_MAX, 1000.0f, 2000.0f); } diff --git a/src/drivers/rc/crsf_rc/CrsfRc.cpp b/src/drivers/rc/crsf_rc/CrsfRc.cpp index dc30620e9831..42b61ea66ff6 100644 --- a/src/drivers/rc/crsf_rc/CrsfRc.cpp +++ b/src/drivers/rc/crsf_rc/CrsfRc.cpp @@ -35,8 +35,6 @@ #include "CrsfParser.hpp" #include "Crc8.hpp" -#include -#include #include #include @@ -118,76 +116,74 @@ void CrsfRc::Run() { if (should_exit()) { ScheduleClear(); - ::close(_rc_fd); - _rc_fd = -1; + + if (_uart) { + (void) _uart->close(); + delete _uart; + _uart = nullptr; + } + exit_and_cleanup(); return; } - if (_rc_fd < 0) { - _rc_fd = ::open(_device, O_RDWR | O_NONBLOCK); + if (_uart == nullptr) { + // Create the UART port instance + _uart = new Serial(_device); - if (_rc_fd >= 0) { - struct termios t; - - tcgetattr(_rc_fd, &t); - cfsetspeed(&t, CRSF_BAUDRATE); - t.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS); - t.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG); - t.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON); - t.c_oflag = 0; - tcsetattr(_rc_fd, TCSANOW, &t); + if (_uart == nullptr) { + PX4_ERR("Error creating serial device %s", _device); + px4_sleep(1); + return; + } + } - if (board_rc_swap_rxtx(_device)) { -#if defined(TIOCSSWAP) - ioctl(_rc_fd, TIOCSSWAP, SER_SWAP_ENABLED); -#endif // TIOCSSWAP - } + if (! _uart->isOpen()) { + // Configure the desired baudrate if one was specified by the user. + // Otherwise the default baudrate will be used. + if (! _uart->setBaudrate(CRSF_BAUDRATE)) { + PX4_ERR("Error setting baudrate to %u on %s", CRSF_BAUDRATE, _device); + px4_sleep(1); + return; + } - if (board_rc_singlewire(_device)) { - _is_singlewire = true; -#if defined(TIOCSSINGLEWIRE) - ioctl(_rc_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); -#endif // TIOCSSINGLEWIRE - } + // Open the UART. If this is successful then the UART is ready to use. + if (! _uart->open()) { + PX4_ERR("Error opening serial device %s", _device); + px4_sleep(1); + return; + } - PX4_INFO("Crsf serial opened sucessfully"); + if (board_rc_swap_rxtx(_device)) { + _uart->setSwapRxTxMode(); + } - if (_is_singlewire) { - PX4_INFO("Crsf serial is single wire. Telemetry disabled"); - } + if (board_rc_singlewire(_device)) { + _is_singlewire = true; + _uart->setSingleWireMode(); + } - tcflush(_rc_fd, TCIOFLUSH); + PX4_INFO("Crsf serial opened sucessfully"); - Crc8Init(0xd5); + if (_is_singlewire) { + PX4_INFO("Crsf serial is single wire. Telemetry disabled"); } + _uart->flush(); + + Crc8Init(0xd5); + _input_rc.rssi_dbm = NAN; _input_rc.link_quality = -1; CrsfParser_Init(); - - - } - - // poll with 100mS timeout - pollfd fds[1]; - fds[0].fd = _rc_fd; - fds[0].events = POLLIN; - int ret = ::poll(fds, 1, 100); - - if (ret < 0) { - PX4_ERR("poll error"); - // try again with delay - ScheduleDelayed(100_ms); - return; } const hrt_abstime time_now_us = hrt_absolute_time(); perf_count_interval(_cycle_interval_perf, time_now_us); // Read all available data from the serial RC input UART - int new_bytes = ::read(_rc_fd, &_rcs_buf[0], RC_MAX_BUFFER_SIZE); + int new_bytes = _uart->readAtLeast(&_rcs_buf[0], RC_MAX_BUFFER_SIZE, 1, 100); if (new_bytes > 0) { _bytes_rx += new_bytes; @@ -433,7 +429,8 @@ bool CrsfRc::SendTelemetryBattery(const uint16_t voltage, const uint16_t current write_uint24_t(buf, offset, fuel); write_uint8_t(buf, offset, remaining); WriteFrameCrc(buf, offset, sizeof(buf)); - return write(_rc_fd, buf, offset) == offset; + return _uart->write((void *) buf, (size_t) offset); + } bool CrsfRc::SendTelemetryGps(const int32_t latitude, const int32_t longitude, const uint16_t groundspeed, @@ -449,7 +446,7 @@ bool CrsfRc::SendTelemetryGps(const int32_t latitude, const int32_t longitude, c write_uint16_t(buf, offset, altitude); write_uint8_t(buf, offset, num_satellites); WriteFrameCrc(buf, offset, sizeof(buf)); - return write(_rc_fd, buf, offset) == offset; + return _uart->write((void *) buf, (size_t) offset); } bool CrsfRc::SendTelemetryAttitude(const int16_t pitch, const int16_t roll, const int16_t yaw) @@ -461,7 +458,7 @@ bool CrsfRc::SendTelemetryAttitude(const int16_t pitch, const int16_t roll, cons write_uint16_t(buf, offset, roll); write_uint16_t(buf, offset, yaw); WriteFrameCrc(buf, offset, sizeof(buf)); - return write(_rc_fd, buf, offset) == offset; + return _uart->write((void *) buf, (size_t) offset); } bool CrsfRc::SendTelemetryFlightMode(const char *flight_mode) @@ -480,7 +477,7 @@ bool CrsfRc::SendTelemetryFlightMode(const char *flight_mode) offset += length; buf[offset - 1] = 0; // ensure null-terminated string WriteFrameCrc(buf, offset, length + 4); - return write(_rc_fd, buf, offset) == offset; + return _uart->write((void *) buf, (size_t) offset); } int CrsfRc::print_status() diff --git a/src/drivers/rc/crsf_rc/CrsfRc.hpp b/src/drivers/rc/crsf_rc/CrsfRc.hpp index 6603e01ea3af..c3b0a4ec54d0 100644 --- a/src/drivers/rc/crsf_rc/CrsfRc.hpp +++ b/src/drivers/rc/crsf_rc/CrsfRc.hpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -53,6 +54,8 @@ #include #include +using namespace device; + class CrsfRc : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { public: @@ -87,7 +90,8 @@ class CrsfRc : public ModuleBase, public ModuleParams, public px4::Sched bool SendTelemetryFlightMode(const char *flight_mode); - int _rc_fd{-1}; + Serial *_uart = nullptr; ///< UART interface to RC + char _device[20] {}; ///< device / serial port path bool _is_singlewire{false}; From f7bc13dab0d7f5c32a104e7206036d435c4293d3 Mon Sep 17 00:00:00 2001 From: Peize-Liu Date: Tue, 2 Apr 2024 21:49:10 +0800 Subject: [PATCH 063/652] boards: new hkust nxt-fc board support (#22961) --- boards/hkust/nxt-dual/bootloader.px4board | 3 + boards/hkust/nxt-dual/default.px4board | 89 +++ .../extras/hkust_nxt-dual_bootloader.bin | Bin 0 -> 43256 bytes boards/hkust/nxt-dual/firmware.prototype | 13 + boards/hkust/nxt-dual/init/rc.board_defaults | 24 + boards/hkust/nxt-dual/init/rc.board_extras | 13 + boards/hkust/nxt-dual/init/rc.board_sensors | 16 + boards/hkust/nxt-dual/nuttx-config/Kconfig | 17 + .../nuttx-config/bootloader/defconfig | 92 ++++ .../nxt-dual/nuttx-config/include/board.h | 487 +++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 62 +++ .../hkust/nxt-dual/nuttx-config/nsh/defconfig | 288 ++++++++++ .../nuttx-config/nsh/old_defconfig.txt | 271 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 ++++++++ .../nxt-dual/nuttx-config/scripts/script.ld | 228 ++++++++ boards/hkust/nxt-dual/src/CMakeLists.txt | 69 +++ boards/hkust/nxt-dual/src/board_config.h | 230 ++++++++ boards/hkust/nxt-dual/src/bootloader_main.c | 75 +++ boards/hkust/nxt-dual/src/flash_w25q128.c | 505 ++++++++++++++++++ boards/hkust/nxt-dual/src/hw_config.h | 135 +++++ boards/hkust/nxt-dual/src/i2c.cpp | 39 ++ boards/hkust/nxt-dual/src/init.c | 205 +++++++ boards/hkust/nxt-dual/src/led.c | 113 ++++ boards/hkust/nxt-dual/src/manifest.c | 131 +++++ boards/hkust/nxt-dual/src/mtd.cpp | 77 +++ boards/hkust/nxt-dual/src/sdio.c | 177 ++++++ boards/hkust/nxt-dual/src/spi.cpp | 56 ++ boards/hkust/nxt-dual/src/timer_config.cpp | 56 ++ boards/hkust/nxt-dual/src/usb.c | 78 +++ boards/hkust/nxt-v1/bootloader.px4board | 3 + boards/hkust/nxt-v1/default.px4board | 105 ++++ .../nxt-v1/extras/hkust_nxt-v1_bootloader.bin | Bin 0 -> 43248 bytes boards/hkust/nxt-v1/firmware.prototype | 13 + boards/hkust/nxt-v1/init/rc.board_defaults | 6 + boards/hkust/nxt-v1/init/rc.board_extras | 13 + boards/hkust/nxt-v1/init/rc.board_sensors | 16 + boards/hkust/nxt-v1/nuttx-config/Kconfig | 17 + .../nxt-v1/nuttx-config/bootloader/defconfig | 92 ++++ .../hkust/nxt-v1/nuttx-config/include/board.h | 484 +++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 62 +++ .../hkust/nxt-v1/nuttx-config/nsh/defconfig | 272 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 ++++++++ .../nxt-v1/nuttx-config/scripts/script.ld | 228 ++++++++ boards/hkust/nxt-v1/src/CMakeLists.txt | 68 +++ boards/hkust/nxt-v1/src/board_config.h | 227 ++++++++ boards/hkust/nxt-v1/src/bootloader_main.c | 75 +++ boards/hkust/nxt-v1/src/hw_config.h | 135 +++++ boards/hkust/nxt-v1/src/i2c.cpp | 39 ++ boards/hkust/nxt-v1/src/init.c | 205 +++++++ boards/hkust/nxt-v1/src/led.c | 113 ++++ boards/hkust/nxt-v1/src/mtd.cpp | 81 +++ boards/hkust/nxt-v1/src/sdio.c | 177 ++++++ boards/hkust/nxt-v1/src/spi.cpp | 52 ++ boards/hkust/nxt-v1/src/timer_config.cpp | 55 ++ boards/hkust/nxt-v1/src/usb.c | 78 +++ 55 files changed, 6591 insertions(+) create mode 100644 boards/hkust/nxt-dual/bootloader.px4board create mode 100644 boards/hkust/nxt-dual/default.px4board create mode 100755 boards/hkust/nxt-dual/extras/hkust_nxt-dual_bootloader.bin create mode 100644 boards/hkust/nxt-dual/firmware.prototype create mode 100644 boards/hkust/nxt-dual/init/rc.board_defaults create mode 100644 boards/hkust/nxt-dual/init/rc.board_extras create mode 100644 boards/hkust/nxt-dual/init/rc.board_sensors create mode 100644 boards/hkust/nxt-dual/nuttx-config/Kconfig create mode 100644 boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig create mode 100644 boards/hkust/nxt-dual/nuttx-config/include/board.h create mode 100644 boards/hkust/nxt-dual/nuttx-config/include/board_dma_map.h create mode 100644 boards/hkust/nxt-dual/nuttx-config/nsh/defconfig create mode 100644 boards/hkust/nxt-dual/nuttx-config/nsh/old_defconfig.txt create mode 100644 boards/hkust/nxt-dual/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/hkust/nxt-dual/nuttx-config/scripts/script.ld create mode 100644 boards/hkust/nxt-dual/src/CMakeLists.txt create mode 100644 boards/hkust/nxt-dual/src/board_config.h create mode 100644 boards/hkust/nxt-dual/src/bootloader_main.c create mode 100644 boards/hkust/nxt-dual/src/flash_w25q128.c create mode 100644 boards/hkust/nxt-dual/src/hw_config.h create mode 100644 boards/hkust/nxt-dual/src/i2c.cpp create mode 100644 boards/hkust/nxt-dual/src/init.c create mode 100644 boards/hkust/nxt-dual/src/led.c create mode 100644 boards/hkust/nxt-dual/src/manifest.c create mode 100644 boards/hkust/nxt-dual/src/mtd.cpp create mode 100644 boards/hkust/nxt-dual/src/sdio.c create mode 100644 boards/hkust/nxt-dual/src/spi.cpp create mode 100644 boards/hkust/nxt-dual/src/timer_config.cpp create mode 100644 boards/hkust/nxt-dual/src/usb.c create mode 100644 boards/hkust/nxt-v1/bootloader.px4board create mode 100644 boards/hkust/nxt-v1/default.px4board create mode 100755 boards/hkust/nxt-v1/extras/hkust_nxt-v1_bootloader.bin create mode 100644 boards/hkust/nxt-v1/firmware.prototype create mode 100644 boards/hkust/nxt-v1/init/rc.board_defaults create mode 100644 boards/hkust/nxt-v1/init/rc.board_extras create mode 100644 boards/hkust/nxt-v1/init/rc.board_sensors create mode 100644 boards/hkust/nxt-v1/nuttx-config/Kconfig create mode 100644 boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig create mode 100644 boards/hkust/nxt-v1/nuttx-config/include/board.h create mode 100644 boards/hkust/nxt-v1/nuttx-config/include/board_dma_map.h create mode 100644 boards/hkust/nxt-v1/nuttx-config/nsh/defconfig create mode 100644 boards/hkust/nxt-v1/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/hkust/nxt-v1/nuttx-config/scripts/script.ld create mode 100644 boards/hkust/nxt-v1/src/CMakeLists.txt create mode 100644 boards/hkust/nxt-v1/src/board_config.h create mode 100644 boards/hkust/nxt-v1/src/bootloader_main.c create mode 100644 boards/hkust/nxt-v1/src/hw_config.h create mode 100644 boards/hkust/nxt-v1/src/i2c.cpp create mode 100644 boards/hkust/nxt-v1/src/init.c create mode 100644 boards/hkust/nxt-v1/src/led.c create mode 100644 boards/hkust/nxt-v1/src/mtd.cpp create mode 100644 boards/hkust/nxt-v1/src/sdio.c create mode 100644 boards/hkust/nxt-v1/src/spi.cpp create mode 100644 boards/hkust/nxt-v1/src/timer_config.cpp create mode 100644 boards/hkust/nxt-v1/src/usb.c diff --git a/boards/hkust/nxt-dual/bootloader.px4board b/boards/hkust/nxt-dual/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/hkust/nxt-dual/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/hkust/nxt-dual/default.px4board b/boards/hkust/nxt-dual/default.px4board new file mode 100644 index 000000000000..884487955590 --- /dev/null +++ b/boards/hkust/nxt-dual/default.px4board @@ -0,0 +1,89 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS7" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +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 +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +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/hkust/nxt-dual/extras/hkust_nxt-dual_bootloader.bin b/boards/hkust/nxt-dual/extras/hkust_nxt-dual_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..a9eb4be10db07aea7184f463b7b8c6721d721085 GIT binary patch literal 43256 zcmeFZd3;k<{y%)~lH|52O}YT-0?oqG1u(QA6ape&I{+ZTtBzRqub(r*e;% zc^&KhrZ1-MIdP@P1|;^IzJ&VmvR)V0KJ_d8=B-UrFAkMfh-Z{cFOiEvO&5krqp3}o z^qXx~T0XAb-6w2v_r+|g?@QQJRVeUeg3vOygqX%U8| zj7A#_nSdcp=zoO>JmOowA>BW7ZfHuC%>8b&z2BXi>bkRp*~aW5*`%-0%`}o6TiQ(uhCB`5#v5F7o%WK+GUQVWm!3&HDrf; zS;g5!bPTq|j()OO>zYjS_1o6i`^lPA7mIke9S~W>M&l9auqbbq@m+SKzp*rbBJwBF z77+*Z*ruw&ROxx{wku`(m|e{5C4N%CE>UiHo*3{84_&N?> zX@A@pz2SZ$yOnS-E^LTEl3>Ot=8VB;Q(cP{VTuDGDU#-1?2!L}w1i07GHIDh7x`|) zxA@4n)QZ$Hp^dcDF$r~KA?@EUz8UEuB+N`fyc6Lwgl>cj2r|MK2vvpQOV$HeCmV^y zZT_ZDU%%!r8-V%sefmulcSk$Nl%z=so49`W!_^*UdV)J~)5D%a9%7-XUo>w--n|~) zX#FdZod=6O%uQeUN%l8hN56Zmx+KZPSbF?qs^4qDJB#mnxJnc_ayOjlz#`1-fytS#62JTY4G$!jG!$qH;-)K)*J?Y7*?u{D;fl-z#9}iI_!r)$n1PkmxW&$%e(B2NRTuqCBa_E8 zT=7T0GN)JMe|hcO)yTK~S602XA0kGn7<(Mwa;IRx6$*f zB5#-cznQ|GES1AneOto(t&wkM{dy;#sdaI_(tbC_dDO4UWDzHMieDXxxh;KuUFJET z#z|WTwzTt~lWqYa4ndDF0kF__lkRa&TKBkOeM_3efx0bA=K}ebvb;tz7j$!reb6`7 zIkwm^KgCrlyQim=nOr-|7BizuqN7{ku!GJvAXfrlpHQqdrn-pyP>7gy#hj7I4}>hB zfwc~Y-0iTqWDCWXd;g*bYk#+fG3K=&;2gSGgk zi7O&<{=gLUB@?0hk3{&#DkfWK5xi`6tT(mwxLH_DJtQd19D=Yrz_9-3V%~PWhs^B%{uUkg|CjM)X3y-RV?>)7MunYI+LPp1 z(U;*U?MW`UuP>vZv}g3Z`};EHmG+Dgf6vW}<>uR;HS>Wgbxu`%3o(I$$wR}O#bBOQ zYU8TV0$S9L#evuSsIw9qBICl2gUVV?$VD3?~l^ z@RmGRp2XzLJ8hNRgp=b#*-it#@GfJ~A8UymJGe(0U(_Yt<6`7BLupt!eW6tRr{lZI zoVtdXGq655)Jo(IMJ*df(w$llk!K91;i-|Q52Z%lH-s7a^#MlSI;fKU3U7%iq9xJ? zRgsc6DeA~`pTfwu3=R47q~)X;Yt4YQb^t-a8l4+Q1U=$M5I#m|Lg+wv17T?r5tctm z1XVhvCs?1sWnq=mcJ*=l3KQARqrWE=qe$rqX-{Y*Lc#86K9v*n^xlzcdAh&NQ!$DN zcOuWrnN=++F-}bF1TA?AwB&ocYkF%q_=jP$sF^PmU2V20Gi{{zePVY#1qz7yY+Egl zCW9Eq+;}2fKtEs36k6gsV@eh&R_k&P+uOk|l6DlT!FM3Iz;&2a&a3`Zk(QzPuaA|M z7wA6yBlPS>6H^opdPnX-e^sD*IUZF>qLkR0`Ye;1x-o)P?X(_Bx00OtmQ?9IPa^W| zZKeDE_eaz`V6>8)n9qnMX=5yMEpCl+Cd8<3W9BqACv7A-SA5_28ToK1;J;q)LDXH< z@>G*beAXB*esYn|<>ZSBFM2)1^g%uMeB4gKQ5-&^ zWQyvhsy3ter9|Y%27><8vR2ja&uCGq+u-nxyd~%V@ zND^a3))WqQL{gGk_-kK@IUMW_(;1(7v9Iu{+D)QLd|sR`W{9Vi%$JD#`vHFZ>@Kt` zb7~@=!dqO|)1F1*O=2ci;NcKIUWHU5uSZJKsh@dh{M7+dcdocFlA{OTzdp6MlH>%u z(<5Jg61wEqHWrJqCCK|*A}1;Q__JMcyXGR5$h+~@6{)dyfMO!3&(pw*L?TSR7%b&Q z3N>QEj6D6r9qWuj{)kX_OgyEK1;p5?5Ir+9AAHIV`=~Cx)PZ%ItIQ}-i6m3>g`1xS z_5p%qb~iIMNjlihOl0Qd*cK|5txRuyd~1N{tiFFL#1?M;()AH)r1{Tox!U}qV%1|m zZ#2v0EF*Kwq;=(Gu?_}fx_{lCva|JkpnxTEJ^H^1kjw%v>5YkfEg;0~7x`N{um##E z1`hI~r(mwg%vgZ8or8B4oSc{DBgPVik2@qCm451qj>&eJN%@Ha@iNov<>c1}8S4|3 z>Vn_f#~fv5%%2zVt(Mi~qTi|Tr9V;l4AAoDIr+DPZjsq(6omjIaB}5fL4g;6Et3{0 zMys>++?JOsqIm>gg7|7-IQa1pW8Gx`#>W^HKLc#!WX*sQS-ZRluD#`pX3l964On}7 z2aUk~-3ndT`WAzU$J?M{^z4zkBo3Ud9u!RridNMEc=rFQij}X9@Zwg``~8Ee@jO;D zE1w?86sy|!zyxx@rIzQSMlz9;KO5+atZLcsy~sj_WX#LfR2Am8Y?M^u3{UyvOb&mN znNz-oSoXT|K?#W5NK4AO1GFZ!Y{DBScha>ZzcJG5C-RQBiTvBQ!bIsC4u_87Iz3CZo{$xo|q$ab;Fv! zP&sS^BtUjrf|r|?>}94U`&K?+l42cX!paq05owIb36Nf=4;w|L%_OaSfO5Rw_|4K+ zfY@mM64n8o4};U%GERE333Bf60}oJ|LWaL^@HTGy1nfeID6N7#!@Wx6D#ek`h;w0f9vG~S4D5qX-zLHF?`Al5g;7|&d5C%>hha?Vd;3`R(V7=!!T z7>MzOigh0IW1H=29~Uq%)>Z*<*%Riwjp76;;AiDm!e2F0`Ozrmx9MBBC+een%=fT5 zzL=Gz@O8XqbK-nx??$@$9Hc0q4rWe;GVA4?`!5%RGsGZRd}WmX=7EWpe# zP6_%TBjA=w`-p^xO6 z6V7ZkpdMDfF>Gk1`8Et*_J@PN3-|lMo6a32##HlS*8T!3E58$FGBsii?LXxXzBf)w z?bT*=PNFZXnhz8a3LTdxM>2}%?yHn6_Y=#W6_~4Vgjbk!pqoDbBxO~jE{drX_Rt_u z*i#L{o{A)o;jvA2!FRNoY8CQ4+0b3AlyKdiFHt_v{w#cW0Utp_hyG(*2l~KN)5kITzblzEKm|PZx-)ZM06+ zE(+sI-p{wFw$1G)4}D%g7j1P6A6E*RS|n$WN_F1~TEkjN9f)I8yR1*_D5Nd&yHseI zu4mdNrAhp@x#HO^R?&=B&(`1jz)x%&dbI3l+mk(7)WOOx4XYZX6bk&+uodty4ZZ{k zJA6q6J~ACt?{A?9+y>|h1rK_N(kY>Zbuz{@q;4IEzPlwO)=DPu@pwBiLiTAR7NH~& z6uS#d zmLK8)P5lCxb7q)o)WGw0(>nj<^Hc18@`w3Zxo!A6szusqyO=}AQxf*T+e>9O#(3jP z;*(8QK>5AlN@=a&M)sNNA-dbVG<h++Zpk%TU zsT9KCKo3&Nmyh)~8ypL$xtW+)IcJy{FJae=?#=p^BcL%ve*9V~R!)9UqZ%?7bSt~mCKmBoL&O-x8mz_g zjYPgZ6rGj)HjRnM>YmZI4F~w%05&At18sDgoBsE;OS4T zu(Psph<8Qz3Vj=T^dnkR4pc$yV;<0MV)D|OwQgeJRzx`i%Cn%%M!G$=CirK%Bm_ zazRKX7I{d(rJ3?@rf8Ts9eCv(+-DE^T$uTpAzoZUQ&sHbv3E><*eDui&>Zc9FC&Ky zIVN1oVN;RG`a34CHH!L3j<>$ek@Rg2cCzqqIbMw9P}&UGV~q%zbgxCAd+vXOK37av zn|qM1HY#7!vXlmn7Jpijk@;lPQH3;VAm4N;!b|)~Iv)>i?rR!r}zYMXvxW?`FeqWT% zq8IgS1Jj67o7Vh=wzvtgC74|~#5VF`G*^3scc*YBmRT(uB!=!NPkvvL-(E4LHM)YB z9aPh8dW?CMl?w+aNSDFyjDo(^<{1f|4^OB__E^^MwR66a;5XoO^V=p!SN!2iiJnr(xmoI$zAZfo|_kX7`vd1Bv^XQ!fJ5!fuk6q`pNNJv3(jTSRf?cj9o>=gt zMImBzxvo$%<|T-sw@8tw#< zM=Mhv&2IzFghGBEbYJCUYxOOQm0UgL2W|}!i{;UXUOciVXeD<2eoy-P?RNFiWzxN^ z9T!RN5|`jg>Q2KP(Ko%T2vS#EcQn2PTJREyWCwhB&wKYGAq*rkx*yMKNxXfEG$k@u zH6aG{+uEi>&#Oa_4U;Ow(yMV*Zz{z4oWk0e-*EC*BMhXqV!H-;?hl>!tMR-Sd-++& z07V#IC;B&tFli4F?nB_gU2?9&0sUg`3bANi)E4p?baJe^v`3#5cbwW3)X-{KjJc2n zb%e2`csST|x0ZqSS_k|up$^c5LRAbecJy&$N6UiBCLeRJbS_pVyT~+9a5w3&82h}`Vnf5nDp6Q1rHZ1P*~jy?iC&j(=!I=CO>kl8Go{GvO#zpC^|A7>rwwP;FZ zU5vB+)qub`#8P=eT&Zk~Yb19m>h72jH$XyM-?W~Xct=k>H(ya(OM8l9ILoIB>E^Py zPz=(z_|-jJ9D_K`ljmCP<@;@U=+A8rc+tz-;@VjYL5a9-nm?{5K2leo%iS7jJNA0p z6O2YU}@x{h}OjBZpX>b$Sz3Rzv?ZMkAw?eM;Q#l7-WfT-s6#;W#9 zs!+@o#z=FCTp!L*?Ufvc!HPX_|l$DoX*GxnhH2M zjytXh$vbQsv})=hjMi~P5oSc?2Vw+o@-%B&;^$01^=FB9`ib$Eeq#BZpRxSL&rW>T z&rNLiTY3oh&j{}OBXii%91fiu_v`6I`eei_4ed;gBa00Vh<+m zbpC}FUM?Ht<$Dl*J~+y0kPNMHz^gQAZ7VTqSXG=#{K}+2vx8+Eh zzysvus)#-Z9MvlaX?;|G8R7F=>MP@*DNGO>TdDkCJMwDztCdY2Cgno8N!BnisTJi! z{#fbVLX5D>F7B<*Z*x@cv0w5M`6mk12Ks$x{nXZW*&j1sXtDek8`v$QL`Z=nPHKvHyM-#q8HR#&;lOPXN4^w^XoNxPi`C31#&`Ow!C!tYh!siphGA$!@<9|+bWNnv&5GI$GPrGLqYfb;LQfk zRhCtrU8OBZa+Oz{T}3@u-cvSOAqB2Ex9YI6$+%h`!=78U>t5MR-#=b(Zq+hy?v$45 zTO6x+k$XE0bGX4i&X+phA|DVE=l`51}nr}QlwS26vaYhO|p=oy(|%<#_W zT$2Qg@P<{?M~2~29M8L`O!MRXLpb=aZ*@X)%i+pMt{>>pcCLa)3M55VW>kXfUk~21 z>LG#YEo3}{R|6}uW}jrHLz=Y}3r6JGwMy^WwaVveP=2bnlrULr4`K6s_Wq808RY$))G~RRfYWm&%P@OB= z(YWf1=2REucI38q`|PYq)-g7;9mB`OB{(|#Y?jcDn(zJ4zaQ;;u5_=)JA7*X4qO|# z82;vP<*ro=R_<388ErkRy`wo6I`TbuqtZ%8bo4*qv6_?x)|)&I*~okWO1vx_<+&~W zTOTq3;{E=^m5r-9D?0jY`l>=2-+AxI}qk6%g zS5SUpr~Oi;%ImpOSDWQsEgJ|{e)fFtcIBtmK@XDyZ-s~A+F@5)3r@kYU0I^ni&SH8 zGZ7PgU#h2Xr81dI-yO1*YjA!3AS;i<8b0Yy5x?-~?r(sXf|apmnS3ONIaRj$q9+Np zj`b$>liK8V1`@zVwALW$#lwB>q>aiF#JhAGm8FoVQ9R~{`Cf= z$0L>76&D!>4?)Z{mJpGuM}l#O@>|}oR2OH9zroj$AP?!t&`RUO!6Oll`17oY3}2Zn zHlU3hPkm)$g&DT39fcOrAi^?c8bJNY;B4fR*r!T6cnKuD6B{ z;9II%O}|>x)NJHyX_)HNljL~aH{N(l(!H0!cju#@#H14UtV(fF92w`_1>W3fPA?h` zW{q^O!n_X}SBHZ?8+5G}JmKKt!QHDUlo!L#=a-9PJkT91UhK*gcdtrtCP-Ral8dJQ zM2|HHUpBf99X)f)8(iVw{E^+Oh>`l95qL$7f{zPh`IEAMY*g;FVosA88})7C-U;VH zZk=?bQU$xuom7+fwA-8qS^nQ8rRgG-tA>Z8)~8c# zLdS3_GKT-b7!01a3kv9|?``GVHfvk7#S-@4<0Hfpb9=f7Yf9Qpp1aend6M{?5(8_` zheLU=)(BGqJ|33C4)7NrBTy`j6`2a?XFbjeu8eDSlo5-wth~lpbGWZVWo+%1$a+`b zVXpj40*#o;+_7UzGU3IPTR#lF6O2taku< zmUWc7UM=(Fs$Xv5Yi8_E5?3(ErC%P(IS2d8bP#zjVOKLbV0Cn zw`^4m9Z7eT_RJsKwls$ydwegacShUEfj0Hqc6y%0Oh(&!`#;(uHH<}7Qg0(h;DiHn z&_-ft{dq&Qe&=JckNv&c-ou$4HFTHlQZpyQ!6WVA;IG=}*041nfzP)m&Tki-G0tZ+ zNd?sNjwBXE=vk`EQL`ElbUYH__u3=%qVM3I82LJ_|DN6DX~W3+zkAeK=1$0mAto^0 z=JPNU-w@+Ms=gHa?_s-`)Dy4%qIqN;rEuw%N{89w$}<$mZPUeze(uV)wXkH()J#3^ zi%N^c7{L1L@U&8?o9c7m4M(w)mZsWsXH5*|pClOysP_5Y^;*Z_by0nezKzBH-qANI z!lw#=1-HJeZ!X8JqoYA>(EWU0udjjS^(K!+W`WCxqZSRIf=8Z=kLW@l{617uZ zVsNEM&j6at?2wN$4hQdsc1>v06TxO1#SuNMZ`AUyhHvBF|1Fm@l8dxo&zIlA0jEca z4v(Xz3p9k(xWNg19JW-X!9o!Zc7+GP!_yU5JJJtGME1@f^n11ZU}WFujL>;Xd8oIE zsuh+#BO}K^YhmyhpiyLGA2gAA@KaT^rXSIna_dj2<4;ikfG$n!iI_W7#u-up*2V;x z;qzRWc4fvjIhyiiq@BW*!bR=Wl)!&9;Ibc8F3e`HUNFP!4%kR#1U+!ZKm?cEqN*{L zKFIVgtNmh4l7m|89X&@J%rwItLc61R% zR%eX^9>LB>a-X@f>22sU*+BKhz z@#RId2j!8{<&T(Z49*hf=#t*_ZOzTSdvwC7(It#UFKw}LfYjgp_77o05>bSJjop$n>6@2*NKFvf{;csRY?k>dVA(XQUdl#!PHz#53p}Zb&$=uMS zJ`JsCF`pL;F9c>==rb0+pEND%F=MV+)@rFqEn3c`ESW2lvJ}AT-UzI!+I*W*AYFxn zS;M{lbDI+HST;VPz+B@Q>T*GEcnPWdX= zt0QBrTz8!I3;08EDAmb|RV^LTmg_dJ@6m$AHA(R89_LH0aF*TNO5b?(dl&hH80ZMO z?gbTd%M9YevZxlQ3VXAjPY^liBZo(zYh0+qtFr94%-QNCd`9hx5I)${jL)= zLnkOMQ(Vt)anwL#r=ER+tC<0uS-xZ(pL^oR*ArW_h*`YEf*rykZ*?qQkX6FfEM?eU zN0LEuqs}c$D0SJgz!+Kg-eK6pY8ZG_Y_M5+SWfGrE1N>J_nIYxTB?7%rEu_-Fk6#U z9Bcf~7KeigAxlks32R!;Xp43(*nMU08tVD#E>CiqYdDF8zLPO;jZ#YXgDq z9~AZi0x?s`GC_1%p(hwAU(ZM8r+giiV!}c44owXQ??(?}jj_eF2UwvFM?XngykI!! z9Z;7<_>oAfbgl(pHPx5V`YBB9HJo@<%^U~+(9YJVixx2nOTecmB)}_XS&dy5*kzAU z_|v}qH!7F~p6NH=+6%(L6JZ4ulLdV>w>ly?>Y!~x*K~5Q96K9b-^(>uj+;a_q5;L8 z_>OlJd{NL>s?$o6^5#>nDhV7FH{2~5z&)76F8FngSf-YqQI5FDBxnR;OXc*KbL%V* z#|)~kArRiK(vU3uYQP2dQz6wtJZ1wz0mEUQkRWtQi&%c{b` z!J*2>G}A2de6I4LQ}EfP)@))*E=q;$$0ROuX)W+_cR`}Pd6ANQv!#Ee+>WQsY}p(= z*T8d@4XnkoCLH{9&<08`6j6IBG(qqZnGQHp7}K#??O|SA zEsG50un!FJ0T-cf%+_%5&7tkeEz|G+CFKQ}9b;q{`0-n&Z&x0((k~nFL@xlR(jIOx zd?mpT*%n(isJwh&bOd*8g9Y7tYPKus-P@J19g}OyYR=Zo@6k-2+ryc*D`U3Wd*aQy z(9?>xSr^(c(i(`&7GB2lFhUB_Y1oIb zUD0=>)XcQ$UUu3jFPV1CN3wjrkHLX_+-HmXI?9B~_!aUG+( zIk}co=N#@l3@d1?8rDX(w5Oh%-|otzT#lt+Iptfq@<-t<@F+M@?E0&RzFSw};7^BM z^Z(+}S00u9#`SuP=J#Hb{eq9S&Q2TSBRACcm+p(Uaog3BeYBMwM5{*qR?KCU5&MTO zVi7TqJn1LXYWwr|F(@;0A1B`1$0u3VU9b1H{x$nZc5VOaebKrTQTMIBXw9=Dy^jZv zSWo`F=FAbF|Ngg`8#td$))V8pfB4xOCioKMu+HR*iQTiFxrxt8?mTk=9H(}aE`czh z796){9fhfpg9L59>gUY;e%^f9uQJR2)!(L4F1**zXlk!a-uJKbm({iXmVJw%qpj`F z*jIbQZCBIxm9M8dX*TD!{xSP3;MeF{aP-6_CAo}F^X4SmU*QGE;B3W)wU!Mv{yx;e z?rS}7T3?Dfhu@O%9(rpDJke_VufD}#+I7@_3$L! zMzs{s1<0?uCvx#8o_0Q6GEPdAM%$*w+2q&Uut1nLmZZhu%#z&bF6VS7YMiy#a=h70 zrrP9~I+|yFNn?FFMHR80EOBe0NfmqI zq2doC)GMum^Xz~x@`I4u-WxcpzUxG#bDX4tZvJ3Et^3Jms(v{ss-<677uC}L5>NLH zMZWj@Vn>sy1>U=z>66rh!i_t{Pn8)D5$Nwr>VB)-{KrFpx=ps#eX3X=dIB>fb9(eK zzs@!_N7MwykyqPomW)vSAZb_%`qDH=8ZV@VgC7q57LcYXvu#!i;_&PPr3B8oyS}quKm-)%0 zGfId1jMDiMXm!&!npr1Gd&HEbicke_OKXNr(WISVEMw#_DOLn)qmp3F0p81;D@W&> z4Ep)`P$Sv_7r|)YN%gA`%~1vpYzv;P8ukQhq2*?4v?plF_5M=p4yk z^^NsMarT^#j)OGO6&enDhPwP`G~`6Izsde&$PVC>ZLvd53Z>C>|D}5`rP0^vw-MKgFvP%n%i}1B(?TH8B6?MuxpBYLwP3qy)_c+HxLr? zvq5>xmfLL%KUd%_svV#wf-}BgtD?O9xEH3rB%e% z6R-am-%{4?S~nZ86C$k*sx>FNh(CRUUef5BY;>bheVlIYqQ@`A(WX9(!I<_w8FC4$I+jZkk3zduNOo9^ZCz=Y?>q8m})3^%l>NnG%+Le zlrk4-YeTQ5g@ezAZhB@@!7Ga3?mBOFF29Dawf!gF$^bBW0^QmR#jeX?V5lB@Si%CGAY=>8nh4Pd^n&v|}}c7C_ZByyl5 zI|@~hsD{--$kWm>}7*d z{x|-1qiB(`#O0_JdEuiMm8-AkeAxI!^H6a72r*HJO3>h4h-gHq%olAV^Y#l8)lz*J zM)@D{k;7O_8SpO)2aA=5jZ@YP1%tyT(JVd;S=pw9Eh#0?C%QnjbKg_Crzg4IQ%J5c z_kZt6xuaNTy6Z02UH5+G+6COmgP-L*rE>iW>?D=z=qRe%Xg?_&DQuON?bL!IlQq!P zMmYL~IH$R_Xe9X3z_0QDV&s3UcAgTd&+@TOrr-n(TU| z$o4?>>OKZ3dz6xnb3S58pKP0Ws<}g%P}ZSX6Vk12#b|OXaVE_mm&oL8Q*N27$)P1S zAoh|Hzwm;Om@A6u%>N-w^;S{o^QQLuoNn`d^HW{-m0G0x?zlyyIA?Kj$d@!UM}nrc zi@7xj4?3#l%5mN0gw+g`l9@v_7ehg2XlY5ZF(MP>C1HO$to*bjm%hs#;C<-{Fsem# zL*I`%l@BPTfR5Xh?%H#uqdZmGbNREi=KhXFhn3GJA48xgRcRdhWSr(>uWVzNxr%cS zE8Rx=|3&2gLgfEat=<`k#XTvH;s3djWHLJs{DV{`GdV9A=Xob!N^r-WgX!PgjmYF8EW7z|&~pVOUoc z+feXjYO}=oOzj&2i9?8eD~8T* zBT%|e=|7J^>AyZdj%;Xxj^-z65*T|A9FFmw7peMV^^tt-H&a%z$hoauj8k{dNUepa1R$AlIJLpc2SX$i>x23z$z*`TYU%qd=r@Wz z5&uvYnlNoEF9!})6-MpIDp8Q)(DrD>p04U8dQ~r*SYKiBq(})Kqf}>C9oz0Y0#A6( z^BL@asbV91c$==cb(*7G416SWNGImex?C9WCqlOv)v3G&I{N4E4(hA)BOc}_6q~85 z+3b2>vCXB{yQ;Q3AqV~mu%l({Cmbp?zTE|DJOQa5s{`j$rtiH|_gjSR07YYong%Y*)F^+|< z6!>F@gLQy$+XZUJUDvL_POqc8%#ZY!n7!y}7wDSJMEgso%!W*HqgN9ctC}e5RQv4K zPHNSk8g2nx@{ZEFSB2Gp<;DtrzggNNy>8Dwc2;VD517_-RyqY5v?NWJ8F$iBP?q9a zc)M$&>-tEn;xbVG8R2qCm_ex_HWBi=Rh)u%XZUTv`(uB)_zBLNGS7#D zzYkNbC_E*BF(N!<=!v56CAxb2A;FVu#p)><^8XcU2ih=~78Y9pK08%~PRZa3`QhOs zZt=K1_3+zHm112b@Q;iEMRy`cj)!^}HP}Nw_#I9F0D^%1Hnq&`Je zgrhY=-`Cs;3^S=xSUE%NiFEg_K z0DB&_0dTNO>}uy+1U7Q&v-$5STmB=3j+#OzBkRR>oKiw4X z7EFY$lE@z^R#1)>rNG*#(VSqw@8Ha)a$}ECo!PDyr%JtkHT1Gdiv!d|Cz707yP6_- zXTvM3LwTTL$n$l@0lOwbkN!uwR8di}B9-D^&dL|;lYBR(<%%Xzg4I)m*W;*DzfnYJ z8CdQ~Ji$AS@X`u9ZSj!ug`Y3DF;(Xw)4u$yvSLy}Z`lF+ac^(Mvh<#^WQEB|t%40= z!Ug|oS>XTax3)Y3PxMig;=jsZc0U4LC33ZrB{I9{Ns;{nDp(DO{3}q%7*IT+Wf=TB znK*G1u#)@W3o$Q`$T({pSWk{9?gd1ijrfO% zf4m^-agqyvWnP?O9S&08w_P!!RG%i02VJz1O@d-f7Pi7bwD< zBTDl0;h=?5UG$|8XNn*X4xNFfjz^CnMS-&kb?HH)XC1_9G@)O4j9IWUbq=ibH{oke z`5wUrdEgzPjm|eOf32v*bI?{NLgyr?t*GUbFgIR<`p1rN5}$L$`)p31cey>Mm9c#3 zV!ADxnLNves)!dhFaO^P-gDxydQqBKHqaK&xp2A`JyD@8s^RRz8A;0qY7ZtA;h^#k z9sMZLR6*y?G{RUp?>UJNvw~o zRBk$`gOi>;zfwqquMq0*Bm&8Hc=a-)Nb)YELw%6>e@7*$!81OT>LS9Dp1-yYjU3k&&0`JpN0cz5MefKp^t^n@5 z(a!Fm{`=G)3p(DpvGdK6y*2js*gLe)=uUCBU_6Y);)3S14z}qzZ`-dNbIj{Ix}z}Q z@4#Mg=@lZ-K)}e+r=|t8)vSePocbz#cTVKjSe<0zX~osl0DUmkj)1CcJQSFy!&#L) zw!tDT1hz9XPr?gl%I6I@roStlrn1|xU?#_!Zxs)U2Lre1oSlaPIl5cC$#@!dbG(NF z7TvAh*8^6rt2rj8w9^2LN^EBbHM5Fjx4;gnZ`5=j3QW~yA*WT><13OGfo;Sr>}4Bh zFOK_O56px1thzHcV2my5Crj=LZ4S{|gm(4hLxKBr1I;#hvzwV-)bB3(dowX_=`NC4 zp-AS1Q~n}Z5dH`Mdf~YL;1yDP=-8pat7CNvR+Hixkvv3Z}3;zX@AFyciW5PO~RYVH%-?W$!C+-)uZj|J^1#3PK$4( z*3gcgO5fE?s<$Imiln+%Ur!~~(RSU^lSr-7vF(}YL-ZS|-r#>da34m#>Exk6IcDR{ zx>)%Pw-{Qg&bpK0ADl}SelLZP(7sEg{aqj?!@mr)U^w(Cr-msloN zT~1fSysT4iqXr5Awu@;bIrIA62KcgF_8v#k-xStOc^=KrZkPeT6e6z$P2k!y(G zySyN2j;djAZ!E{`dd%Knzq$P%0m7+v(b7}et(IeVtxVrMkKbmNCY<7Sh8^4v=B9)8 z&UT$hd#3R|mag(mLn{pJ*^5l$+w)?5FDes_GqY1WRftW1eoPN6nr<;m@ae-E-&%Mh zyq}EF#U2WTZ&Ug9rql8~XuuBC(CVLV0j+wO2ul#|LLeRCFly8r#pzk&+v#juWIgvB zeWC=p!6Myqnw<%|P%N!yN8!)rK}J7?b#f1#(d71dru*Q(L}!Wb%B4NBcB!YG_$WZM zQ%%u1x0>D##ONk{7Jaiw+JKcok7n*D{QNw#i}rcZyv^J|dwe6$+rcj3I?v3Kl$?$vNJ+QAo#hcOTN?Zh&=V0-~^S$Jy+~UpwtPjr1 z!1&#lJ??_bdUmi`+rzSY*q3tTgjkxAidl!G>5hNhUXZAyOtEHDul4Nyj*@Iye=Uaq z9eI;G6??nNyWj4<{Hi;c+SgoIu%}n0#YvRG9o;8Edq^#Xn?Wq?Irq>mN)uQA&Wo?B zi!)oqSb4+$|XG~5Z>@b|XV3LU6SW%os z>(>VOm@a5z880z??x!t;uC?H9?r84!XUb!=vC!8?A;o#eQb@7WycABAezq~K`lmUu zJ{C7Xu?-F>Rnlx@Fh}qM9{S)*C*Yk1STJ5d+^M&mj^Yd6I-ob=*Pigx`J8B?coU^* zI|}!HDOmpQKPVRX9pWi*DgJ-vPwjV?0?YD9H=Ebh?DEgOtY%YtSlw;?%lGxsI)FnA z>d^M8uov#PU+E%~`0he+iGRO+;MCPrIv-|G%_v2nwdsMgheYqZtgcsj1#)oShd9rs zDxmamvX5!ZDHtc-`(-Ltkt)EdEK+j&5>s^qPrsmTbE%+=XS}JP=c)h`NzXAEO{n)C zL;F-y4|+sfqEuu@;m3a9d0zbMMsZQ7{_;Jcdc`6oLPtec&$XW4hJF9bOi>p(0ZQ7Z zUQ|lq1NoRn+$4?>)7vfZvcw9HNf%F#&Bsj$W-$kR?jr*+*@wi#xF2DY81tDmcketk z_$#4(_qDgE1*Ypku#ycxF;Qv|fH{hS>&41JurT=J*I|aO#xa^^uAG*aAwXc9H(|+SWaIGBs zKLwCQdi+gacRcZjuL>#;d@Vjf>tjzB$UOfq{~x}Z`^15-{}yTE=O^sNf<-rxG5+DJ zTPvUcO82FM^jcoNtYC!P zGa}jAl?EMJqXRcP{QC4Fak)r#6a%jRP)NWUx0Ie*+qP4T#c44?VLsyJca#m{7V*4) z^tHaD-<8I%)fnmDD(Oi1u4unS?R^E;dwt2b2mCzs>kmhM-_#N^W73t%I0tce&wA|e zT!;0~M36w|FHl3$-(Hh!pTg7U|Ma4I!PHdaRK}NaLwaYM9e1U)-y&vU9g!rh7-`D&@mTe3j*33$*e)o>mG@R` zwI_McRcu!Z^=XjQk6hH4iFs-2My1dQ{h>SxEpw+RHItQY=mEpQOR#=`iiurRLwJx% zoTC8CaPT9@hb)DHmELfJvoR>`$2F-vqws1H8NQ*c8E%|Xx3_WJD=xt^%@fW-`s z1nH@1%v=@&O;PsSOys%wZF^Lwgb?||xAR+cxAS6lb)r11i}Ae&Ed`N_p}*w1 zVx6oxwTkb~sm7_}$SrgEZF@8!q_-mdY8SM==CA$lLvHyvnM}~P2=iSoUj7EQk`w4V z-=%`Bih<5w-&PL(D&PzGy~y_=@(Vau>kq#aFmg-mOXgBJJ7&HL^ut`uX4Br@Fla%W zDj&Tehw23BjUCiBMBCE0B;tevlQ-T=?_yNV*=0{TsdF~sTmvb`DYLv?_JpIn96P{6 zOA`*l&q_Y4@baIb!QkZ-+yg=-ZeIShHR2ycSb;}q!o8nyCB#B~v2iL%Z}QN8<|aG+ z&*O2rRP9Ww&THKxSz1{m^t%JOmOU639nTT;iFJ0mPT_>z5F}Xo4YD8PJ$?OiO=RMs zJ2bfORM@i#ch>N~IUw=SqtKndNz{2j8LIYEi^PrpP=p0L#c@>(YF{=m*+Xr}B!|d3 z8;FtKZ>QR-0;hQynq*#{J)mkd&C%yv=wx=IpE7B$SVDwa1V6$zKl?5`u{0V_Sw@5t z2pP+X@C3r&5gHL_-n_era2xWmXeSTz21#=R-$=Ece8WB6rTve?mYfh)jqkV|tfP5M zkvxGqX*{1vE`L>b<^oD+;}enzZ>ob`J0(m@v)ma!Z+fEWD*k_2)QA7|MY2DAB6Q+2 zdHG?5H)*zNUJVD?@RX_jzAyc>=6*=fL_Si-H`04(ILJ=#)ZvW$MArBWph4*+FK0pH z#N#XwFY4cpd?&p8p3(_R`5ycDPQDTL7)pzAOA+4ynA#X{6KSomJMT)XPO6%FIgw*c znper>Hj&?&fun-rQ+-MWZ#D<@qA(s6qYw9TB{6^4wP zv(;{s)#zPk1Y*l0ZROOFi8qMTy2;d=d=I71@@jrNp=6=-ZtHeYD+)$VX5yC%?|`Cd zy!G;fj{5$5uD+jh)XPSW$;a(J)8~U9^k6K0A0T7WLm$ITf5OIRbv4rydi6bHC-?jK znH0u*?H_ky=3dqOE*zXVLdSw*tmo;?K+lFXTMzr`I-={L8hg+I#1A4++VF7_0>0Dr zOV@{HFQirNIB|uMZ3qX?g7$V?{?H9cPs=vG4M~u40PY%7q_6a9UP}g?)59u}H>tO(f!Dts&JrnpZ=<KlpXKQ^*t-fjKAehWCAL~%Nb(aVNUe;Hk~w-3vnwdtdL6z4UsvZiQy z$uRB5E5oBAoFQFlX~ECz%3HZF2HIL!*j~E>1ob!u?1dL&OHEz1?9lNZBqHH(fyA*_G)sN>s-? z68sV#=qqsc;tSxzdf-bpp4Gq?XaMIMVH*-DCy{3Xl_l-;ds2%Ibf4ttPQ^QEoh)vB zrh6&f|EP5(#%XjJBzk6zF@wipjL7lS0F(JOWK<2jZfPB~4cZ>-q}&Is(P%IJg<-cgOTsXPt#(Ynikx(m8tEDj*pecVsw0DbWzP9g~WiL=2gH&hz8)n!!e}? zU_(-1yEKXU7;i2u<7I9kQ?K}#88W3q4~HUU;DKR* zk}nke2(*S5GjJ2eNU$*!wZs^@IeA?8vR@n7t>;%WQ{WXjMewfhz^cMu^cPF+YDRu! z@N>Ttx1ty@t5@MQNN)o(@TdHg4{;AuZ9DGJIY@aGJ*+cAONqxRZ3f&_T#{ppE6F2N zu(CONvcXc?-?fGZ~P(Ng1mXRBE`9CNmnG3`d1WmVf&LU$8Lg@;nz;BK5l zEf%+}r1}}E;n<9_=c>zF$+RQ5Q-~vkdH5>TuD2LG|-eHth4fvXOd)=O^iM7TAg zf)7lIDFW6l#cgRBU1TC;H!ainqMbi_uDZ)Jsug8adny@7h>aCH3eP@g`Bh?bTJtX4 zlC!5WZDpE=n2pdO?WajW0>IL2ow7%*>=RVTXTI_JEJt8w~BS@U$dT+kJF@AURGiZtGhx zTDGZ*>FrjV-PH33Fr$`Q3bWmn^t=g$#I}m9g`YoX{#6Wm@VtGpZ+E2s|M`{mQg}V% zKU=*Uwx4vIFk_oo`O^p#DTjKln!r=@@qP4J+rNGvAgX#i0>Q8RwB&a%`31f%P(46l ztg49I$5k)gU7-#bB6oMaiF+F@U45wKMqgevcvd;Anc-z_m`ca+BX>sSJw|mnm96_L zt+2&H&jxD{y(@}RhEGD2$CT@6T4N+_eFP-#h3Ad4Sks#(u}{Oi%czr<;unq3vRq$PNvTA>GSx2F{VJVxcJ_B zu1H*4#>&e><y^>7)^N?fA;@f7>1RQdA?5nd7&PjB^JP?cJKVmIy`1LeQ!!;MX`3sA>D zai?Z#S8p{ZhnX$=|5sz*0@uWq_I)Okga8pDctJo61QY}$3f^rE0R|PjTD7gMb{j%DGw$`>=g3^^*i>+ ze~C8aY^o3C&*MIe696s(^IrH(g}PM%yYU?8_SS?0z$u~GIH3}; z(!H(|=LoRaSjEswbbxW?CJ$noaw4J$ODI{)M#zUiu+O-*~={ouBB^%$4sMtJV; zt-pX91~)>{kbb#sTd|>IQ1k^CQNVw2yx4|zt^W6RP1$_urC>jaxNr$`Y69leo$+5O zh<}+l$E<8i+1!Q@nBC2+F(%$iqvIaw?AcTnYES+`*`_^M70-M2Y_j1UW(LIk+kc4n zQ$Nt2uivx)@#y>9#3P;so9gbyj)}iT@$VtcIU4#4VeU&WnSMj-Rjjiw#wFJA`?zfN z*|JSWp}r;{6$I`ylH}!U9_tOmGUA-P&|_}~S0GzO=zOfxQxEE}^ZXmO-w={UZoTaV z57ph|TaUd@y4-P$bkKiqjdXng4fOBaEc+5r4le;q&{WzkmX%gwPCAcs_Dq|pq7o38SbHvN#R?uMwwP6G%NHH?t>D%6zf+# z^#4ZSBzRs06|pF<%Ee5zR&Z#Hh9fm1%Tizb^L##wcg5r4ayvW`kaG(&0;n5U7-}I$ zSg`4jjlDC3!TnP&QG+gFM6F>JTowF1^H!eO=}a35^RXTN>SSG8?(km)6p_ z38s0*Lp>B)gf1?HXeDJPOh4@!h*ChNznl2|T35bM2U>Rm_U({k2bwg|1HiE%>>4L8 zf>%X)642+Z0j*ASFAxu^Ela10$JU*2Ko+|qu9$EbYN1chGW9K(s~LqtIQ-N5hZvu} z72G|J-Zt?fVVx+nhG27k?nuYXcfTJJI=1xYT*#lq!@2Eru<>qV|JFZ!+zc# zzwEJP=a&Jg!T#9tAB=n!ois$m*t{N+lt|1{;`pGJA}AE_;<2`J$QrYv0~-> z_gJ%7$MZUi;Fq#}Tjj@5ALT%dm^YJUm%7y*Tf@)DTY&>L-L+g~$+_zdVk6Mv;tJ6+ z#{KPl1X?qfPS18W)`G*&OevdR!pu}_&2*bEN7jNqrZ(h29dqLuP<#6;t=QAGzbNVK z6x8B_T_Z6Q1*9D8?2mgczXaaMQEudd%53ZpG)Ln>DSfwgC(WwHVETXY>@R9R8!vnf zP20hRqpO#C6Ew&nkRMEfcG{Q87L3(zdV;HNaFqpJr1{Y^c`;$A)QGx@d$)nJGr}C( zu_RjW+StrjqugA#bV<>_S`b3c9e0FqG^k}BHs1zXGv)eBj~9BU54I381l9dk`7s0U zRcUJE`Nj_Cubf3r6ZmvS$a8Z_iv*;u9?n!F&qK(0Y}^st8Amr4puGsW`%&=At|>D@ zdf>W3zx~|j+a83T3ELz85rgDW=N7bIEM%k{aA{ohBDUe#K<5Zv;F+&&Kn<*M3{};# zf6*Cm$@VS8HR6BQENjiS%yBI?6IXji-sGS$Hyry8warYpNgH^=!CM>LbF9UlgC!r7 zQ;xpexMx$eZ&O!H<5pmFmtu7b?mX1kdC*)$ySCscj_T^&seKECsn@Zuq1}r{*)!op z-r9EVtxbELn%sEmaqFBtG%MK&x$!mYo*M4LUOBaa8~KGt-LVNY$4EcMjB%teMc^i2 z%-{q-a(p2h9HW+jGBUA7`SH`s5s@i3camL&84xoydp?Ly+DtZkh+6ndOYhb+q0n2eojK%so8|&+7+g7>E%pdr7 zNj01Gp?0Jz>ct(Ge7UOHNbgfCZn)dehfYGqi*W`k3(}4C?;u;e}`V?V;Bqb z&A)b1Z0NLLy!=4 zkLa>e#G`L>6I(o`o8Gt^duqZh&`13>FDU(xP(mMc>Y#noEyc>D#X~d#^)akUkZGj# zLoL(-#l|7eF@UG(Z(G8P^FTQmmj+!MT%ug&iE+h559@`sG%oMav%w$3JT)C0i2!JO zX1dc@S@TW}^=*?l4^r=#mq7yszf60C8nKVSvZlIdcKa|e3fd*R0)JbQ;mm}FBISUY zE-l)Yp5nU4c0a^M>w!)trob2S4-Wm9kAa_Ay7cF<%bvV< zJ~0Aym}%_KH3wwcW49fS5&CVFmzAxY#-`9M@^C~jM128Sm`oq_!w zc*cR!wi+9kLf_viA4E7+D4Y?gTy@nz3Owj{NbzeZw&DF>!2$SQtG>PAS2Ty#*qnkT znd+j=Z@01ZiLN(gU4yn%KjvXrJR4l{aM5Yob*!(SX~8Fpuq9JjP9WsC1KQF7(^f!c z9`&>_$k`!23vqU6mNKLKugNs$LEhvhH;U#wnmcu4eo@p44WaoJiJ&~vg}P$su@Kew zGO&l$uX>~krn^$fbeErIIzrRwFX$l8S%I<1yyJZ)aX9W1AlI?2m`W0s76}wZb)m{(qPZ|RxWhxvQgjpMAkc~XA>o(5$w&h-s;D2xgT3;&Hd3$ z+&ADHVMKi2`6uOMx1#5OGOijtR5s$zL<_IV>Z1>?`rWGOSGg?rDi?GFUzPbS!c}hQ zma4v0maE|-&dOCY`+9BaXy4|Z)$ZAlI^29qJCXK`CzU-Tf1+SQ`Sj)vRrF9-a|a)t zg?|o`KOZ}?M6yr9fD2@TEVMddiE#Vlkl`@vBK9RVr} zOAkNKOqJDINKftJ(vijo;I4Q``)f@Gp2owj3d^u~H#?s2ZSJ5RXuOmUk$ z#~6=O%db6L#`A7GnYqj=@B-`1yNXoU6YMHl=4M$-!RsOF82$#j8-o4H2cGJTG9?Df zeBz&CJcJmt(OVMjIFrkI&^@clIDsGj09GJiQmeA>+nrGy3SZ!!EB`Vl%$SKYwnMVo zxWlnc)*5##Tjxp680`)lkxSu>TZ?ks1<;ZBQvRiJ$GUy;0^`nA>*R&zv$6bRV9)60x&OTGXu;#$l94 zhH0I7ws9fJoq`+F)1g6SYS3n2(d0U+!xdtVkacjVe8kp)*x9cLxeuLQnPmeZ;LRp#hPFvZf z8ujgYE9w^*N`O|F7hSSJR&Rk`k9ne?oTPdm@1iq~9%*PGOtIOKC3H!u?l(O%g*mu8 z=L-|+z|%Pc9!eLk?{S%%);6paBc~aXe=9$NRYL^*JE2R2G{f7VBq@#tIsiUta#uQ@ zE_9J43W`r_hB`eHEe=hnWPb1v*8c(8)#y9Hl}sEYtg)&(RH}Zh7RH-Y<}&-yMx$NZ z#+%f}5_`BwXWwZ5(r!Nz{=oO1@CUxb)#kZAAJSwpmk3On#oyAXWT0VNCcedV@8L4z z8jXuhu@_H=%cVogz@nCY6rizZZM;_$ra09RmW>M-;a zoetxqBj7M`$*PnY-tee8`=wyFk>l|krf++;Mow~=R+O&Tv*NoI$t%lNdVndi` zbEVHMMNH$-=)xK~nR%XDT2UjL95cKTx+lG>!)oL-bB#RIQ6s0=EyHT$VQn>Xs=Y=| zw=F@e;pQmB%0ynW5F*1?BWEM@2wXY1%tveFk?cCs%SDJ$@XbTa(eN2#sFBCQcO2VS zVZ#o$MjnrAg0V)Ph!B$y;y%OupdP)|B$c59Kacai2l)*`pYlsXo0-?zEH|xzO$}ND zOs7t;KxWF>^~{2u_gkG|g6Mps$^i=D6MwOs#_Y}9ef3qZTQ%p$p{Kp&2c9O2XnO=c zT~eJNS_z|@te(?P+TOG?Bkf8D!deaS8oQ)zM`&-nwu-wi?37LHlGbD2Mf?h%botQx z%s#YCJo~7*&~QKV8hryg43G<^H(k;*{>x}vc?Q{yS_j$4!2;|rcwODq_8gLFLF{uSsw@#m)?^xmHIw)2oRjQ~FBIjkSB!^6*Q znQxtsTAy)sBk+FIF}0$RJKg-L%pB_W6BNogdoEx2gbjD*dAR%i-McBmMH_SmpIijxhNaFfx^W@0L&Z@(9zZ@0w^BMYu70JSjrKl^VFiG- zYx>`3dq>Q5W`bWa5%JQIM`{b5`VK~HgqrMo>D0G?p0}3tAH2hfdiMr!hTgB0W%X%& zr|KY54?q8%p%PLyVaO|`s_s`W<~EZi4eLRCromZ>Nmv59&=3|U>T;p;l{iW`Y~?>4 zAlz{q(B?EVEr#Y0boIJvuFC8D9{XBIi-a`Mx}=1kSps0*`H@m)+*r$bLD{ie%e9fv*eVq0c4-xj|fJe*PS)!^N=tOGBIPDKCI z6ETHf&%wG4^wp|~lUabeXhTY*Eu@2X@P)(NM82BzZz&FN(J_0(DY`Jjn^{7lxl1bc z#X-I)XZTHM#;}e!o|^<6ubh}>$U)n0cyfmOT#&HHyoD23ehT5I_UiM}S@aL!$ukpC z+XIAHo2qJE0~=oCdI|C}uvx)#`%Yfrb5FurAY{lOkv94~_lJvD_&MWH+A%U;FffHyGqrY`&eOhpC7MS%b24P;6mX*kRpn$r(imsRGI(MdA-*bS zxXv|fT0ir!shqb%uEZHrzAMv~R+26zihNa0=6!B9bgVGFIYn3s+GuzwtO2M$zoL3J z4*gEuF_0@D?WC`vqmV;r718bpXU_0}?tt`3fUi32ytJNhH~7qcu6l7OY>Gv;rNCe1 z+FGPJ{oOg1N@=DDr#)rjFdK(T5knjI; z=7COLDC(Vc;EGW{D)2KC@|KIdVu_$%4i?8^#^DF52?+}+e`@)J%A6F~*@BP4)T-i%qs2g;#yA2Yzumu4boAIU=eT; zgB1aF(x6t=A09;CBKlmN)Tb4a)Jst#Z&GU+T$=4PT0aEc3KTI=v*Uz!FlP4owA)1V zz6Lp>%^zwjgL`5{qL|mL-B#C3dl02pzL;@U$IlWdmAc{!upJeSPzfkayDJ@gj?y=l~BgRQ^%JJh~f_)P;zYQmm)05u2cQ`J89JMdDGKRx6$)!SIDX6MB#su;rG zQYWd-tM&n}3p`=6Sr~P2V3TG)&SMj(1Fb@nHBD#q1`7|ZQ^P@CtN~(T*f;Z? zriv2hPI00W8fGPNO3l(8)v*pIAV0O~WXu;owdr5)(WcFJzl7F4s22Bz>AqPb&T}T< z3$6dpFL19u>g3-JNPYh48yA&tP=E6&v*p#hWvcnvmz=lrSL>RNi5mB#K;i9@0)FCy z)9DQL=+D8))(hB!WIXIj9zN&Xu~4f;y7`I-$i2=}P7n*RZloBw+!Z!!+uI0xzbiQ< zZlo=-3%gm;7JNsHha_yP5?7Tu(5+S8?GPiH6Dpu>kEeh%wEJDLOne8@B|Fx0qjppW zq+CoGe5hnv3l@Nm_pHuMM1tukHksNwRavmQ<6|G2c7-?+m}r#x#C8BRlb zEq2;rL+8vD_HcVB-%;+&iiFB~Cs`bWlmPz8R=pYY%Odmx`;j_uS(tYYW=EFlm*!(% zl_)3_VS!fI*svZ{0~`m9`-VLp;%!-|rnV4nQs*OS<&8}-EL6)Ds zG)!nNQeT(^UP(vmO4~m?nHAiA@}c@uCwW@AvDZDjtsl0$C-xH{w=om?>Ro-DyNjZ+ zv(eeV#GC%kch+;c@1S0qx>(M67tQai6SHpK)39#A4cE66iZl{Ffz-lUv|6;#o3}wI zv+2Nvr}`b3R|)Rkei~EiBuFjo9BkuWr*u9Hh_*gczPO^&K$949xg@=yH~PU{=7pI~ zZVOA**!GFrFoO5WmoeTRfh{{)ORjjfV!b;iJ_?@6XV7W5S*%T32aNY2!lSKN+q`=q zodxu=i`?5J1jZL8PQrV_k8O)2QB1wXQFMUa9obdhhhkkwq3=PF z5>-Pso&r)c;%Qo`r&U5qmeT39Z8sC^@_waO>e06Ki22{(yp21e!DYV{ot3r#@N(hRZ{P$wcSu=m$L!U+0d!CsLCS(P1vT783s8xDtE@^`O4*UTAb+Xg&mvJH7IUMPb;Nv3VKE$KPg zGaFWCfWLxoQ#pd=%0j7vxcg+A#pH|=8+;D0B^;uuvOqjQ+iDZOz`17I5f{K9*j zKc5BS1N9Vs9c;MbWS4hnE;6HWVXrM6@a7k4K#!NzbV|uRu!6@(e#BzEj`r=(+LiRF zjg9EBCj$InpDReYe2%q83rR)4B=jijsTr+p>_RVR>3Jl{caOaA>x%CLmeZ-A#vT0r zQtt*f?g+n*&YXEiFsD%$^e7G1;l*pLeZV12Wu3~ZgR_B!ozfdU!I;eW9T0(o2=W)f zXE=*`Ac~4;7mboHUw7|1PaJZx6)j7X$U@;gxa67Z;??12GGU)A>YE_{S(e6N-NddT z>*hsn5{=ha1F4NyJz0+H9`H|-K$o-*$ryN6mSV6Xs&T$q0sS8~^Cd{P!b<0X2EY@h) z5s8K!5z516#g0lO=7-mNQt?KeY}y1Qgc_iSJ=ZB!`?=&Fz)u_`^LU2OL{klVy<)S2 z`ltr|4p!J!)2e$EJ&-IT_Vz)$PEIEYvefqo`6{U&QSV`}we+9AOS>RFXuNH(?ZVQ>yV&rtE|xL+KS);< z08ge9Jgp&9xx6K|DDiWw+ez4Y`avmWwV9C{W_m@O7sq|mR~*?~Z|!%Xub9#NeSGZH zYaRpapLjj%M7}V17d4G+UC;3u+Nh_;w7nw!&RXBj@q62O_3m~x_loUDw`MBM@{@e; z+JYy_ifx{13+ynVz91`I0y|Y{0vpOr*kLn?v7j5FQF76KgmUzKmr1c>Rjt^uDi8(R zQJkN^K5h%ehx93U)l}w*E~_{Mi2P%FEt&s|tu@Wpmoz}4pG{Q%;}mJA;U7*DW8QC9_ zk*p5aDKfq#Q|LQz%!2D3? zt6Z^uAxZh=x`_Y5l9Q%j2GF4-ZAat2m8*^>Ov`Tvm(Fy}AH^~6Um#(|2?M7Q$NM~Z z8QSDdP$d@R;J-U@s%T)QAsO`xV}MrV2bHxBXN>c0Ec*-B9CVg(Kn8|- zO0+Q^*b_R7B(3~7Fe{ApYh!I0o0!f3*N%BKN+?R|FLTib=Zb_2K+3Qm>6DfQZhLy= z{!E?(*DpP@Ez;&)0Uz)VD0LGQ~RtBp308L-g>yr<-VdS*k#i@Pv9(g3-rHL zTH#!zxHEoMVWe%8O($BgGTCiYU{_FW=CMPMFE{~inP1BHX*+c4i_XY)9czV^y&bj~ zXRE9?pSIW&ar6yH3>MkrCd!l8{3V-(CO z&h3|KKO|JDIQRvwVf9$PCA5}A+EgV41q~Betu6ZseDycZVzC2m_D&vO2xki*9b{hq**6sQ2-& zQuq|?Kh^vE(&+9m;NlrTqx+?eSbJzXm>*gn-PA_FJ10T zQS@e+<@x6RZ7l7Y#|H`ss6OBa`hmwwzDvE#GRZmGiCJFevi3tl534J*s?Cs&^A@aa zfMzy*Ien&!zISt{XjEjcjO$q~9s)`v=p zq}!ZpOKD@n{!S8>e~Zib9HO zZ~_*{qnu{voOUm?vJt1;v}d6`tJ<&0v2CtmU7K_l+(%5LYVSXq$}Ukf{5vB2F*6e2EWR-_1Vg_3lCSGzd8f+d>@+imVS zw0nZ>W=IQ$8Az`PXXb%kJGa^rASl_iCDzgco2Fz9_AE!Q@FOGbM7OMch3Ou`MVL#+ zL@xIjjS}EB@k%&)f<9}=KO!UILQZnUWQiNC;65e)N z&{O&&)jP0Ho`bK9SKjF9jSKs0dyb%Wj#ae3z14c`#DL6HMOaQ7tdJfZF1ty`CqjU{ zQD5eLNzr#6fN?e+e2^4bl?}Wnta!{jP#%RDbjGdfWkj_Bdkkn@ehGTXqV9+>UE>NL zr%vA#l7OV0O9aAhScX1vh^1I=^herH9P&232)p-+KDEelX1gX<9Ba1R=#%@pwaJtoES!ELyvTaL00PcPT;oNFX_m&}_hf9siu^xQ5=^)D`N zzvYJh!JrK3sn#RdPv<(wZlaEz@I)Pat|{z2?rq>iRkGjqNDpIgu5G2YlLMEQPKRhG z;e)Pq?@oef6uZJP4C03!cN&^?IL`u=jlJ(}@YXw9)v(-7^p{bt6OGN^ttWhAe)x}W zwL(kwSGb)08TwMoF7TvvO&VAcgp3dAbo+vo!^y*}rF1RHE7GpTFIj!1NttorljD3L zU5K}1$Aq(mJDy)RFK=cUAES*hljlRapoOI;VypzgSp!LQ?9&2e-_JL{D&VSEAy`n1TIA6ykS6T_~`lsumdTq|}L8U4KXDGu}I6aQQHx?0$T*~S9%-W#j~h2nFKz87v-ou5L( zA=SscuUKBQSgvyVt(F;A2Tn2RKl00WhWK9W(fJ2_QgD?k(E6h~wp+0(#A!PMW`}oB z^>(Y}#(-+o{Syo4#qVuA;FrBRzah8qDqqO_Q9W-Kg`b-=h+%K-@M@~xEVA5CRjbBL zDzseHTK2X_soBuM&NCL}Y@uKz=r~yRY!3XD^2CPEbe~8-E`EXU%iPcd{+_O6eUv{j z7j_l$b$Qr43 zyKxTswtIoHV7aQdw0Jh6G%OoDeptHzKOYiA!F(L>t+~TSOmlCvs!qRv)DJmo;!E3k zjx(bEviG?VcKRD0)EjT~@poRca6Xlna(m8VF5vaZ1J#=xNG4l#ls!q4J^bCapmEmYq|L8((-L9yKRadA{f{>Up2`R*Fx5 zGqJ$v(@UIBdvnIse!oce={trLOr#ui4)N6>2ZJaF`Qd(@Z$pvFr@g@tQg^O24q8Cw zDW^6R3FqGKP=zNK?rx9ZTJF|f@l~!ExsVT`_B_;rBS)M%RFs8W3`6UMTi$Bdh1L00 z>t_^w0sX@G(*s?PI}fx+sh(`-!oqy|t{ax=KoF8FsHb6UXs}L4fCC%}yvZwnj}yB8 zUQl%T)S-4&R0VdE+_-N&I^mSZCcNaS7MeYagl9ZvVVdXN4wZgf2$M zZ4FIkqi(t^jqJkME*pXwP?j>gCL3ib9o8)PX(k|VgX7ZTfE~EAxFGv(gl*nVEiih1 zWp5Sd7C@V&lX<`H3~GNi0T;Ldyj`L#PvU)3Cqwuh_z(K82j;Gx?B#$aCVM%vVB01f z{E5D}*G*0F?wgfz%K+?C?KFCma?62x$}6m*&o$s;EWl+c`9OYc%xm_|@N&vd2&c#& z(pMY(K_A1ye3TJ{^|KV?3E*DxO(|)%)sWGN>ZnJVKrMV3|x2YW+Z!9OwjlL z)gf!9>$UZVz>ngL`ZSH7r93S5|5g4Cs24+%!Fq#(n*^7h6J7brv##Z_v;|3#!pfuw zV4n;;g>&Dfa})ooIV<%AYoeVyw=MB;yCvQWZrC@TN7Jr&=B9Z(52szmDh)l9#g{#C zpuA9T$kS1@2Ul`*u2PRbbPVCrK{-PvhIfHVo+3+w4|B=f6rX2ExSCDI#if(48on%< z{QDe+MX-PJ*ELayNSE$NIQ%>P4(!A}Y1G0x4iMC(+aGH1_Il{83YZbBr8jNDpj~rQ zx6V-9o?np0o4=>qe&3B`8cc(zL@saMBk}Qn0T%`G6H!r=E4_TQea~C~WxMu#lcaTrTvi zP7hK6v1h5|ySn)7aA00Arf*4wE+$K!4auQF1)7pUsEe1tn;56;i2R?2sjzK|(RFT{E2ygO3eN8sG2 z=<(eS*rldYwA`HWa@h1r$VA3Mz9!5?C93b@Cf#<^$-=lJaYC2JQZgOB%)~m3Dz1t%2QmoB@CB>vjuYq%wGTM% za#M6VQd*=2zMCNYQbEFg3i;@fD!W+vR3#Vd0%71G6a!N@AWaLXO%nvFho=MW;*4AN z1^VPm@##W>ioexX7LXPM9Ev}MosZnZP6zf5=EIOVLG97=g8>t0Z;BU8FZhniIi*W~ zm`>t`2YzsBZ?n>f!c-tAiT{R}DAO+?x)ie6mM(xJ(R(-Zk~Gqe};3 zx1>THlHdD1pgwb1NlU{IagYsC%DkLvx+>-*>}r=@}(H zf}HNK=DL^TE)jPl+>N-4!(E2^2JZUdF4aA%;t}L{hjoa1Iqvkhi+4BTPKUex?i;vM zBsR%=LWK&^RCX{A4U)KfJj5u)l=+k#lwBc+n} zc=VXp)Xb+zPYERZq)!hUnl#g?Y!dVv(;0A&A$e2=O5qmC907-k0d?L8+m>`9i`6YDg}l819`%r{u6O~Bp4*}i5P zX zURt`aeEAbkmsTuc`F6W?dBu_^AF{KG<;!w#J@L$v@+y0I*~;>T6)TqG^OKe=T~hjV z`TdO2yAlU{sF2HtTrE6K;(ZvN$<^WcINXSke>k2gUS#N5A9DMI+!f`^%a$&gFu_^M<1*mt{UxgA<}56KHfQC^RkN#Dp!fB^xJp~myNuyX zcLdk#up3>C>yvb*>x(NBS2?av@NOC0Rk)f$7ZiqdrP)lk9aqx`rhA)QT$JAH@aq@} ztS`L(Ev^dOSHfME3*OYzm|6Tt$%|{jq7)~sLy?gON%QD zfvN51A~1cd0fEBdQiq^EV8a8o{m~fE18^N_j8WUu2cpPDg3;vu4c|4u{gh)Wa%*_T zlZ%AZaE-gen1-Ie(lIT$hA0*Wmw3lIdfwWXg~PR7faMm}6te)5Ro*8J~_itCD*t+>dG;}!puc1_BCYu`7f zJ5$Hs_tve#?&vp0z5d#!uXP{JODkCV?!t8KmsIumrCJn+JsNb^9aG$z|9ve#SkC-{ zflD+^O^0fQ+ntlI@H56eFlw;5bINlsJT|Fi#p;VQ`aeT$oyG3BH{MI_1-f~SFj|Q*87WtZb8V+4!!S-aMouQSF#5%<}2Bhl80u`F+P<4 zu<;jFD`(ElV=?GrDm3VVktGbaM^ro)xE8yL>FA;|@F6#CMNZlZ^y|2)FdpExFE}7mLVAlvg2V?&iTHgzf literal 0 HcmV?d00001 diff --git a/boards/hkust/nxt-dual/firmware.prototype b/boards/hkust/nxt-dual/firmware.prototype new file mode 100644 index 000000000000..e236ff1bcf5b --- /dev/null +++ b/boards/hkust/nxt-dual/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1013, + "magic": "PX4FWv1", + "description": "Firmware for the MatekH743-slim board", + "image": "", + "build_time": 0, + "summary": "MatekH743-mini", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1835008, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/hkust/nxt-dual/init/rc.board_defaults b/boards/hkust/nxt-dual/init/rc.board_defaults new file mode 100644 index 000000000000..a4afdd873eeb --- /dev/null +++ b/boards/hkust/nxt-dual/init/rc.board_defaults @@ -0,0 +1,24 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ +param set-default BAT1_A_PER_V 17 +param set-default BAT1_N_CELLS 4 +param set-default BAT1_V_CHARGED 4.2 +param set-default BAT1_V_DIV 10.1 +param set-default BAT1_V_EMPTY 3.2 + +param set-default SYS_HAS_MAG 0 +param set-default PWM_MAIN_TIM0 -4 +param set-default RC_INPUT_PROTO -1 + +param set-default IMU_GYRO_RATEMAX 2000 +param set-default SYS_AUTOSTART 4001 +param set-default MC_PITCHRATE_K 0.4 +param set-default MC_ROLLRATE_K 0.35 +param set-default MC_YAWRATE_K 1.2 +param set-default MC_YAWRATE_MAX 360 +param set-default MAV_TYPE 2 +param set-default CA_AIRFRAME 0 +param set-default CA_ROTOR_COUNT 4 +param set-default CBRK_SUPPLY_CHK 894281 diff --git a/boards/hkust/nxt-dual/init/rc.board_extras b/boards/hkust/nxt-dual/init/rc.board_extras new file mode 100644 index 000000000000..780b13dc96b3 --- /dev/null +++ b/boards/hkust/nxt-dual/init/rc.board_extras @@ -0,0 +1,13 @@ +#!/bin/sh +# +# board specific extras init +#------------------------------------------------------------------------------ + +# NxtV1 does not have OSD +# if ! param compare OSD_ATXXXX_CFG 0 +# then +# atxxxx start -s +# fi + +# DShot telemetry is always on UART7 +# dshot telemetry /dev/ttyS5 diff --git a/boards/hkust/nxt-dual/init/rc.board_sensors b/boards/hkust/nxt-dual/init/rc.board_sensors new file mode 100644 index 000000000000..3091824e8b20 --- /dev/null +++ b/boards/hkust/nxt-dual/init/rc.board_sensors @@ -0,0 +1,16 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ + +board_adc start + +# # Internal SPI bus BMI088 accel/gyro +bmi088 -s -b 1 -A -R 2 start +bmi088 -s -b 1 -G -R 2 start + +bmi088 -s -b 4 -A -R 2 start +bmi088 -s -b 4 -G -R 2 start + +# internal baro +spl06 -X -a 0x77 start diff --git a/boards/hkust/nxt-dual/nuttx-config/Kconfig b/boards/hkust/nxt-dual/nuttx-config/Kconfig new file mode 100644 index 000000000000..bb33d3cfda4d --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig b/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig new file mode 100644 index 000000000000..42a2a2bcf1f9 --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig @@ -0,0 +1,92 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-dual/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004b +CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +#TODO:ally for VENDOR ID in the future +CONFIG_CDCACM_VENDORID=0x3162 +CONFIG_CDCACM_VENDORSTR="Matek" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_USART6=y #debug port, can be modified to UART8 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=300 +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/hkust/nxt-dual/nuttx-config/include/board.h b/boards/hkust/nxt-dual/nuttx-config/include/board.h new file mode 100644 index 000000000000..436b172b1ff9 --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/include/board.h @@ -0,0 +1,487 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6u/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * 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 NuttX 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 __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The MatekH743-Slim board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 clock source */ + +// #define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED, + * that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PBA10 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */ +#define GPIO_USART1_CK GPIO_USART1_CK /* PB8 NC */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_CK GPIO_USART2_CK_2 /* PD7 NC */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ +#define GPIO_USART3_CK GPIO_USART3_CK_3 /* PD10 NC */ + +#define GPIO_UART4_RX GPIO_UART4_RX_3 /* PB8 */ +#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */ +#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 NC */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + +/* SPI + * + + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */ +#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_2) /* PE2 */ + +/* I2C + * + + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_1 /* PD12 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_1 /* PD13 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN12) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN13) + + +/* SDMMC1 + * + * SDMMC1_D0 PC8 + * SDMMC1_D1 PC9 + * SDMMC1_D2 PC10 + * SDMMC1_D3 PC11 + * SDMMC1_CK PC12 + * SDMMC1_CMD PD2 + */ + +// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */ +// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */ +// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */ +// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */ +// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */ +// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +// #if defined(CONFIG_BOARD_USE_PROBES) +// # include "stm32_gpio.h" +// # define PROBE_N(n) (1<<((n)-1)) +// # define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +// # define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +// # define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +// # define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +// # define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +// # define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +// # define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +// # define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +// # define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +// # define PROBE_INIT(mask) \ +// do { \ +// if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ +// if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ +// if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ +// if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ +// if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ +// if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ +// if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ +// if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ +// if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ +// } while(0) + +// # define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +// # define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +// #else +// # define PROBE_INIT(mask) +// # define PROBE(n,s) +// # define PROBE_MARK(n) +// #endif + +#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */ diff --git a/boards/hkust/nxt-dual/nuttx-config/include/board_dma_map.h b/boards/hkust/nxt-dual/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..a27735b3541e --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/include/board_dma_map.h @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2021 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 +// #define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +// #define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */ + +// DMAMUX2 +// #define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* DMA1:61 */ +// #define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* DMA1:62 */ + +// #define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */ +// #define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */ + +//TODO: UART DMA test +// #define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_1 /*DMA2:41*/ +// #define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_1 /*DMA2:42*/ + +// #define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */ +// #define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */ + +// #define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* DMA2:45 */ +// #define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* DMA2:46 */ + +#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA1:63 */ +#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA1:64 */ + +// #define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_0 /* DMA1:65 */ +// #define DMAMAP_UART5_TX DMAMAP_DMA12_UART5RX_0 /* DMA1:66 */ diff --git a/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig b/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..8dc5c7cf5790 --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig @@ -0,0 +1,288 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PRINTF is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-dual/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="Matek" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=n +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_IOB=y +CONFIG_MM_REGIONS=4 +# Avaible in Dual Version TODO: MTD IO error +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_MTD_W25=y +CONFIG_MTD_W25QXXXJV=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC2=y +CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SDMMC1_DMA=y +CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024 +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +# CONFIG_STM32H7_SPI1_DMA=y +# CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +# CONFIG_STM32H7_SPI3_DMA=y +# CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI4=y +# CONFIG_STM32H7_SPI4_DMA=y +# CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI_DMA=y +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM2=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +# CONFIG_STM32H7_TIM5=y +# CONFIG_STM32H7_TIM6=y +# CONFIG_STM32H7_TIM7=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_USART1=y #ttyS0 +CONFIG_STM32H7_USART2=y #ttyS1 +CONFIG_STM32H7_USART3=y #ttyS2 +CONFIG_STM32H7_UART4=y #ttyS3 +CONFIG_STM32H7_UART5=y #ttyS4 +CONFIG_STM32H7_USART6=y #ttyS5 NC +CONFIG_STM32H7_UART7=y #ttyS6 +CONFIG_STM32H7_UART8=y #ttyS7 +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_UART4_BAUD=921600 +CONFIG_UART4_RXBUFSIZE=3000 +CONFIG_UART4_TXBUFSIZE=3000 +CONFIG_UART4_RXDMA=y +CONFIG_UART4_TXDMA=y +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=180 +CONFIG_USART6_SERIAL_CONSOLE=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=3000 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_WATCHDOG=y +CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/hkust/nxt-dual/nuttx-config/nsh/old_defconfig.txt b/boards/hkust/nxt-dual/nuttx-config/nsh/old_defconfig.txt new file mode 100644 index 000000000000..cbe89638ad1b --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/nsh/old_defconfig.txt @@ -0,0 +1,271 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_TIME is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="NxtPX4" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="Gumstix" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_IOB=y +CONFIG_MM_REGIONS=4 +# CONFIG_MTD=y +# CONFIG_MTD_BYTE_WRITE=y +# CONFIG_MTD_PARTITION=y +# CONFIG_MTD_PROGMEM=y +# CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +# CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +# CONFIG_STM32H7_I2C3=y +# CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SDMMC1_DMA=y +CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024 +# CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +# CONFIG_STM32H7_SPI5=y +# CONFIG_STM32H7_SPI6=y +# CONFIG_STM32H7_SPI6_DMA=y +# CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI_DMA=y +# CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y + + +CONFIG_STM32H7_USART1=y #ttyS0 +CONFIG_STM32H7_USART2=y #ttyS1 +CONFIG_STM32H7_USART3=y #ttyS2 +CONFIG_STM32H7_UART4=y #ttyS3 +CONFIG_STM32H7_UART5=y #ttyS4 +CONFIG_STM32H7_UART7=y #ttyS5 + +# CONFIG_STM32H7_USART_BREAKS=y +# CONFIG_STM32H7_USART_INVERT=y +# CONFIG_STM32H7_USART_SINGLEWIRE=y +# CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 + + +# CONFIG_UART5_IFLOWCONTROL=y +# CONFIG_UART5_OFLOWCONTROL=y + +# CONFIG_UART8_BAUD=57600 +# CONFIG_UART8_RXBUFSIZE=600 +# CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 + +CONFIG_USART2_BAUD=57600 +# CONFIG_USART2_IFLOWCONTROL=y +# CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 + +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 + +CONFIG_UART4_BAUD=921600 +CONFIG_UART4_RXBUFSIZE=3000 +CONFIG_UART4_TXBUFSIZE=1200 +# CONFIG_UART4_RXDMA=y +# CONFIG_UART4_TXDMA=y + +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=1500 + + +# CONFIG_USART6_BAUD=57600 +# CONFIG_USART6_RXBUFSIZE=600 +# CONFIG_USART6_TXBUFSIZE=1500 + +CONFIG_UART7_BAUD=57600 +# CONFIG_UART7_IFLOWCONTROL=y +# CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=3000 + + +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y +CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/hkust/nxt-dual/nuttx-config/scripts/bootloader_script.ld b/boards/hkust/nxt-dual/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..511ef2624248 --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/hkust/nxt-dual/nuttx-config/scripts/script.ld b/boards/hkust/nxt-dual/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..1dc1a0ef97eb --- /dev/null +++ b/boards/hkust/nxt-dual/nuttx-config/scripts/script.ld @@ -0,0 +1,228 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The board uses an STM32H743II and has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/hkust/nxt-dual/src/CMakeLists.txt b/boards/hkust/nxt-dual/src/CMakeLists.txt new file mode 100644 index 000000000000..798c5243474e --- /dev/null +++ b/boards/hkust/nxt-dual/src/CMakeLists.txt @@ -0,0 +1,69 @@ +############################################################################ +# +# Copyright (c) 2021 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + mtd.cpp + ) + # add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/hkust/nxt-dual/src/board_config.h b/boards/hkust/nxt-dual/src/board_config.h new file mode 100644 index 000000000000..2b8aba1296db --- /dev/null +++ b/boards/hkust/nxt-dual/src/board_config.h @@ -0,0 +1,230 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#define FLASH_BASED_PARAMS + + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +# define GPIO_nLED_RED /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN15) +# define GPIO_nLED_GREEN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11) +# define GPIO_nLED_BLUE /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +/* I2C busses */ +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +// #define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_SPL_ADDR_SET /* PB5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN5) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +#define ADC12_CH(n) (n) + +#define PX4_ADC_GPIO \ + /* PC4 */ GPIO_ADC12_INP4, \ + /* PC5 */ GPIO_ADC12_INP8 + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL ADC12_CH(4) +#define ADC_BATTERY_CURRENT_CHANNEL ADC12_CH(5) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL)) + +#define BOARD_ADC_OPEN_CIRCUIT_V (1.6f) + + + +/* Define Battery 1 Voltage Divider and A per V + */ + +// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +// #define BOARD_BATTERY1_A_PER_V (40.0f) +// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + + +/* Spare GPIO */ +#define GPIO_PA4 /* PA4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN4) +#define GPIO_PC0 /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0) +#define GPIO_PC1 /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1) +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 4 /* Timer 4 */ +#define TONE_ALARM_CHANNEL 3 /* PD14 GPIO_TIM4_CH3 NC */ +/*NC can be modified with Spare GPIO then connected with hardware */ +#define GPIO_BUZZER_1 /* PA4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN4) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_BUZZER_1 + +/* USB OTG FS + * + * PD0 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PD0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN0) +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */ + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS4" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +// #define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) +// #define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true); + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_LIB_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_SPL_ADDR_SET, \ + GPIO_PC0, \ + GPIO_PC1, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 5 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/hkust/nxt-dual/src/bootloader_main.c b/boards/hkust/nxt-dual/src/bootloader_main.c new file mode 100644 index 000000000000..5670308a29d8 --- /dev/null +++ b/boards/hkust/nxt-dual/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/hkust/nxt-dual/src/flash_w25q128.c b/boards/hkust/nxt-dual/src/flash_w25q128.c new file mode 100644 index 000000000000..3a3e2cee1fcc --- /dev/null +++ b/boards/hkust/nxt-dual/src/flash_w25q128.c @@ -0,0 +1,505 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file flash_w25q128.c + * + * Board-specific external flash W25Q128 functions. + */ + + +#include "board_config.h" +#include "qspi.h" +#include "arm_internal.h" +#include +#include + + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#define N25Q128_SECTOR_SIZE (4*1024) +#define N25Q128_SECTOR_SHIFT (12) +#define N25Q128_SECTOR_COUNT (4096) +#define N25Q128_PAGE_SIZE (256) +#define N25Q128_PAGE_SHIFT (8) + +#define W25Q_DUMMY_CYCLES_FAST_READ_QUAD 6 +#define W25Q_INSTR_FAST_READ_QUAD 0xEB +#define W25Q_ADDRESS_SIZE 3 // 3 bytes -> 24 bits + +#define N25QXXX_READ_STATUS 0x05 /* Read status register: * + * 0x05 | SR */ +#define N25QXXX_PAGE_PROGRAM 0x02 /* Page Program: * + * 0x02 | ADDR(MS) | ADDR(MID) | * + * ADDR(LS) | data */ +#define N25QXXX_WRITE_ENABLE 0x06 /* Write enable: * + * 0x06 */ +#define N25QXXX_WRITE_DISABLE 0x04 /* Write disable command code: * + * 0x04 */ +#define N25QXXX_SUBSECTOR_ERASE 0x20 /* Sub-sector Erase (4 kB) * + * 0x20 | ADDR(MS) | ADDR(MID) | * + * ADDR(LS) */ + + +/* N25QXXX Registers ****************************************************************/ +/* Status register bit definitions */ + +#define STATUS_BUSY_MASK (1 << 0) /* Bit 0: Device ready/busy status */ +# define STATUS_READY (0 << 0) /* 0 = Not Busy */ +# define STATUS_BUSY (1 << 0) /* 1 = Busy */ +#define STATUS_WEL_MASK (1 << 1) /* Bit 1: Write enable latch status */ +# define STATUS_WEL_DISABLED (0 << 1) /* 0 = Not Write Enabled */ +# define STATUS_WEL_ENABLED (1 << 1) /* 1 = Write Enabled */ +#define STATUS_BP_SHIFT (2) /* Bits 2-4: Block protect bits */ +#define STATUS_BP_MASK (7 << STATUS_BP_SHIFT) +# define STATUS_BP_NONE (0 << STATUS_BP_SHIFT) +# define STATUS_BP_ALL (7 << STATUS_BP_SHIFT) +#define STATUS_TB_MASK (1 << 5) /* Bit 5: Top / Bottom Protect */ +# define STATUS_TB_TOP (0 << 5) /* 0 = BP2-BP0 protect Top down */ +# define STATUS_TB_BOTTOM (1 << 5) /* 1 = BP2-BP0 protect Bottom up */ +#define STATUS_BP3_MASK (1 << 5) /* Bit 6: BP3 */ +#define STATUS_SRP0_MASK (1 << 7) /* Bit 7: Status register protect 0 */ +# define STATUS_SRP0_UNLOCKED (0 << 7) /* 0 = WP# no effect / PS Lock Down */ +# define STATUS_SRP0_LOCKED (1 << 7) /* 1 = WP# protect / OTP Lock Down */ + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/* This type represents the state of the MTD device. The struct mtd_dev_s must + * appear at the beginning of the definition so that you can freely cast between + * pointers to struct mtd_dev_s and struct n25qxxx_dev_s. + */ + +struct n25qxxx_dev_s { + //struct mtd_dev_s mtd; /* MTD interface */ + FAR struct qspi_dev_s *qspi; /* Saved QuadSPI interface instance */ + uint16_t nsectors; /* Number of erase sectors */ + uint8_t sectorshift; /* Log2 of sector size */ + uint8_t pageshift; /* Log2 of page size */ + FAR uint8_t *cmdbuf; /* Allocated command buffer */ + FAR uint8_t *readbuf; /* Allocated status read buffer */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct qspi_dev_s *ptr_qspi_dev; +struct qspi_meminfo_s qspi_meminfo = { + .flags = QSPIMEM_QUADIO, + .addrlen = W25Q_ADDRESS_SIZE, + .dummies = W25Q_DUMMY_CYCLES_FAST_READ_QUAD, + .cmd = W25Q_INSTR_FAST_READ_QUAD +}; + +struct n25qxxx_dev_s n25qxxx_dev; +uint8_t cmdbuf[4] = {0u}; +uint8_t readbuf[1] = {0u}; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ +__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd); +__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv); +__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd, + FAR void *buffer, size_t buflen); +__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv); +__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv); + +__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer, + off_t address, size_t buflen); + +__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo); + +__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector); + +__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status, + off_t address); + +__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd, + off_t addr, uint8_t addrlen); + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +void flash_w25q128_init(void) +{ + int qspi_interface_number = 0; + ptr_qspi_dev = stm32h7_qspi_initialize(qspi_interface_number); + n25qxxx_dev.qspi = ptr_qspi_dev; + n25qxxx_dev.cmdbuf = cmdbuf; + n25qxxx_dev.readbuf = readbuf; + n25qxxx_dev.sectorshift = N25Q128_SECTOR_SHIFT; + n25qxxx_dev.pageshift = N25Q128_PAGE_SHIFT; + n25qxxx_dev.nsectors = N25Q128_SECTOR_COUNT; +} + +__ramfunc__ ssize_t up_progmem_ext_getpage(size_t addr) +{ + ssize_t page_address = (addr - STM32_FMC_BANK4) / N25Q128_SECTOR_COUNT; + + return page_address; +} + +__ramfunc__ ssize_t up_progmem_ext_eraseblock(size_t block) +{ + ssize_t size = N25Q128_SECTOR_COUNT; + + irqstate_t irqstate = px4_enter_critical_section(); + stm32h7_qspi_exit_memorymapped(ptr_qspi_dev); + + n25qxxx_erase_sector(&n25qxxx_dev, block); + + stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0); + px4_leave_critical_section(irqstate); + return size; +} + +__ramfunc__ ssize_t up_progmem_ext_write(size_t addr, FAR const void *buf, size_t count) +{ + ssize_t ret_val = 0; + + irqstate_t irqstate = px4_enter_critical_section(); + stm32h7_qspi_exit_memorymapped(ptr_qspi_dev); + + addr &= 0xFFFFFF; + n25qxxx_write_page(&n25qxxx_dev, buf, (off_t)addr, count); + + stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0); + px4_leave_critical_section(irqstate); + + return ret_val; +} + +/************************************************************************************ + * Name: n25qxxx_command + ************************************************************************************/ + +__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd) +{ + struct qspi_cmdinfo_s cmdinfo; + + finfo("CMD: %02" PRIx8 "\n", cmd); + + cmdinfo.flags = 0; + cmdinfo.addrlen = 0; + cmdinfo.cmd = cmd; + cmdinfo.buflen = 0; + cmdinfo.addr = 0; + cmdinfo.buffer = NULL; + + int rv; + rv = qspi_command(qspi, &cmdinfo); + return rv; +} + +/************************************************************************************ + * Name: n25qxxx_read_status + ************************************************************************************/ + +__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv) +{ + DEBUGVERIFY(n25qxxx_command_read(priv->qspi, N25QXXX_READ_STATUS, + (FAR void *)&priv->readbuf[0], 1)); + return priv->readbuf[0]; +} + +/************************************************************************************ + * Name: n25qxxx_command_read + ************************************************************************************/ + +__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd, + FAR void *buffer, size_t buflen) +{ + struct qspi_cmdinfo_s cmdinfo; + + finfo("CMD: %02" PRIx8 " buflen: %zu\n", cmd, buflen); + + cmdinfo.flags = QSPICMD_READDATA; + cmdinfo.addrlen = 0; + cmdinfo.cmd = cmd; + cmdinfo.buflen = buflen; + cmdinfo.addr = 0; + cmdinfo.buffer = buffer; + + int rv; + rv = qspi_command(qspi, &cmdinfo); + return rv; +} + + +/************************************************************************************ + * Name: n25qxxx_write_enable + ************************************************************************************/ + +__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv) +{ + uint8_t status; + + do { + n25qxxx_command(priv->qspi, N25QXXX_WRITE_ENABLE); + status = n25qxxx_read_status(priv); + } while ((status & STATUS_WEL_MASK) != STATUS_WEL_ENABLED); +} + +/************************************************************************************ + * Name: n25qxxx_write_disable + ************************************************************************************/ + +__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv) +{ + uint8_t status; + + do { + n25qxxx_command(priv->qspi, N25QXXX_WRITE_DISABLE); + status = n25qxxx_read_status(priv); + } while ((status & STATUS_WEL_MASK) != STATUS_WEL_DISABLED); +} + +/************************************************************************************ + * Name: n25qxxx_write_page + ************************************************************************************/ + +__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer, + off_t address, size_t buflen) +{ + struct qspi_meminfo_s meminfo; + unsigned int pagesize; + unsigned int npages; + unsigned int firstpagesize = 0; + int ret = OK; + unsigned int i; + + finfo("address: %08jx buflen: %zu\n", (intmax_t)address, buflen); + + pagesize = (1 << priv->pageshift); + + /* Set up non-varying parts of transfer description */ + + meminfo.flags = QSPIMEM_WRITE; + meminfo.cmd = N25QXXX_PAGE_PROGRAM; + meminfo.addrlen = 3; + meminfo.dummies = 0; + meminfo.buffer = (void *)buffer; + + if (0 != (address % pagesize)) { + firstpagesize = pagesize - (address % pagesize); + } + + if (buflen <= firstpagesize) { + meminfo.addr = address; + meminfo.buflen = buflen; + ret = n25qxxx_write_one_page(priv, &meminfo); + + } else { + + if (firstpagesize > 0) { + meminfo.addr = address; + meminfo.buflen = firstpagesize; + ret = n25qxxx_write_one_page(priv, &meminfo); + + buffer += firstpagesize; + address += firstpagesize; + buflen -= firstpagesize; + } + + npages = (buflen >> priv->pageshift); + + meminfo.buflen = pagesize; + + /* Then write each page */ + + for (i = 0; (i < npages) && (ret == OK); i++) { + /* Set up varying parts of the transfer description */ + + meminfo.addr = address; + meminfo.buffer = (void *)buffer; + + ret = n25qxxx_write_one_page(priv, &meminfo); + + /* Update for the next time through the loop */ + + buffer += pagesize; + address += pagesize; + buflen -= pagesize; + } + + if ((ret == OK) && (buflen > 0)) { + meminfo.addr = address; + meminfo.buffer = (void *)buffer; + meminfo.buflen = buflen; + + ret = n25qxxx_write_one_page(priv, &meminfo); + } + } + + return ret; +} + +__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo) +{ + int ret; + + n25qxxx_write_enable(priv); + ret = qspi_memory(priv->qspi, meminfo); + n25qxxx_write_disable(priv); + + if (ret < 0) { + ferr("ERROR: QSPI_MEMORY failed writing address=%06" PRIx32 "\n", + meminfo->addr); + } + + return ret; +} + +/************************************************************************************ + * Name: n25qxxx_erase_sector + ************************************************************************************/ + +__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector) +{ + off_t address; + uint8_t status; + + finfo("sector: %08jx\n", (intmax_t) sector); + + /* Check that the flash is ready and unprotected */ + + status = n25qxxx_read_status(priv); + + if ((status & STATUS_BUSY_MASK) != STATUS_READY) { + ferr("ERROR: Flash busy: %02" PRIx8, status); + return -EBUSY; + } + + /* Get the address associated with the sector */ + + address = (off_t)sector << priv->sectorshift; + + if ((status & (STATUS_BP3_MASK | STATUS_BP_MASK)) != 0 && + n25qxxx_isprotected(priv, status, address)) { + ferr("ERROR: Flash protected: %02" PRIx8, status); + return -EACCES; + } + + /* Send the sector erase command */ + + n25qxxx_write_enable(priv); + n25qxxx_command_address(priv->qspi, N25QXXX_SUBSECTOR_ERASE, address, 3); + + /* Wait for erasure to finish */ + + while ((n25qxxx_read_status(priv) & STATUS_BUSY_MASK) != 0); + + return OK; +} + +/************************************************************************************ + * Name: n25qxxx_isprotected + ************************************************************************************/ + +__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status, + off_t address) +{ + off_t protstart; + off_t protend; + off_t protsize; + unsigned int bp; + + /* The BP field is spread across non-contiguous bits */ + + bp = (status & STATUS_BP_MASK) >> STATUS_BP_SHIFT; + + if (status & STATUS_BP3_MASK) { + bp |= 8; + } + + /* the BP field is essentially the power-of-two of the number of 64k sectors, + * saturated to the device size. + */ + + if (0 == bp) { + return false; + } + + protsize = 0x00010000; + protsize <<= (protsize << (bp - 1)); + protend = (1 << priv->sectorshift) * priv->nsectors; + + if (protsize > protend) { + protsize = protend; + } + + /* The final protection range then depends on if the protection region is + * configured top-down or bottom up (assuming CMP=0). + */ + + if ((status & STATUS_TB_MASK) != 0) { + protstart = 0x00000000; + protend = protstart + protsize; + + } else { + protstart = protend - protsize; + /* protend already computed above */ + } + + return (address >= protstart && address < protend); +} + +/************************************************************************************ + * Name: n25qxxx_command_address + ************************************************************************************/ + +__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd, + off_t addr, uint8_t addrlen) +{ + struct qspi_cmdinfo_s cmdinfo; + + finfo("CMD: %02" PRIx8 " Address: %04jx addrlen=%" PRIx8 "\n", cmd, (intmax_t) addr, addrlen); + + cmdinfo.flags = QSPICMD_ADDRESS; + cmdinfo.addrlen = addrlen; + cmdinfo.cmd = cmd; + cmdinfo.buflen = 0; + cmdinfo.addr = addr; + cmdinfo.buffer = NULL; + + int rv; + rv = qspi_command(qspi, &cmdinfo); + return rv; +} diff --git a/boards/hkust/nxt-dual/src/hw_config.h b/boards/hkust/nxt-dual/src/hw_config.h new file mode 100644 index 000000000000..7c2676f4ff4a --- /dev/null +++ b/boards/hkust/nxt-dual/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 6 +#define INTERFACE_USART_CONFIG "/dev/ttyS5,57600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1013 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_RED // RED +#define BOARD_LED_ON 1 +#define BOARD_LED_OFF 0 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/hkust/nxt-dual/src/i2c.cpp b/boards/hkust/nxt-dual/src/i2c.cpp new file mode 100644 index 000000000000..72ba2d6c0b57 --- /dev/null +++ b/boards/hkust/nxt-dual/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(4), +}; diff --git a/boards/hkust/nxt-dual/src/init.c b/boards/hkust/nxt-dual/src/init.c new file mode 100644 index 000000000000..657c0080c019 --- /dev/null +++ b/boards/hkust/nxt-dual/src/init.c @@ -0,0 +1,205 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + UNUSED(ms); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* configure USB interfaces */ + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + return ret; + } + +#endif + +// TODO:internal flash store parameters +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {15, 128 * 1024, 0x081E0000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + led_on(LED_RED); + } + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/hkust/nxt-dual/src/led.c b/boards/hkust/nxt-dual/src/led.c new file mode 100644 index 000000000000..0420c1da2e79 --- /dev/null +++ b/boards/hkust/nxt-dual/src/led.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/hkust/nxt-dual/src/manifest.c b/boards/hkust/nxt-dual/src/manifest.c new file mode 100644 index 000000000000..e13f3d08607f --- /dev/null +++ b/boards/hkust/nxt-dual/src/manifest.c @@ -0,0 +1,131 @@ +/**************************************************************************** + * + * Copyright (c) 2018-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file manifest.c + * + * This module supplies the interface to the manifest of hardware that is + * optional and dependent on the HW REV and HW VER IDs + * + * The manifest allows the system to know whether a hardware option + * say for example the PX4IO is an no-pop option vs it is broken. + * + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#include "systemlib/px4_macros.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +typedef struct { + uint32_t hw_ver_rev; /* the version and revision */ + const px4_hw_mft_item_t *mft; /* The first entry */ + uint32_t entries; /* the lenght of the list */ +} px4_hw_mft_list_entry_t; + +typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry; +#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1 + +static const px4_hw_mft_item_t device_unsupported = {0, 0, 0}; + +// List of components on a specific board configuration +// The index of those components is given by the enum (px4_hw_mft_item_id_t) +// declared in board_common.h +static const px4_hw_mft_item_t hw_mft_list_v0600[] = { + { + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, +}; + +static px4_hw_mft_list_entry_t mft_lists[] = { + {V6U00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, +}; + +/************************************************************************************ + * Name: board_query_manifest + * + * Description: + * Optional returns manifest item. + * + * Input Parameters: + * manifest_id - the ID for the manifest item to retrieve + * + * Returned Value: + * 0 - item is not in manifest => assume legacy operations + * pointer to a manifest item + * + ************************************************************************************/ + +__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id) +{ + static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized; + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + uint32_t ver_rev = board_get_hw_version() << 16; + ver_rev |= board_get_hw_revision(); + + for (unsigned i = 0; i < arraySize(mft_lists); i++) { + if (mft_lists[i].hw_ver_rev == ver_rev) { + boards_manifest = &mft_lists[i]; + break; + } + } + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev); + } + } + + px4_hw_mft_item rv = &device_unsupported; + + if (boards_manifest != px4_hw_mft_list_uninitialized && + id < boards_manifest->entries) { + rv = &boards_manifest->mft[id]; + } + + return rv; +} diff --git a/boards/hkust/nxt-dual/src/mtd.cpp b/boards/hkust/nxt-dual/src/mtd.cpp new file mode 100644 index 000000000000..e374a9be7e68 --- /dev/null +++ b/boards/hkust/nxt-dual/src/mtd.cpp @@ -0,0 +1,77 @@ +/**************************************************************************** + * + * Copyright (C) 2020 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. + * + ****************************************************************************/ +//TODO:Prepare for NxtDual + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = 32 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 1, + .entries = { + &fmum_fram + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mtd_mft + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/hkust/nxt-dual/src/sdio.c b/boards/hkust/nxt-dual/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/hkust/nxt-dual/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/hkust/nxt-dual/src/spi.cpp b/boards/hkust/nxt-dual/src/spi.cpp new file mode 100644 index 000000000000..058c48982636 --- /dev/null +++ b/boards/hkust/nxt-dual/src/spi.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin3}, SPI::DRDY{GPIO::PortA, GPIO::Pin1}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin2}, SPI::DRDY{GPIO::PortA, GPIO::Pin0}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin4}) + }), + initSPIBus(SPI::Bus::SPI3, { + // not in use, future development + }), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortE, GPIO::Pin3}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortC, GPIO::Pin13}, SPI::DRDY{GPIO::PortE, GPIO::Pin4}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/hkust/nxt-dual/src/timer_config.cpp b/boards/hkust/nxt-dual/src/timer_config.cpp new file mode 100644 index 000000000000..27ad0f247617 --- /dev/null +++ b/boards/hkust/nxt-dual/src/timer_config.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer2, DMA{DMA::Index1}), + initIOTimer(Timer::Timer3, DMA{DMA::Index1}), + // initIOTimer(Timer::Timer2), + // initIOTimer(Timer::Timer3), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/hkust/nxt-dual/src/usb.c b/boards/hkust/nxt-dual/src/usb.c new file mode 100644 index 000000000000..9591784866a6 --- /dev/null +++ b/boards/hkust/nxt-dual/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/boards/hkust/nxt-v1/bootloader.px4board b/boards/hkust/nxt-v1/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/hkust/nxt-v1/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board new file mode 100644 index 000000000000..bc04f1ce9491 --- /dev/null +++ b/boards/hkust/nxt-v1/default.px4board @@ -0,0 +1,105 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PWM_OUT_SIM=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_RPM=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +#CONFIG_DRIVERS_UAVCAN=y +#CONFIG_BOARD_UAVCAN_INTERFACES=1 +#CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +# CONFIG_MODULES_FW_POS_CONTROL_L1=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MIXER=y +CONFIG_SYSTEMCMDS_MOTOR_TEST=y +#CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_PWM=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 +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +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/hkust/nxt-v1/extras/hkust_nxt-v1_bootloader.bin b/boards/hkust/nxt-v1/extras/hkust_nxt-v1_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..1456ce1ab847b66f9330a5df2b0e1dfecfef3e6d GIT binary patch literal 43248 zcmeFZd3;pW{Xcx}GBY=skeMvNWC3Pj$p#JyNC1~%CfqE8hQ(GETL+`|hA2cpjY^XV zK}FCO32lLBYr)oqDw)9aA=sEGXl>O#Gc0}s(Go!!NKo&Pz}!rh`Mu8!*jDZH{GR`w zKYsIiow?`UvwzO#e9mV(C*MFOsyHIN#{Qr1e_-(c9~>apevwP>ZvV;8RquV%r*e;% zc^&KfrZ2AkIdPT91|{~JzNCinvR;?aKJ_d8mTk>bFAkMgif5E8ACc|h<_kmRvDD^E z`YkpqEuYZt?h`h<`{Fh?^d)VsE*5w)QSgo}Bc`#=M!V_w80Xlsv87w>6OI#EH9+K9 zVIto-(B4=6%l5uCzf3Mmkt{O9rMQ+vpG#cVQ;6&uBJyRFSUu!W_>9iLVujZtrtJ(A zjYb;`nTR1xyz~kYc*M7TL%Q#DZfs7M%>8b&z2BXm?z*Fl+0N`HIi#=2%`}l*Ti>tT z3(FRjqRsy53X81c9I}A6wRrEYaL6`Jdp+LouF$$@->Q+vhCGem#v5Jpoc6M;xx4R~ zSC(EeuWWY(dxhku-)k#7eNVb%mtS3+?n;-oGealSB|ZN0F~(hF=;UlX9kLpA&2l1N zzs(-a#}A#HQ5r98!?OTSyUeojuKZ|>K@2q^+GUQVWm&n9HROc- z*`+xpbPTp7j()O4>zYFI_1o6k`^nmL7mIke9S~W}#^O=vuqbbq@m+SKzwtDGGV&+W z77+*Z*yifubm@8S)+;ObGrO5NO9P~cU8>yhJTc&ziI9bmY_pNMET_4FWth!EJ4q;E zml_awgnp#w@nk76lEr$&??70HuoOY?8l8-Z7%9XUjAmR}5`rEfO^UaTE49mde9gpH z+8;MYZ@8bxk1LT-LS$?dk_0nGF=sSJo9Py~H8^4r%&m+Hz^RYqzu; zd3faE^G-{rT|ygar{fXo$s*dfpM5jZLr8?lL%b8=Q-p4W3kcQ4kxSNtSR0#&#clqk zPv5Zi&l`d54So8}6kkU>$CPDANt?NT_ro!THc73O|h2i zueGc$rE~6Hr*#n%?@V(aZ=owN5_8WJSo>@6uD+A<~Jb< zyVM4U%ySKWsherdd#-%4)*{;+?<#+qPTQ#lmeBfVpnhGJ-aGxXmx6kJLSFo*T+rp< zuB>!uF+W_G?@x6RV`lfQc|vFA0&8JrQ9|@Pk@c?2fxGkgPQ!wQ(XV}hI=qcuP#t}{ z6!=vhd#YTHSoLj53${hSoek)ne3sV5`OEv=80WEoDvL#&6et08H0HMS1$0^G{2C{1 z9oW*&e@?mugaiaV!bHGA-%Yy5IceSFO7-3hi33Gjp2-CZEh`I}$UM->t@c6xSm)SM z!-6zdx$K^vw$kLnFx-2%jdmVPr)<)z?0_>AYwZ?Q8k=KNYSy###iM%Ro0o|)} zIOJ}J#U)!Pw%qe)Jz&eDZ8z-``T;sDWYXss=pSJId>j#ef{@~MTbS1?MP7`A7DbG$ zy1dUWlIiScX`n6oHmvI&y7HAkikEzw@8%!K7w<@S4Fs^ac;lQI5)E{pBHvq!ZP2}%R*t62b3vK#62hKf7Mqn5I(3KOs3F-fh==$jtfgZ?SRze;Hp^&de@4MzlG>sIYU(dr}6G0Dk)r1TQ21e2~Ff0ZteNFOi8t|8E`yRgr~5#E7R! z5E*Cesv_DmOR$*pGOv0vMVn5%h>3MfeDz8KDE=PY9(cL|F195w2uV zT0$m9Ldzp6r|s(F_Ipia2ao=qQj8*{C8RyBi3m6CiRDu{K}+u$xt6E<+dRug5n%!H z{2{B_s}d8$^iI%`r$9%(v$JNlMnb|$wWu^PMw0_8N!D(BTex=72={MW}y%L{am z{sCHcqlqbrgnT1+qQ5Foyj+i}ELlo!O@EfjPu~>9s&-lrrCBLXy*FKY*OQEV`&#Lq z|J@O_3>d8>H||qnN!b*STuWMGTnRDi+nBjcEh(Ew?iK$x0Y*L&4hF8*dkA$`d!K4n ziO(7n#g8xY`JDWf!izo+F}>fwJ)f|PeO|kZc|LyEXGkN@XNyEGP*meprzsA9pk#^a z=IS=1_@zYT#|A=yHL_OKADG}(zd*LfqdsN^v7}*d_&CC24kvguFR(k*FMNEF%t#UA zMb;DvbwpEAy!^GV#2g9rM(B)Bz1Ua$RNZD#B|a}s7bl3HDOoQO`L_f7_&Hr@SLW12 zK8?48uBSbV#o1yOR^X8^KVF4YB5y!S%IP~jH2&&6wT3t?_ZzZS4DDzzUk2~ zKMG$8Xq!sK_%h`EHIY*ke*D?4gx&LyO5{Cw>x$M`H$X8F)aPm7MKTelUJRAe(=#R8K4eSF1 z$((LxYKnBIotebU&9yC3EZdmghQ!t&(OLcfP>3zk@}=uT)JXH6-FmgnIRjOqUMdsm)q;DbdhksHweO-klA277)a^!~_LP#I4C+W>DiKN<=B zW26K;6-M_$6u&&SDc3^LXys?h^5|YrWTC;_)`97(IKXE{OwIs|Q8Xf}&M>0nh$lRI_q;gcrAg-X9oLjpwnNS^4vk zEU~(c4^AWpU21tgY9y05xqF~5x~k=X?;;DCkufh{TU}h}-6W~R8J>#AnOy!9Gq++b zvFvjdf)Wt9iI$Y}2WU-dc@o|@`BS=fLPAR|@n@!5?$O z{zz!cVM;qG%`EitqTxV?)a=2^qLR^fRno1 zm#_}#d>EWo?>OnnX2`X}4?I9=3K{;w!P~eU6R`^=qqGXL4EHLLs})BkBkFz3HttnU zzFT2-(cGX%qSeEUqwyw;i^$Uy4!Vvn0kOUz#(3shJB8i`$~8ZUF&H5YVhrwUV<5&C zD%X3=k8QE5{anz%SX%|a<&_BEZ4@U;!2m1oi+t5WWk;h}*rxY#Pc+2#nD1b9Vks*> z5V?-mY;J-d?frnntSapZFu7m(+b-yBtn3Bs3**T|D?%Z5WoDu&ipxYXwlXt}c_BaK zn;EoaI_o63K$V5wEsZQ}<%4%bY|uRVGr#Ag+0|C z?5#}k7#`bf7yQRss79f{lLKAFD(EV@0~wMW_%ZhCLC=p$SozF|vGoo-yGBUXF<-9a za8*eSuIP+@uZKKl@v9bA{=*2JwYLI4JPsRp8&*Cr676Z$Nx$C6%2$U-)?Odv-E|)W zHb(}tYhD8VI6kPx9+c;^NhJq}{Lev><@BvX4_c&+u0E+r&7a7wVJus1DUJqLu5<)F z<5vD~n|yEqLt9-sV#faRFE~X)FAk!_<{yH#I#=+27rq@McZWACn`wy~1Rrx6D@tt@ zu|L&=lBxeEV5w8(a(*7XGy(5xsng_s4|5V^={Srfo@oRY3I_+wR<;rSZ{U81 z`F(orpPxa`p2qy1-OByuOiMEKaPdC6AG5N5m}%l%Y*WQ1O>{q9D5|#8I#s(Vj4$~< z->TX^ub({hdBZ%kb#(ZIQq=5~oINVlefQED)=BDM0;Ae(ePU-ZZIR!tLd$eL(>5th z;?;hqP6WZT%IWk=hd?9rkQR(^R{)fA&p;ID?QfQM=DB}mtiODgb@ znV@=q4M*WNKvyVu(8H8Y30~I87&DN%Z6NmUmW)^{dBDdL?ZgP#r;S*IvSd)~dQcL! z_XxMNro%yG267Hlpv?_pr>ZWl!M<4NeNtKu?N~a^P3rAw(cG$_k=!NyB}!Yqj|VjM z3t-NHvHm_ zDCH}}`nv@j3#hr7m{|FSVPd?5T{E^f>%B)oW2go+R*IDkZ%wok`JuzaqVcjKvyCws z!1oppLE~*vn;4^7o;L)&%5JrZMSSiMF~%@Ca)}cGv-kxriCuA!HJCZ+ zHp;^pJnu@o?FP*8htYiv@~m+nK>0ShXHpvb!!y9u@pHLcXcOh1g?WnxYq4Szk#7sf zW~H!AVZero?jd2E)XF-`wfC=R#u$n04jPCGts+>5# z>VcfiOn!1pj+>b0ZDK*;>#p^!5V}(ZvT2qx`*xS{$VF0=<)r^puKmA{IDKd3lCVlF z@sOZPllO3zXqY)2cy(fMzdhu4VdiItd2uOCRk2gX-ah4FqiC2xa~v7`19I4qBkNiY zn~F@)-#%rXQPf9sw0xUm?6*1CDZ;#3N($xUI z7yZfA6__b8Q)HB%A!AC|yyCQ!L5OXZg$HQL*E>T*t z)orE{*uU%SCu1L-g_U-9cxxZkXu8d3l+De|_Pac^HlsLYJu7Pl?{lq__PP#8=UguY z76Sg#055(JWq&svKCgp7-n~KO*`!U{urG_FB;fJ zrU|7sul+M^aWi5|F}wX?wuu*Gx!R+=JB2f`%<^uO7`mf8`CUnVM`d1XYy~kpsg~RH z81pJCI|nC9m%;Chg09u(83~<_Osq`xST^jlbN-RgH{f&&+a^j^0+CC}pz#@!!;=IU zc*EVT`jQwQw*PPx|G&peXi6v^ycDK*01gUp_(BmpScebm+vpy89iPA#{`|l5g|6`R zmHfZU7ru6gv|q3Lztb4m-}J5$NL>ltvG`JGz{@0(6ZGS~;GK(vFp$XTemu*Yd|RHB7oDq(VFvWu z+NML#H-sS@rc{dMR}-q=P>A(8g|#ui;^g2618J?)u0ftv;qw7Cp7&!fKMNV41mp8z z&+0=MzZd#>1RmTa=QVyMV$PGkp zaUZy1!?PJr_YF4rO?O8hfu8662m>A54{^wBwoQJ~o!VbrezcFXj`dkI<+3i$+5T!! z;2dJPJTakMHYPNYyA*YIT$mdmVXkjlPh6s-Cy`sAsIBEaC2^eP6NPkh*<3gdXPJ?75&1_7)dmLqX9LvEb~zBYK=4}ri~UIrT4RwqR}-0y>RK2Pb^$Lr z18HIqHmI@=i%`nUr53kAzZ&}UsQpN;8KjV4Pf=PhGhl-6YY={PB0>8>(*&TZ}DnUjpH89BEV7UCu60RN*G z6ALOTsJ=-vy`hR1F>cip9!J$ad*Z1hRXHL7_Xv4o;A|Bq<`kW+xTk7y#yu4V>>I=~ z7~rTr)|e(>d1DBSrahgzrsc4Ix_b1G16SuW7MZo}|JogId9)%~RrG;KH=^cp|=imS2{qNns zvef`gwO#(&^3vt6jTIGu4x!MDg#OlUt2$xM7GDaU;JT{}Mcwyb*$z^?yU^W z;YRy7fBFK8l+sG~T%mYx@C14HVp_@xbDC&$jfDII7HCUPz$ThpW|594n~ZMra`3e7 zwX_X=+r0ZvnBQ4lfB)}MuKWIxQ0u_C)v^5QGTJW9Pg_2>`ipOM_`jM=<*iZBG0K)d ztd7}lD^?rDnDqGlbxAB)V#WQKkCB*uO7GpYn(6Oc_mZ+u&&Uj8hBrp%+7wuWH?F2W zF$|aHc-}>2njhvLBB6hNs}qvFN2;Q^zNbgqwHh8MkQ7;&Q33Uf0gmjmlEjJjv8=Ta@U5Y`th+^xHC5J^l93c+XGQ(C_Yt>RmaGrqy4xq`N4$ zBe%WNXJ<{ajVUG?XzO9^9WC+Dk?+MDl~y`pqyHX{)vPSE&h|KDBl86)@$yKF=eG23d&mTc_Xmzt zHLdQf?C7)UtBYxT*FFDlwaxQ5dRXR}7Fu8a_4;HtLr3wi`Z`b_)eHWllJXO~?3b!k zKF^iQdVo zNC2DATBD>FkMy}yHYrOH@6v5jmO-K(r*z+!h27w@kxv51rSFaIUw?x1c(iJV;v&PL z4)h{cHttlrDVkJDI)}5r9>m8AU_?E6#)34SH zH5>i9BtmuSDRQFj8(*R&<(^C6y9?1zVp55FSEsosj*NHi2E77Q&ErajLpdYet0SRh zgT^(H(2oaQYXnauw0LmOY6|Bi@bdZjk~j~v2TPW?vcx^BlblJC)|TR;=|9qA6~cRs zu0%)AyoyFwB;*{~vzi#G9~6Nf)F^nkFqW5<2gh-*7LzRQv}J<>Ftn_v zT=p87CszZqm#>|1AVs{FNiF|!*))Fii8s0A+e_N#%kKN8*$Nzvo_Yr(mopCPZ`My7 z=N36?-*sE$a?r$ik8ribD3o$RJV^8ek^v+m2xzMV9+fL83n9o>SZ~aGGq?WO$${K9M2+VL`7TQQ0 zt-oN1*6(~Q{;|K+*n2p$qn7TrU25iJBy_Yr68c5^yjr&QL-70dzvxC|yf;IcnDcf{sU`d|!LCUi6)jv2kCg`QNd>JZ%`+@HdY-+uR8`G0X&~+x#A8 z(x1eHu&OW3{#)2ECif(&zi1g*PbpodrOILUxC#tKa@%zAVt~7{eH|=XGc{As`(sig zF$S>?J3Osa`lfmvc*Ic*rKPDB-B}xl`6nrcBC3UcXM@&pWPMDpqiMd;MM`KN#IVI-~TSQXuMeqH2Z3 z&&bGe&|Vlk251%;*$<7R9(+|bt?37Jr`(3q>co@OPoPT^e=_cNm2rktgtakIX7~aZ zrd^qFO`fLw8EL0*rEpO@HD&M{4Z7^dlnZm%s~61hyaP5;SwRn+F%ZEedsVf@@&}pT zWt>bLB&Wdl{^mQz&nP-Lc(q@wO>t1my`$%-gPCTyU1)do6s_xBG{2UwRmq&{UWS>v zcbUeYeA`s%E7cwC(X{{?XOZ0wE}yowUB7n`U3VEA7sR(KjAf&p>2>q$r*a!J@gISS z5@XGD^*qt#jK zfG4o?k^E<_Y<}G?9IvQdrdFMRPSzBoah|q{+BeeI^gWeArdB)>|Jk|C`|O%e$M_4P zT7-&d>54~8wFYMyb8KmE=JuAB-n}~E^yo6iqL;SXI6&%efpOwjfr4jp#Oa`4X+@FH z&my!Wk6u`6Ev-*%P?_)P)1*AHKL44%&7+InXxV3(w5GX$;vdq>Yga9s@wdV(;#IsmNUG8SD!#W}J>~%N#xLI1)US^lNpa8>a@`9n z=dCn|i&n<8LDkr!^?Z`ZK`%KxVio&f^ZI3^2b_hDz=qgP$TJZhe7hZ%6zXrCtQk5< zahc+Jq1RCh&7FGANv?JVaAw8QaeV&CA6`#v?P6xhQVVtnhrG?PWMOt0SG$a1dmSkT z$&EUq296-TQ`N8>?mDS+UV(>0vpoi>_=6(cWto4QjFe;g%wyS0Zd}N@=|D zKU*9Q>B5%U#4^^jg3*@jTDa%RytUN()m@R|GS_kv3%w^}-V$w(bG=W;PS*wk-9ISo z1q5QI5@wR zvM5&)ZI#Zo0Ia5ZGg?1|slApHkExjxk!EA6&zxvj05DA@(D4>`u=&QNa5yeplZ4)}DQ-c-Q+35OSp}BIxB(hOWDE7p+ zeWT!$g1%DSR*F=xfbv!;;H$XdZpi@d!6bIUziY%Ywfu~7)J-NsGZ0@cXU3gdZ+SRw zP<^FPga^z^bk^|P!`v7NB@U~CHJs|o3lD38M~S6~rcEjmf<|F^P3A1KyntO^4IXQ# z>M_kUi@boVdgwI#cBxgHm{Lp9ApBWEE`omJ~%pxySBli?!C1;l+5lO%Gi!6wJU4S)-LGLOqtiinRX~+w%L0U&ARZ@ zinc`;-Z;`4OweU@>Mrx~%av^TnVCdbb|Vpfho|S-bIB|s{OVeG5zn^}l8{crD+oIj zeMctFr>Nlh%lXI1ZXNMWIB=cEvux+hY_T9MAHFbUYL<>3HB9FmgSA zB=kINX)h~3wZ?qB)ba#1Gi|z$oi@rxrXBZ_Y`^~_a3CM`*%E&L=z<>zd8XB*L)sZdlY2X&Ly9y|mV<}oe`BtvtQFskJ3QiQe{+gkGtt-d^L$3vX z_UJ2*$^qjBJx23eAIW*aPg`fFjq#Hk>iWy~$J)5{YT16;%1)wHqkb#qvf7CKLl?D- zm`9!rkZE=Oh5H$lnYo`6@9E=HEbFh=du#vN{UoQZf6e|_-N~r?7JsbfInmxHf=6s1 z|6X&}h(B=uTg(ld-zMvcasA%|>Ym45$Ui z?Ojh{YUChEo392qbANz0Uk<3ua$wE3sgw)v4KSLzD^vFW^ZaFXUB6}j66k8{`X}tK zyW!TWnfog?P~9|}du#ug{TA?RbS*e~5>irJMyGj8itR7(hGTHPV&gi?#@aw1YGC)b zo;PhMN1elO%6JdIxfC90b^TZ0WH9c&H(x(*-mnO%U%yG)>wPoUUf|8^_}e`|vg-QJ zy=mTJzz78=2g;nYZgN*}x|6lex@$S!XdzQ= za$G&lv!Sf1h2}ZyCVBePkCic|$8JlJvcwpr8V(&BxF8ulthBf?-jgkED>kX(Pd-%o zL6mxBRC1o3@JW6UlH1z@XVrI|ta6T%RM62M3aWKK`c%~~r^K}N>+56M`k&+JzM;hb zUSIrZGPTI}Q)lL6^`LO$F7Xp(#zO>p{IdFAD>wcAFraReZS|ih)`yDCILTPX$PrSi2-YSg$(jqimpNCi&OZh8 z^Yfu5v;!`J(ZHkX7h#%XB{;CHc(!WTldOf7o1@X5q$$_?ORbbY9u}f$4+`oaqkhLf zHW0(vbACDw(o9!qB;*c>4M$`S5?!A;oU#H(jq!T?% zE1=z!hL_7OEi^B}*P3-FAB1;&N&16MjQaTuX^aGqJSDE04GWj^?PR-w^32=>+gMO) zrtu~pX@VckP^M{e52wD{IUag~GRWUQbuxnq(+%SC4X){QC6)W(p~5cANdyEc!*@Cx zmB)<9fQTCJs_+u$a>!Jg1cxO%D{G{C*K80r}E9(-mvf*J`O>8}h z`j7A}ZT;@`a{xOb+S;I6bJAWydbOZ_bHY&Rp$CPKKbR(GD`}crLi<+er0L_a2WN-f z(Hsv7)bmms%+xmcH=IW+ESqxz{YeY^19bO#F&sEw_{_-Wxzdg4hN3s^ueMJUCxo9; z<{@oe_|=R^=-Ke>XEqnTq6qG;^JeFYYxr8%fAY-(!*L*zN!tBs%cWH*0-Lo+Q6EXz+S%Yit0^0YS?qNpSAQypqbHd zRC0J%=`TE{D6=TNco$DfwW_gCb}UJ8^?phDbv**zpQE|~%=h&(Vc=U43GGzq-ron_jn+{OUX1dH?#b7!-_*~GO3T>G24nnh z;%!FJB4vv!P%HAnS1%@4U(fll@r#zBQ053RQHV;=#AZ6z|M*-Q~LLo=;u7fg1(zx16t3ZMYXZN!5Bfit0AnPYOp0TgAJBT2f@P78=_q zN52T?Gq;tDgkBilvMs@` zxH1^g?iw+_yPkcRm=g!t)Xajr?@hap57wx_N7#xWTRc#GqJ_zCQ0}tbE7$RwoCc-D z_CU>=J_ad!m9ma=eqza-Vw-fjr9+vxvO}>ZWm?^e(d1SVOqxM1nJL(=+&oW{OG|7- z>?I{}(FH#-SC-P5Z;DX8RZRMv-F~0bZN6_oy6e7ji*(=ZH;WYKEG`cDl7{9=(71Ln zw}jwHN3~qJuDhJDo`F&_bE)QHC=?l7R+egv$^-=|*q@FlKQ7Cs?{WutUwR6R>Jr`1 z`(sY!gGxD|<921b_Fn0zNSF3r{&bzWzhm(c<gK6Oju!^m)jYuobx`mQE^( zr~X3u6QQADC5zK6*V)beSj7Ds>}EN_ra0=&oNK%@p@g2W9EDu)s~CaD(ZIv7vMRQr z&|Yf0#2HQPp9GSC5dUTznej5t1p(&_c#bLrHvn3VBQCaYbv=}J(~ua$$!_2#UGLop zl8=IjcEhUX)H#8Z?sT9sMGP}3fxl?2}lTWr^4&ZEVKC_+bH0W7M z=to7agq}cJtU&igPoK0eL|+c+$V7PXMg7753g3!|Fk}<&k<%%je zfmlRq zT@miW`P`e%N(GK3z^%KZK5PnXmx~WEK^?c}${w7_)Nx5g<^6ls8X(_)luk_JMDEI- zN8s@`$ieT|$dW5BJ+vpNC%aeb^YsOtE4RQeih4b3aL&YxGayvB5zc=pME8o(*hYrcw9$IHvR;K`bR(;K{eC`_`jKB%vfOa?ftmcCCz0i)Ox z^%G^G3DdUna`13V4V4y8nv~=*O7(Wt@g1(C@QCL; zpTZ89E;hlJxA}@&r#Z&O!B;YubYdQ@D};eSGIWbEoyu#VqkoL-q&`bO;AwtRv6;GB z%&zwo+dOK;t8Tjka^TB=HRbt=5WfQu{<~qJ^u8wL#D`0dU1ZfMMa?e3^NIAnD_KHn zg1)E-|H~y<*;v-G+?6iUIzCKaDs^b|Cyrla_4TeePp9+&w3;-(P-Ji|lBm^>aV&DB z!7n=!st1hQE>L^!`gR5OdL7+mexSd^>_bnxK-X+0+Fz142QtNtK230}YLcu|?YCPy zsday9#0$6-9HVuwj;I04O_lrsv$R)w-JWy&tkei!FsQ zZG>t?;V}t}5#cFAPZmWk(bW?O3!YRfR!_-L;4fG^(1y9Ru-ppp-Kj2iN(NUr08bxr ztH3ZU0?QFJ;055_yq(CK=?OvoOT|N>HwLYqmMf&3JC@wS zx~Vpt`a;n&w*UEEfd2W>$Qbklw9*<1WO+>R#e{~nh58G{%1}SdzH5G%k&r9$FF(u) z*}sEbkJx=KR5EI>KDN|CimqdCcd-@(~U<;EVPI;&kRPL+BCYUpJZuLIOXCz9M-x|*YT z=fFFxLwTTb$n$mOLAxeOkN!uwR9RVhZ#u=j+*L2wC;M;A$QMnb1nZ{=@5fQ6f2D}f zGO*l}c!GBt;iY@+w8g{97XiNL#&n&BO#AZFs>;bly(-F zpmf~nNa(o{oQ$yx@CRYc@J2S}p(jiPb379#Z-Q2GAABO_7Z4d|j)NP>QN_KG$a4_? z0P&9&#yn5*;kV3-dDda@?eH*B4AW02sf!-O$&5nq%O6De;3hne;_18QUGa8%mbg$6 z<{nj2rw@lFP^yc*6yt0WSXAg1ho~ld>rA%Yf%5#5l-TBulSzL?end$=e9DI zFI`NxWeZba*;pO*#^&Y!Tfuv7B33U-6U#>0;yD*5htLxh+M*iHKAe@bY@~K!QW*&; zZ`09_5>1tK?o1<$mGhmG7?h$mo6m4cfX|hE3T(e|PORg~3Xcak1M5=1yH4XYw5Ny- z(UrYc!fc)_#+X%dr$~YUk(B z983;-DpsELq*cppf9hp5!koWeB=?^Sa52i{y@HL0{in z*#ODOy@YZMX^whO6l>dScGmySN|P82F!@5kgq#a_1An^cVqhtFpN>jU6EF7N*EqQn zxbvrWb|>}Yr+!(`@y?51V3zEy@wdg_u7yT7&+Wx{7>mUP&1pSs({talUpelW-*;?h zaWK$ZpVU|5^ugmJR}|p-l}tU9uDT}ZuX_(Y1Ga2 z9S&M_xAz#Jsh; zL}rB&nHNq6N@PL!AN=cu6M;ilNZsM%hl7vnrlPI&x*Ytk(oOVd^}D4BIH6P0Z>u3LH%snt5RJqvw^eIqp+1Fr|~!^k(EIvlLP zY`jq)FQ4I-KugtGe@gtFbD6^LqYx6>cZ;;Y3&m9UnSmBeC-R~pjrhXnhlBU)>iQqq zA1|UeB|4KfsEN~M3$JF&nz*cXovHN_t0i*D;ET#cXoKQdCdckG$gIxpH$Z<24;q=k zR$z=zkrQ-9fELlEw(}Owa=@N&+8_(MKlXBJ!9Pp1NJdEYJByiH2mCXO$Yh$6_g%-B zoyD|%0W-I*9QH2VI?$5|;vaf7@$tPH)mTuA%GOyT)y(~U|=K@DsK2wa%Oyf!?v)jC*ivqVO7DpeBcyO^e?`4dlTgN%l0I+LLbZ|)$LTWs1!8J9v#VtMJ1xxff5)9LcaQ&PfK2%`V89(zhIXbP z5TH=t8@CnnP0U;~`0}fO#(43&(4de@@VAJ3cYH81#~Ov4MWVTA{vV6B<7mdyU(-C~yD+lMv2 zt@uWGK^dWoJsgbOs`Bs4q~&?gfSstJH89-*TJ;AaEJU~ifpkP7s8Meer)Q6Er?YL5 z_1tsxi4x=ni*)m6>`d5&;%PlQi|?Ed8T~ZY$=!5DQ`_g8?t>o_oh802pZ3VwrJi>3 z!ywU4HO1!KYI-Xer zluSw~b{79NIzx<~nfYFTw$GweM?1UYw-n6iOiHypf6ZcbDzT*W;#cs z{mr7PTL?x9(Q35c#q&eQ-?sm;SHsO{2VX26!8{bU6U*qL@kPL8;obR+|K_5d=V>p~ zf!7%Ow0<9R%Vn(Ydv!v;v4X`as?qGM=VEpdO9(U1YJv-Q`S?FQanvb$E-urbSJ)UFG^O@@~k=3dp)PWqbx_( zU&|ptN8apC$KI~;9k9DEzv>R9_q7xk?d?@*aUx}KXZI=49#Ti)W)RDJ&ONl7(!@2t z@!{*5gmy#A(w29|ZVS-yrvJxyvt+gQaB!)Pj!wk>u!cL`5|>lj8JAlOI}9f;oGjuu zRupH^`n5qmt_#{&#z#z_2WSi7Yc052I$HVzS@IZdJoNQ3NO8Wg6jJOoAB9s@fNjdC z`EhQ%pT#XuY@rMvfd`>b^ zyou4YoyGgU6fA!W91@EH4)L_O4F7iq()-=zz_J3;%@%aExB~MotJ(A(R(EUviv4}G z4&V@jI<&ni?1cyHSGve#zPngl8aQAdIDIvp&W9OPGe!|;ZF=DBVbM1~yX%!+fgGCu z0nW9liYPst;%Az2i^hrfe3_0_qzbYsi7aR{80dSUXb{@QCu8uxO{iGL9s~5&{5IVbFJsMV&DHVOVmYA zf|B;B7nO4OLO!MuH;ZG$%ytXBEwRGmGR4ov7UD((vzQA$_mP3PoWtS~+>@|bjQiA@ zzi+-8{FTtYXa1#Q^bD->OL`XsA&7qM$c@e%A_c>-Sf3g z%S`m*KlrsiJO;NM@Qh5ee7pNGSB}r@Vl?(J#p~szed~m$w_;uV9`xt zjKBNpma6B!(m!GRT7%U0qa{=)adu;<`RiisA9@p1%v@pi0Z__bf4*l@&zI|%g7l(a zLyJE~%y)9V?{ke`kteKQYqY=nD)-y^`L33)`6rl}ZhY4SRl*tNWmtV)ZeDarujS>- z3P#91Ba&@h8PK6MIdH?nFF#u>t`N!2Qo!}^3JF>hmeJE|+joiaI5j3H%!j=Ewz5&& zDxMFFzSej2yUO^r8YBH{6&)$x73;UCy|3tcuP^!cf}f}U{gLSJn>s>fOukZ;;2`eq zS&to==g9gaoS{JHyD6=AzyEUWa~#3lX7GR15GqxS3Tg=C4B4WPEdEn)AUL~DwN~+Y zVLz20S7@$AqzJqRMMLf2T7ZrCRG|*qSCDT#0c~|^eas@bT6r#+e-C`)zBDS9OlPgIDI*w#|keV zu!2h7j&?_#ra7su<*ose*LnKa*CgAg@bm{hxu{+^HQhLs@lUuRv$M^PJ5$}j{`;G9LUeK7k`BO z{9YGd^m4Dj9|=%AAMlyPGEqi78h$WjMV-!~zLj4`B}pqrns$9WR(+eJvJX183yN{o zJ(b(+DZX=+JCtI51|;>P7d2*LUY5Q|DKp=o#AHfW0!`6Vo2B zn8A?{Jw1(?%VwY{%6W^4KDWF@H8Dh95Iq}0PYQjiwMf%k)XnoCJ2i}9+@=+?8sP_sBTrOVz2DXxu z=sVw~f~|^y&R^eF0sboJ4+nh6_W|+?(CY*uF9nUJ!0 z(5A{yZ_1%ML3(oswGGj>^xkBgbYKd``;uUDQO(_LPdlY^HsO2&slaKog5CC{W4s(c zz(Y$D3Bk`wKCAHZAECkEG16u+;b}I-Hf|y_+K5Ac<52+&fhHRJfIBK2dG8j#=k4V!d>FHY6i70ADH5yHe`}Z zb1!r)#V7)Y+&mxz*kcp`}^wOn^5%QF0akKQHOS|ArDdkU0rD z@tM5*u)>=(+cd96LTn^&YQO)>0Ij(n5;T#I*7HsDJ{k_P)7$kpD?f=fJ_Be_ddbV# z&^Yn(T$};czZLyXc==tW6PEJ5_VJy36YMdR7UQ-ez7a6BG2kXLT48tIol%ogJ@0Zd z$C@;+k|}Q}nb1oe84+RAWzZvoaty1Hm$MYcYLkCd&(Am!$VZ=cjL?xkUOyUkC!738 zeQp}s(r>ks%hmPJFV~UF57eK*jW^50*X^nP4^ZOy=qOg!Pi(bEZB65Ghv+2um`*DC zlYO+G!bad01t?r`rWf8~6(gA2og}N{a&f(CC%22;&0rs7@;?cHhXR+*$(_(Pb8=S% zGH&iRyG>T3cb!p)t%$ajTTdq4AWrKhQ)l}h%ADoX{CZ;9BI%vh9imngjGW9Qt`Ob^ zMbr2imTYjc506*x#SOR`P#-xWnhME3^jnD3Cp(phkdd5!a z_wzF;jQ80;>cq^ws`*VMG--s61;<&>(;I@GjcB$V3D9*!*F!b-po54XLZGzaqZ9;u zr|Xxl56wPEtJ-nmy+*b%5;_ao+j02=HzYkR+w>MBLCOipeoYe_O}~J2A|GR;FNSr2|E#GkTGQVDTGNqeO^v8&x5g&_(kFK-{e1| z>}aMr=J#l|%g|H*NG$*Hk)`u*?f>PQ!08l<(=m)*KK$92u{C?!u-RhpaDUi4oVo=hOTg((PX0%DRH@O$$*04(C&^=o+Ca6pIZOsA$Hn5t3+Ow$vRp=q z>Uc*&U%~_ZE}Xsi0{E~V_|lDM4e$jTzy(IwhD6Fq6j(rIamNO}r+9Us`y^L)I?+k% zWaXcrMlQNTQtL{b)95lt^z0gA29LuSk>jZWChKd+s2X_P(mH4xv^~~Ixer>$>#g+r zcxSaYHj2&798NfAl&UeFM{ut~;Q>P_g-LbTdVrJD;p^^z4xg1L3~=L9x{`0J6mv1+ z-{7=8^zfpk|Ij*mLWym}nY-at(0*q@H~(DNDhhyiHAcOvwY>lH8LHd5Kmk6-Dkkj| z26X%z(2qy(ygvT-NB%W_nil8OcyZ@embNQ4K2{!!(ecsI#WaJI6Br24yb8Do(EvPn zIIjF4Y)A@hmnN|gJ>jTL#A}-;c&DJJP@w(YXz~|P97Jz9MDF0>jgDT9=sy+1mC?LSXKCofl|p` z!^n>eejae*b`%3<^(wpu>8)S}{&axyA?{(SZO2_YhbXV2hjm8qmU*1g7Qju#r8u^_ zQanN>E1P2{8!YAhU2EA=wgk5(;I7MO0k3)l+~X(it%Ah%eAg;ywswJ2^3nGdtEg9{ z-exGKQp)^id9it5vURgKwFPG%wYXn+=050N$fUi`X29P)-dFML)RsM~s0|8!?C$$E z#pDtOJFgYDnI~<57Ypv-*$S)U)9`nRl^X9qTf@qcxU;Q{X%E_5S-pJ~bT`3tcqr8m z?!kG~QgQn#s-K}6jx8vAuBM`uOgoCZg*fst{K)8S0d?wc@E=d!qjB;sxav@OgX9KJ zgxe!3`CwjL39xP%ZcUreMJ7RZ(=tsj+WBMWYPvk5T2V%|w~B#;*i^Z*`0R6*UnI9= zwCu)hIeV)zR%LjI*$5r-&SF}}&j&%TqpRQYi?h$AwIsJ}v5)uNQ^gc4zAK~U;6T29 z7lnz%^3*vgrN6sQ<%`eJ_)}yX^k$>X%uFg1b_7P{4EU+N!O$KLPfIej-B0%ilI!&0 z*1mNE5d11YOa2QcKf~9B zss|{HRh7|uxf-OOR;q)B=p9~f;QmHSS08G*(O*ylo>h)$X84#JrqVI|z}-;=k5L^? zRqKH&D{QgQv%wlf?~J09;o~snG39!i))Y-UP{o~IAz1Jp;(3g2(&G_59$kcLJu52u^;HLW(WaOp82vt6+2V(o5(2KrNrkRfei;IA2jP$s=6PBKPay{35>bqr#-we zTnK0>4eKhQf%T1ZJ-iZUB`#6_c#8d0s{Bc%2rmhXr?+Mws7f6_shgF556XYlkDHs~ z7ov`T;BL+IuHG6>j{L92z6LC+GVT94b7qDCMwmbo0da-_9Ry?)RQxE10S+j(T3TsZ z4Wf1k)A6Ii-QIOb-2BeMEmPaYurh0R8I)bo49jXOw{1r4eN}X$teq6K!LK>Y0Q3Ld zX9jcMb>Hhh*LCJO=R6L*-74P@N?D;$+VSPgDl_xi>AAclDEH)xPM7GI%}c<9es?Zk0)R z-fPk9c=EGrj)ZL`GIzwCCm7prPcI7TMV++DG7j%!ud8c|>8J!yLMsiAej-WD+bOPVS-YP zmUO972DhQ~FZ_Gy&r=<#X6&ojD9;$RA4w*0y{J?Y4=f9t};fKlgthJDnq&vkUkEE zp0l87`?v6Yf~zXm&_4p2k!=xb0{vb2tqZH@6i3b4OyKW=e zB($EOyak+hQtNx6^;h6Pm*@93R8Me%=E1zvV5e0CaSntqwv_NU^;U%a6In&r|10ja>akwcEhWy$^S$;Ka0Rjzgwn^lJPn`@yUx66`wby# zUU zGbDm@qmrm!Cxb=+_P5-_ft(7g8qBl|R1zc`QoyC7UdMTVYNbA_h`(igSRT2dcvm7WF1OPY1v$3}y%+K< zEL|z&2=g}nv8iu{(7Au^B}&jGjHngNELVV>N>Y!|OaDO558g4;kFEx^`>rRGn%=1T zeC`9Fs2b$eiSX67TN`TG*|%%C(SP?ygx6f~$tE_e5q(<;%I*O6^I@uvN{6~&rX1JM z&10JWXw`!%#2PBh!CNkMlf<)rojgaS+#LL))gk=gI=_h<`?|#IlA7jKwKlnDW;Su7 z&#$3z6H4=>hk7Wq2whw%(Ms}6Xgc8zmef>%X)642+Z1+7kWFOUyvEK4SfN7o*6Ko+|)p@i@l>Y!E6GPSLks~LqtIQ-N5 z2N`eL3ho|9Z<~3MFi&J!L$EnNahNdk-5Y>}j?L7P3mLU6!7R739+F57aSKw7chU^E zaEL+Qh7V}RaOXbq>Eex$!}(ix={{frn0KWrhH(>WaaSNli-~r9>hG66VrQw_ z?Pu(XOCMQ!W+@OG?2jxPvMkD|DK`tp9Go$FX)emNtpq;i%T2`FA>;+Z!INYR!mC7& zmB`<}!E?*D{eAa@Xm^CZNV8 z6rpAGdpr0jv}P`yp6zI=1Bag(Q#WtI%v5L1bQ>{8)`32zHsnAZbK@A$dk4s^*xS9g zIOS9+YVrQ=k(h~sz8viAKll8w3A~Xb+{k%V+1MYbjwFIo`fkk*npO3o^#AVJTikIf zQTPg)wu6gC*DUcSsgOe;Ko|w}l+O$njMcAuL#u9Rl?7d-y6hRdh_F;@MNQ?M+rZfs zWsdJ$9IJJ0XyI#6Zm!37Ue>>w7e>&{KTLQU)G`m5ZveHKa(%Mb3%%3(TL~e8>VB*A zh>rIvRJGDveW&x6&SIw#d^$bkxjDH-g1+uv&R8qWLC85Q|1j?Kqgx8mUWDL18~n0M z@{C{#UXkgy+kL+2Md<0UKk^^3NM<{?p#9<@Bjtcg^qb;GvOz#=LrvQO=!=t273-> z*e|6Xd9mq@jj{fX-EmD@fz@4()h)F1P-5pna}n*@LZdjQyKkrV4Unc@$G(PkFDiM@ zgcEsd`{}ngzVYOwrsI!VXTCwRlARD7U$wqb%bndVr8RORKlLa(H-hFE8Nis)j}%G; zZal^eP5^w4PbHmW)KXAJ`Z(->nCW%bmsn@|3E|ei!|I5%fNk63yND6+pqb01(MKy` zGkS#)QidU^*~eS$hYOrXs;nDVhu3h<74*$)4I#121rkeSF0{417aehDiN>J&w;WE; z9^kn;LO3m1GD^!VqCHf_{Kt({uHFQnD+^91}<^cqOC6Z+9tz)Ew&0p1Z^mK~zY?(pq$ z(C49eM3nN4yQ*d7hScG0uT8eko_7^5ea;Cf5aG^)$BV;+K~v%zH#6`!zO!TS2K8ho-Sn}N!53?cLPsmt%4 zvK%t=sHY7f&JOWeh_geplo{oJRiZf$@+Q}~Q8ee#+^HG!i{dtD2+gfb2IXNA>PuLf zO!d783}WTWo}Vh2=G!W!IrkLKqCklZ5HyhIti;%4z^^rm!*QPkxsGimbW%-TkRMw_X8`f zxtHC)+hF$~^;8hnugfC(xepOL@=8A1fTcU}{UJB6g^& zrIU}%!aoPepAQ^aBH1Znzy&fw7FwCK#R`esq%OB&ZJa*Q(P+i~oX-&Uw3>y?r9V2V zp(8+LVW!A4%ve>UhV;}<&V)4n4DO1Dw7*to;AtG}tFR1SEBNfdKHZ{evH4*~b@*4}N?h{lWKe zPtWB3?njcP|b8+a(!ah=6wZeG*4MvR`KGyGP17^{W|`geS{2x*3QKuJ;@6?6dn zz6sqXJe}<(ixd=})(oX76D{IkoeD+&HVfm83Uh`1 zNR!^KZs(0keVIMdsIhObe`dEIj=b-CPvm{y;cE9>nG0z$iAx41&7yB;R5H-8t+{W* zW)m(Gu54Va)Lv2qmoq`iz@;z^afyc_jHdc+xgTl?3UE1rBSKt zmulPl{Et_zUAo?`2>Y?rDN70It!WMH9L*ad=*EfGaRG zZ5VorMuTzE8FUyqgCcdBH!`N)ets!~$$__)w%ez9b=tRxU5!+ zY_Eb`$bci$ylU-vSVpN|@z1Agr9?bOXxpEul~NqW<>kxYSpMB|!-|R(9$<>>dV1J1 z^PU;@Z27ZG5L167wy0JzFwe6~Dr+U9W12Tg^MrR*M6Hx=u9b#5YNb@WWmv5=ti4uB zv)4){+hW8TZjM2$OyngCAu?>WQZ_=5z?Fl`e56(y$*v&1T!a_}-#o+|4WBW(T4^kN z^VyzC8+N$0(l}h>^|jIjgqVmB_vr2g_2{i3sSFMHd7SqTkl!Hmseo^23+%?WNX@HZ zTZ7gBJ6JtLMZMwzup|PrK5Auv$aB#%|xX!?ZVEQ_bBIaoi?$`_^IKMf?iC z@7n`^V)mgG;;Gr@BHg{rtM}jCse@cFz3KKn9ryulD@`N&QEMR^Iaq)l2Cu892LEsN zDpT%lBPrthh1Vp7`9NzFPAor%T)_rN-a$GZZT}MVp7=AR2)(=4)P4rCrcuBtJ&pB) zhu-(B*16WXsP$LSQ6kk0X-KpRxANL_2huSEeX&1jx&Omz~#aHN= z?n7UoyU-Wt?wqZGI6$C{V+ClqdLQah3tlI9%x$Zyn>&uiCY@p4G}J(B+j8-uP6fQ! z8L$SxI#dJhvArwiIy1qqn1FaDRH&U!%MZ^t?5s|KJ@?)Vnu`GxYv# zEURDJyVd)VdgPh!bXAbDi9lW{Rb~GMF}H;@X;?4fGZoHCjKX5jg}R6YQIiXuujEm} zAuIpU-NH?`4sA{|(;{dNL07Mb=Bm7|@3F6iv`APJt=pG$n?(TToeQZg2Kyuj=cXwr1LUNTw}>;{KE9iYN)z;iOxIi%Yd-eCi)@)Se0$d6`IcR|7;^Eyso`BK7B?bGL_v*;he zlV?Vvw(l0=ZHnr(jcj zwL{1kPCyoJf3TERGo^Z)#@X%r3FDSdz`Zs1IIBeH5EhEI5}NbUzXR8np6hKl!K(nx zZaVK8eJczQg>2_;g`oD=DZj@50440aR`UX+63ru>IT;dk3b;{&s&g_RX^b;u2|O{C zkXW5FT;m!xrN4RDWX{_uRpE@Oz?ErBFEfeBB43@8d5@b79V<+2NfnlWHX2?Is{qPR zE-0Q!K)+LV4&(|+JLxOvDC7`YMXWo@nKOK#JLvl`$X6e7o?l0}8+>MeSA#edw#A~` zQ{k_0Z7o)v`0g}Iqcl^66P^ljn2;>K!)m zkndkR^FSxh7q!lMaK)$}6$Y3QdCNuKa*2zV2aA6cRtX880m8k`F_j~5r8pZw&GkD2 zP33Hy!)Hgi(&-!?c$4$Q_#&1mwN=<`BAqio%r3!No>t)B;a-NO8=dU8aod3dv5n|t zvYAKy{mQNW-r)aP^YZArc$7NU#aI5y`33a+w~Nc1cfp!XKUW+0@BP7*T;kO-dkM9} z60Zt(p=b0c(9LTbUxp<%mNCZ_=T*mIFQVr5a4+?5)$PDZ%u4ku39Tn2wgtV-2I;7U zunf46d7U_&9n_}y{r%`$M4u~D`n5rldI@UeEov>DOZ6I!)`Os1fg%QKHeYxbV`h(E zy-h^#Ym}ne1L3yPxhGU6i+L^TZS^g*2a$W_3mF$R`~w1|QeScwHl!jEDhZ|OaG9{@ zIN|B`ZI(Q!HCzZTgQpv}wz&FQK*fE5+Rrny*)j zbDT-|LfilO1@7h9PX3*suiw9XTiB|w!C<&OtrUt$$6t-m8SWqsB+H+8ZV(k z5FeaQXQ)Si0#3G8z#b&yA(vtJ%+p81trqR(E2ALyI!8W1EW)~xs^@Z-+pO*HAnd&^ zLu$fETXHvcv!pHfu9yf(*fu$?B6FZyEx+3?MzthWLfalsLEq4x_rwbET}YQ~U&oEw zUK8{c$d+|Bcey+fnVdV)_`QdRt2DNwKX7h^@vKJ)mp7jBs51ZCrOy1?9br7~S)I&q z8q#OE(+*oYCoiyvI>Pymac5R0RW&%t@))E9@XsK%WCs1R5dFY@xE@><=ADVzk);KE zbFr^V7G#RBP%Ug|TnDOw4KH=Ou=6Y;YlzeP($%|nL8~jXaz|ArX4y4Ly%0^a>*|S+ z<)<$V6IzOuXD5PJ(%H7c_LC>GlG{r@RDa48Pa8M(if5PgVCx^m{sQDSrbA!7yPtDc zaV&N=8vAE>Gr;-oIxhEJ)JtsR{e1%(Ql#E{D+=>@Gm0PZp` zOm}iySenYVN8E-Hyj%JK`y$=y)w_$Db zz5(ehpqHKF-XR(956HqGzPe2$?g^)2IpbZ-IKeiyosfEV_UJG-YE{=fiV?7SuqF50 zROH}YSSM`U7ulHwxdKX01qw`$)_Sq`8_#KIA$K^FZPSI%rGx@lh()V)`_6U2-XKqw zE*IJ=%8m1OgJ1CR1+`HNPNHD`y_2O+1V=~aO}y~A)W6^x&(t(!K)uzR_Z`ZlQ4xnA zTGi;eN9d608rn4uhRhFSr~}HBxHf(-_ZrQ5V=#k6wn5u0?aVqt$gl!w;pheBf-`8L z??I6gRYSI(g1#2SQ?*e~tAdm)rPF8QZaUWGy>hKIplurv^RM8%`bwuD3?CVZO9h0J~rY zG?+ieibwQA!1oo#rUt8$a(kWasyw@#3X0CgF0Ccc`O!M7SEu->hOjjuD~OX-z2HZ! za?FR2O7tiT`innUkAELV9pxzCd+RWTt%5yBMOaE5XJN8Df&$Ve+eGF}GuunZ)(cAl@ThZ%&+*S~heSivw-ojfd?ri$^;LXYU# zkj>izNC&u{Sg+@_@FJher6)cMY2(QO-*j*(fvyHCFf9FsjIHl&j)%ly{8YtIepo8b z*ph&~P-gQUjuV@lb-*4R@Z5XF(&-09tdmDz|0(^R7EV9IcK5SJ+mL4yg$n4CWZGuf zQl6DOGhlrN_$&A}l_ONHER-sQzfU$=jLrnH(eLnDB7qu$vqTEV;gqs349Rzry-K^Y z%XgQ*-q{hhCK}<|E3O8%1do#fEsJP3358Wg+v=(cAdoYCgDoF3I)@pZ(#vnY8#V&K zFTBI~^C=)cP*364!j>yec6o>D9MkLP_u13|Z+^ZC^ms*Wmv3+{tl=?|AF)`kpnV6h z4mo{lV?BE8u^>O#?+Q^apJ44#LsBu|6ME(K)Qr~FccYgxQyxk3-61dh+LD{WWppa2 za)-XZ#Jis5ALiH6nKSPQ%$gS;tmzF7(VA2xjxq}yTB zN6*zszI{L_A^(u}56!Y&RIAu)1usQ3i%!iHW@rpty`~7nGgb#lg5|Rcxh=FG@`g3h zS*yhw3wt85uqQ%!*eu&qiN^f!dT$!uC=JGqKtiYmdf2mFKG-rh{0M&HAc@B_d?pxc z(d%W~9n?ov=y$Njwu)BWBj|x-A+fI?+94Tt=T__TeS%r;a#Ouiu}TZ;K%;aR+dXu) zO#8S|7?ZQ5U8``80CaLXNsxT~4wJ8(`eCxG^nZPqc0pRuc-vs(g_*{=*zmC~mNEK2 zNLLjCPo~TFwSUNDE^o0dM*IZpb_#Z$0Z>X=?PlbL8DA3TByeBfC5~)qu=YQDmzdG= zePaCNOCBBUpm;rNMZPF>7c+%yUeEOF+Nr0PY@?^f0((rTFUU%l!CqCmz=m?;x7&> zNAe|IXLPJmP`l|ghbV1X=5+N7kYS`;EBz!J#%&uXG<0YbTdeC_k0dg^rHFYibWseF zj2r;TNY)zseES5F6H}~G507$Nt_D-tTM2{WizWmB(|fK^Mj zF@gCZ(^t7-!+etR%XJa|gBemvF#~8&lJ+AB-$>O*lBN`NfJ^(A@Un}o4PZ!5%L|{*7EI!||4}uRwu>S3=-LR2qba3sMM`MKIlmQYKt8*?-It!!>`{6F% z(%=nGpS(Qm4;>(UFXC&}fbxnJ3@v08Lz))wr5}oG3HUzsC$uZVNKAX7C9~hL3z#XO zcl{4bn)e7y6^ZN>;1>G6S21*ZgaUWC<=Glw9aEV z3*G|#Z-rVo9WCxie4r@WHp-?EEm)cCwo=#^RGNA0&=U)ffm;^v75LSi8s#}>bccqu z!P?$-Tb#2^(wa}$a>YHxnMJv_ywiI+RI1K|8`E>eGFxF-?zI?c1$?P~`XA_j-?|O@ z(Hg}#^eCTiK<`VQJ;iq)e-nMYSoo6%qa*!2Pp%l%!7G+SvX|pW*_PY-auQEDF(2|w z6b^Z;kk#ja6jx|F?xB<~b{XWlS_WGq%rxox!at1@=sP~&`JQp`DFAxU9FKRuR*VLp zvEQId@$-m5Clh9WeL*qMRMZ0Wt;^z&TpyG944$NzNOSgC{eu3 zp^X#cWXvhf9q`p1Bvh&d_ysRv^;otgyp}}U6lH~lOkV~c>c95pBFIZBM4(ES{V-5d zdOn~ij+mlPK&$h`9UR8d8NV4aj9Bejsh{`tdyO#C$&FKFdE$jD8!ht}?of{m$ljZ2*z?bE%fUD11^UQ+hfYQy1B7G z<`T7_+{3?2;Zw2yRPG6Y=8FI>o(?p6z_$Twj}0ku+ck(M0W&H?&>)PlC(jmxT|Q}K z_&w10HDLF2U@SN;*xkImWgmyonIy%%eQ- zI$uD zGo<6Zg=-q2nN43dO?T0kuSndEA=TMA_-;;u{9O(*am*`7s+2gS`Cb=GBV4Y<`^Gvs zLU+kJD5pre&AGPJb~fyvBw?8k{jR_bNfpp^Ex8yO3G2gqGlYa{SX!56Ig5(3g<%Kp?*=p=rj$GhJM%#&Q`LCCl z=0046xpY+Ia*xs|0bUa?hodLfdN}MKl@WC|$CPp|XJm~vsja@#%yW8$lk8ihWyGJQ z=g7=!r)?(HxrY!U3LzfmFMBL_9)o8Ep2zY(;4~=#k}x!ntHcqIf;6L!D#4?b+(S`A zz@^&~@Kpskvmf$oNH^!DFcw|P1q^V!B@t~Z?yErh5fZXM^HP*%G%%F8ZCBWKxV2YET{EWNRJMe z+@#|ZB|zTjF6P}N>pS0#aW)QokW@*L4ZJ6;c+5Lc8ig5j+Vz^HM705X3}{^eAM}z% z&0)Ps<%-N#nl^?dAZh0kg|O?FqE8%Psg|n)koMyTyv;9&bW#9nSY$afToWpfwpgzA z%YEJ2?`$*pP%&+9-Y9rFGCKQKwo*cq=|hszS!5$$upH9qee1+EH7 z6aT{{pC5>0oTFelkMsnw|AXBRBksC9M%nVg4Y?=Ehy<*N4nkPPYZw!_#@=Q_xKqJ|yw#O!~zIpPo8JHUymV!!Q$^(O3T+Gy?M zz@??rA=*j!p=;f@lOP(!E^`b+_+g(rbuAj4XMxJb-uDK0>s@V1Sa2u$OE1-n`j+q3 z5xy}${IXjq(~<*ZF6RJ-zSO!EJZVj{3f2T6<3l>#{t)Hx`61Ridkx7e(yk@ov--rYhf85pp7t-7pU7ct<02+xtbNwtO))|%O5&5+NUlk z|IRWZ+gN5|8}mLTos*R9-~kv3ZO>vQL=~2q1RvXNKB4yySSvaTd3#C7W!`E37UE~W zg4_K1;>~E8g8YSYg&d6xtz zKY!Kg{0JHjX@2H?$?~eja*@++wM@G>u+*r1KOo&4;(wu66S(`s!i!v?IuO(OniZ=; zg1R$kc6bNXyk@mry}L$n?}VZ`iMyNj1thN~pvx_~$QQ9dOz&I8k*6mPV%S?dysDbF ziY-?aHH!R+MV5^&}oo%*H+^~US{{LNP_oL}Lk+@7|W3wbT_K=mfY1n#DMpx!j7 zH>F>3JzRGa9o|h2s=M`$P~Fv_?&N&S%fPxWiBB^T=bS|8_EUz>KZ|1S)FZRe1}36z7bA^uwAU=Zb?ATprwuP;{k)mIrp zYEG9YKnuuRdVGDcaQdB2MWmr(S5=b;uHIpX+%;wrT9G6xHY{8wv1=)8! zZ1i@ifzk6zdz(0`5ZWwV%==YWNc*!HxWJ9z?GkPICEho8F@)ca|B(MWVD4(kUJhtt zvX}D!Y}-VFKXDiCHIq}ldmc!=t^@X|dJ4Tsz3#w0VDdFATyv23R7Y-iT4z73V0QM zJ!BP$v&g*n9z@AI@s%40=Y8YQ>Ijwl=jSu9TaKLJ>f^I99h++`OPk__^=zduaP84+ z(d;2HNju<|2dtT{SJxc?KZ?_9(^UbM`j9x_mjzd$UJOkJ>s1bJ3S4?lb`{9an$}0s z=cPmoD^j9>eKPPk&V856O8#|AR@(E{WIK0yTk@lJOQILtu&+I{(}4_@?(sa7{sUHN z=%Fn7!IJ>W3-yLP9YK3=Wk+Vo_4s4w5Y7b388R`v3siEccz(XY5eap*ObsMr@!f2*TZ0K?51x`&+xLH)&e(5hqu4(83sBd&vw(dvM0Tid842=kp@>CFhcu2 z#+?ql?o{wUBEb_($yT4D{>z3H7rtlBZ_N^7(c@o2j9D!YgG=4iLn%Jk6IYgnk(P@z zr}c1#_|kyyo*soE4(>QQW5P+#Pdx$Ojvfgb_G|OFVIO(cqHj&Nuvre&GmV43az`{q zG}dzp&2C(e{+H?#(z$;H>+;*Uc<^s$74l_z?3ssF6%HG5D=efZ z5jO~Yatfm~g{Xk|Q&jTp-F$W=FfSO>wx&TBlNn|}a%fPYs%#MIVgq;+`SOk^;Bg`U zR9@(!3+NS~`Cv5(y!o4;Yp~zz!rmIY&?xbEMEA)v_*Z?+Pk99P-`0*Q6dyrZjocH( znzHS%dmD91af8J@Z&jaGO?e6U*c*XFKoq7t%39B&%*alfet$o~BHjg=Qd1GmOXuA5 z{qB8m?o+k+ZYS(hQz=@nO?xq7Y87N6;~`%Y;i3}l>gFciaMQ^`{^10n+hZx43VtV@ z|EqAW(ChmUrzA@GyyPvQ%e!FxjyT_ONy(;3setJ z1v|uP*X{GPhVzLgAxXhsZ?6dY<^>(HKZTu(+`~=>_73JlkU2r^(ewR5BWQ1m7fLVm zj>=iutvy61al?Z@I@LGWX!1!59&rBA3fY#d{-6bwkX6K3M&6Y;QxE;;ib_b;qGWkw zFRdRVc?Bip6^Q3V=Zpi83Wq$9yxd2Q)#5%-2Ol{04&rY(;kSMgk|7!2PBCF6SD2!U{JA%H8y{C#txu`F+UR(0w zY)L;6mbT2ZrDV8DxCwAIaQnm6!qvgm!PUa;4_5;>0j?5mvbirEO8LuP&7lf05_;Fv z!;UN&h~1I`bx3}H>ILCq<1X40K4Q~-|hhE3P~?&I`x`AQEjNM(Ej^Y z_$|Go#D|g7?bclPGTbHOZiKrDcL})5a9_n;f83?HM^!$I9B;P{aWBK27I%s6CfsRo zH^6-rcS_vpAi<^|8_H#rTR-Np;=j6Y|K2QFu34!ftpTO#4{|I0(W9KKDvJ^o*W2gC z!yYM>yw{_}yryJ+l_@o7@cTYGq-$19rLy^;-)Lfl?X4)Q0Htu9WR8Ht#DF@lhiywb zu`B4-16PDWIv{vy@D#mw2(N3NDeknUyG}mYfUQnpY1y z4Y0?c8{)p+0^GpiN$%}Wf>-0>J54wv5Bk0ePRBZpvgF}h8}kiTY9nyBaJH{14f>9t zSCKr_o?xdZ*~ZeYcqm`V1LzE^KjzsX3Kh!XLRqII^`Ej_cr}JGYo)YDC9t&eWludbHv6d@xQ~nF z%jPdEe|pi15fyCm{6!1&Gs~A(vEZf99)dACC*klw=W43k+}(JlFm%pD{-|{M*%fx@ zEm^W+(US7{3zj|pRC(oMR$#YVmsKu);z2vBT(&d^*W*twUQlgcP_bgc{L1Ca@cD_0 zmn<%SYQepX(mS01e5kO?hg~&14&!|Up2^kVxdm=i*gq1_6fZjbtPQ*U!tU|~%PN*E z9zR}R{J;a#9vH7LShQ?G`TUi7yj(2jBZ`HC=pR_{MCI}o3n<6>!lJ^Qg2Mas@T)9e zq@Ta6@|gw8ehwN=Oen8hv|zq|#S(o5QeCk?zd~H_Z&4RKQ(3WKygq&Y&(UW*T~V=M z`SOKNFIu!xzbyP&O6U&J!(T?foyC;6G`O_5bh!F{$%@# z5yuqd*7A%e7YQlh>UTvj6+M5UVQO-9F)RWu@s2h0y!9>?3D#uJ7N^@{ddf}4y=9|=?QPty@W|18>JLIlCD!aA+ z^J+n;oCSpg7pt0^57Y@ax+Y!Vr{&)_YOuMh^x5Yhnb^8~)wyW{o~E|WVz+v)Idn^v z^>aV|_A%hf;|hI?u?yk*`^uT7=Lx3y>2apHJTK(`&H|<}gzx)O#XwGQuK3N zA1-H_7CX~C{3O$q;Oc~45D!;{>&>T`X2Rl7T5m53xf8-}diZ@L!dahQRK@PYn6F}` zWe?7nseiEGA^k6^S4^Lk$Kue%6llK=zRz7{~Erh@Hw~DPuA$MW6a@N!f;2?%xuQY`*KH33jIP4rDNyhJvaK% z@LWLjy@EwFqO&&+9Us|v_Hu9)M+yIb{j#{-+P-;YmSQT-ZNG;sDWcwSZoyy$xHUuvj=c{E57{BK<{+0YlNSJvHu4L&kGO$ literal 0 HcmV?d00001 diff --git a/boards/hkust/nxt-v1/firmware.prototype b/boards/hkust/nxt-v1/firmware.prototype new file mode 100644 index 000000000000..d715678889a3 --- /dev/null +++ b/boards/hkust/nxt-v1/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1013, + "magic": "PX4FWv1", + "description": "Firmware for the MatekH743-slim board", + "image": "", + "build_time": 0, + "summary": "MatekH743-mini", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/hkust/nxt-v1/init/rc.board_defaults b/boards/hkust/nxt-v1/init/rc.board_defaults new file mode 100644 index 000000000000..d3504a657e8f --- /dev/null +++ b/boards/hkust/nxt-v1/init/rc.board_defaults @@ -0,0 +1,6 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ +param set-default SYS_HAS_MAG 0 +param set-default IMU_GYRO_RATEMAX 2000 diff --git a/boards/hkust/nxt-v1/init/rc.board_extras b/boards/hkust/nxt-v1/init/rc.board_extras new file mode 100644 index 000000000000..780b13dc96b3 --- /dev/null +++ b/boards/hkust/nxt-v1/init/rc.board_extras @@ -0,0 +1,13 @@ +#!/bin/sh +# +# board specific extras init +#------------------------------------------------------------------------------ + +# NxtV1 does not have OSD +# if ! param compare OSD_ATXXXX_CFG 0 +# then +# atxxxx start -s +# fi + +# DShot telemetry is always on UART7 +# dshot telemetry /dev/ttyS5 diff --git a/boards/hkust/nxt-v1/init/rc.board_sensors b/boards/hkust/nxt-v1/init/rc.board_sensors new file mode 100644 index 000000000000..5c51e7642170 --- /dev/null +++ b/boards/hkust/nxt-v1/init/rc.board_sensors @@ -0,0 +1,16 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ + +board_adc start + +# # Internal SPI bus ICM24688P +icm42688p -R 0 -s start + +# # Internal SPI bus BMI088 accel/gyro +bmi088 -A -R 0 -s start +bmi088 -G -R 0 -s start + +# internal baro +bmp388 -I -a 0x76 start diff --git a/boards/hkust/nxt-v1/nuttx-config/Kconfig b/boards/hkust/nxt-v1/nuttx-config/Kconfig new file mode 100644 index 000000000000..bb33d3cfda4d --- /dev/null +++ b/boards/hkust/nxt-v1/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig b/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig new file mode 100644 index 000000000000..e051eadacd4f --- /dev/null +++ b/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig @@ -0,0 +1,92 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-v1/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004b +CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +#TODO:ally for VENDOR ID in the future +CONFIG_CDCACM_VENDORID=0x3162 +CONFIG_CDCACM_VENDORSTR="Matek" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_USART3=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/hkust/nxt-v1/nuttx-config/include/board.h b/boards/hkust/nxt-v1/nuttx-config/include/board.h new file mode 100644 index 000000000000..003922a0ef44 --- /dev/null +++ b/boards/hkust/nxt-v1/nuttx-config/include/board.h @@ -0,0 +1,484 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6u/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * 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 NuttX 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 __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The MatekH743-Slim board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 clock source */ + +// #define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED, + * that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PBA10 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */ +#define GPIO_USART1_CK GPIO_USART1_CK /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_CK GPIO_USART2_CK_2 /* PD7 */ + + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ +#define GPIO_USART3_CK GPIO_USART3_CK_3 /* PD10 */ + + +#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */ +#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */ +#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ + + +/* SPI + * + + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2 /* PC1 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PC10 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PB6 */ +#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */ + +/* I2C + * + + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) + + +/* SDMMC1 + * + * SDMMC1_D0 PC8 + * SDMMC1_D1 PC9 + * SDMMC1_D2 PC10 + * SDMMC1_D3 PC11 + * SDMMC1_CK PC12 + * SDMMC1_CMD PD2 + */ + +// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */ +// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */ +// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */ +// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */ +// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */ +// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */ diff --git a/boards/hkust/nxt-v1/nuttx-config/include/board_dma_map.h b/boards/hkust/nxt-v1/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..ff89fb6ae9db --- /dev/null +++ b/boards/hkust/nxt-v1/nuttx-config/include/board_dma_map.h @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2021 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 +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */ + +// DMAMUX2 +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* DMA1:61 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* DMA1:62 */ + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */ + +//TODO: UART DMA test +#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_1 /*DMA2:41*/ +#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_1 /*DMA2:42*/ + +#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */ +#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* DMA2:45 */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* DMA2:46 */ + +#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 */ +#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_0 /* DMA1:65 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5RX_0 /* DMA1:66 */ diff --git a/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig b/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..202258c5c6cc --- /dev/null +++ b/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig @@ -0,0 +1,272 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PRINTF is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-v1/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="Matek" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=n +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_IOB=y +CONFIG_MM_REGIONS=4 +# Avaible in Dual Version +# CONFIG_MTD=y +# CONFIG_MTD_BYTE_WRITE=y +# CONFIG_MTD_PARTITION=y +# CONFIG_MTD_PROGMEM=y +# CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC2=y +CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SDMMC1_DMA=y +CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024 +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI_DMA=y +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_USART1=y #ttyS0 +CONFIG_STM32H7_USART2=y #ttyS1 +CONFIG_STM32H7_USART3=y #ttyS2 +CONFIG_STM32H7_UART4=y #ttyS3 +CONFIG_STM32H7_UART5=y #ttyS4 +CONFIG_STM32H7_UART7=y #ttyS5 +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_UART4_BAUD=921600 +CONFIG_UART4_RXBUFSIZE=3000 +CONFIG_UART4_TXBUFSIZE=1200 +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y +CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/hkust/nxt-v1/nuttx-config/scripts/bootloader_script.ld b/boards/hkust/nxt-v1/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..511ef2624248 --- /dev/null +++ b/boards/hkust/nxt-v1/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/hkust/nxt-v1/nuttx-config/scripts/script.ld b/boards/hkust/nxt-v1/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..85f4990724d5 --- /dev/null +++ b/boards/hkust/nxt-v1/nuttx-config/scripts/script.ld @@ -0,0 +1,228 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The board uses an STM32H743II and has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/hkust/nxt-v1/src/CMakeLists.txt b/boards/hkust/nxt-v1/src/CMakeLists.txt new file mode 100644 index 000000000000..45d0650aaea8 --- /dev/null +++ b/boards/hkust/nxt-v1/src/CMakeLists.txt @@ -0,0 +1,68 @@ +############################################################################ +# +# Copyright (c) 2021 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + # add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/hkust/nxt-v1/src/board_config.h b/boards/hkust/nxt-v1/src/board_config.h new file mode 100644 index 000000000000..34dff55da531 --- /dev/null +++ b/boards/hkust/nxt-v1/src/board_config.h @@ -0,0 +1,227 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +// #define FLASH_BASED_PARAMS + + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +# define GPIO_nLED_RED /* PC6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6) +# define GPIO_nLED_GREEN /* PB14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14) +# define GPIO_nLED_BLUE /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +/* I2C busses */ +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +// #define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_I2C1_DRDY1_BMP388 /* PB9 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN9) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +#define ADC12_CH(n) (n) + +#define PX4_ADC_GPIO \ + /* PB0 */ GPIO_ADC12_INP5, \ + /* PB1 */ GPIO_ADC12_INP9 + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL ADC12_CH(9) +#define ADC_BATTERY_CURRENT_CHANNEL ADC12_CH(5) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL)) + +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + + + +/* Define Battery 1 Voltage Divider and A per V + */ + +// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +// #define BOARD_BATTERY1_A_PER_V (40.0f) +// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + + +/* Spare GPIO */ +#define GPIO_PD4 /* PD4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN4) +#define GPIO_PC13 /* PC13 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN13) +#define GPIO_PH1 /* PH1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTH|GPIO_PIN1) + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 1 /* Timer 3 */ +#define TONE_ALARM_CHANNEL 1 /* PC7 GPIO_TIM3_CH2 */ +/*NC can be modified with Spare GPIO then connected with hardware */ +#define GPIO_BUZZER_1 /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_BUZZER_1 + +/* USB OTG FS + * + * PE2 OTG_FS_VBUS VBUS sensing + */ + + +#define GPIO_OTGFS_VBUS /* PA15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN15) +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */ + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS5" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_LIB_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 5 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/hkust/nxt-v1/src/bootloader_main.c b/boards/hkust/nxt-v1/src/bootloader_main.c new file mode 100644 index 000000000000..5670308a29d8 --- /dev/null +++ b/boards/hkust/nxt-v1/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/hkust/nxt-v1/src/hw_config.h b/boards/hkust/nxt-v1/src/hw_config.h new file mode 100644 index 000000000000..1e91b651457e --- /dev/null +++ b/boards/hkust/nxt-v1/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1013 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_RED // RED +#define BOARD_LED_ON 1 +#define BOARD_LED_OFF 0 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/hkust/nxt-v1/src/i2c.cpp b/boards/hkust/nxt-v1/src/i2c.cpp new file mode 100644 index 000000000000..6700d8c8f244 --- /dev/null +++ b/boards/hkust/nxt-v1/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusInternal(1), + initI2CBusExternal(2), +}; diff --git a/boards/hkust/nxt-v1/src/init.c b/boards/hkust/nxt-v1/src/init.c new file mode 100644 index 000000000000..657c0080c019 --- /dev/null +++ b/boards/hkust/nxt-v1/src/init.c @@ -0,0 +1,205 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + UNUSED(ms); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* configure USB interfaces */ + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + return ret; + } + +#endif + +// TODO:internal flash store parameters +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {15, 128 * 1024, 0x081E0000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + led_on(LED_RED); + } + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/hkust/nxt-v1/src/led.c b/boards/hkust/nxt-v1/src/led.c new file mode 100644 index 000000000000..0420c1da2e79 --- /dev/null +++ b/boards/hkust/nxt-v1/src/led.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/hkust/nxt-v1/src/mtd.cpp b/boards/hkust/nxt-v1/src/mtd.cpp new file mode 100644 index 000000000000..51c6dec3cc93 --- /dev/null +++ b/boards/hkust/nxt-v1/src/mtd.cpp @@ -0,0 +1,81 @@ +/**************************************************************************** + * + * Copyright (C) 2020 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. + * + ****************************************************************************/ +//TODO:Prepare for NxtDual + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 512 X 64 + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 2, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = 32 + }, + { + .type = MTD_WAYPOINTS, + .path = "/fs/mtd_waypoints", + .nblocks = 32 + + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 1, + .entries = { + &fmum_fram + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = &mtd_mft +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/hkust/nxt-v1/src/sdio.c b/boards/hkust/nxt-v1/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/hkust/nxt-v1/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/hkust/nxt-v1/src/spi.cpp b/boards/hkust/nxt-v1/src/spi.cpp new file mode 100644 index 000000000000..54a338d94ce6 --- /dev/null +++ b/boards/hkust/nxt-v1/src/spi.cpp @@ -0,0 +1,52 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_MPU6500, SPI::CS{GPIO::PortC, GPIO::Pin4}, SPI::DRDY{GPIO::PortC, GPIO::Pin5}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin3}, SPI::DRDY{GPIO::PortA, GPIO::Pin4}), + }), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin3}, SPI::DRDY{GPIO::PortE, GPIO::Pin0}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/hkust/nxt-v1/src/timer_config.cpp b/boards/hkust/nxt-v1/src/timer_config.cpp new file mode 100644 index 000000000000..e3373ffeed96 --- /dev/null +++ b/boards/hkust/nxt-v1/src/timer_config.cpp @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer3), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortC, GPIO::Pin7}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}) +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/hkust/nxt-v1/src/usb.c b/boards/hkust/nxt-v1/src/usb.c new file mode 100644 index 000000000000..9591784866a6 --- /dev/null +++ b/boards/hkust/nxt-v1/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} From 67fb70a65e7ece632470a85256bca8b7c04f9853 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 28 Mar 2024 21:34:47 +0100 Subject: [PATCH 064/652] logger: make logging of rtl_status not optional Signed-off-by: Silvan Fuhrer --- src/modules/logger/logged_topics.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index cd72d324a0c9..870e9a925751 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -103,7 +103,7 @@ void LoggedTopics::add_default_topics() add_optional_topic("px4io_status"); add_topic("radio_status"); add_topic("rtl_time_estimate", 1000); - add_optional_topic("rtl_status", 5000); + add_topic("rtl_status", 5000); add_optional_topic("sensor_airflow", 100); add_topic("sensor_combined"); add_optional_topic("sensor_correction"); From cf87cd27f5c18373de0b1b28f7546cc1999c0870 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 28 Mar 2024 21:36:12 +0100 Subject: [PATCH 065/652] logger: reduce interval of rtl_status logging Signed-off-by: Silvan Fuhrer --- src/modules/logger/logged_topics.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 870e9a925751..3465d857bc05 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -103,7 +103,7 @@ void LoggedTopics::add_default_topics() add_optional_topic("px4io_status"); add_topic("radio_status"); add_topic("rtl_time_estimate", 1000); - add_topic("rtl_status", 5000); + add_topic("rtl_status", 2000); add_optional_topic("sensor_airflow", 100); add_topic("sensor_combined"); add_optional_topic("sensor_correction"); From ab1087906d56ad0cd519aa5641bd7f23ab00e8b5 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 25 Mar 2024 19:09:14 +0100 Subject: [PATCH 066/652] px4io: remove special handling for HITL In HITL the actuators should not be mapped and they are in lockdown. We should not reconfigure disarmed, min, max PWM values without updating the actual output values because the IO will consider the last outputs before the FMU was rebooted with the configuration of the new boot. This can result in spinning motors when switching to SIH. --- src/drivers/px4io/px4io.cpp | 29 +++++++---------------------- 1 file changed, 7 insertions(+), 22 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index e98a9c837d55..52ad8325144e 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -335,8 +335,7 @@ class PX4IO : public cdev::CDev, public ModuleBase, public OutputModuleIn (ParamInt) _param_rc_rssi_pwm_chan, (ParamInt) _param_rc_rssi_pwm_max, (ParamInt) _param_rc_rssi_pwm_min, - (ParamInt) _param_sens_en_themal, - (ParamInt) _param_sys_hitl + (ParamInt) _param_sens_en_themal ) }; @@ -474,9 +473,7 @@ int PX4IO::init() } /* try to claim the generic PWM output device node as well - it's OK if we fail at this */ - if (_param_sys_hitl.get() <= 0) { - _mixing_output.setMaxTopicUpdateRate(MIN_TOPIC_UPDATE_INTERVAL); - } + _mixing_output.setMaxTopicUpdateRate(MIN_TOPIC_UPDATE_INTERVAL); _px4io_status_pub.advertise(); @@ -525,9 +522,7 @@ void PX4IO::Run() perf_count(_interval_perf); /* if we have new control data from the ORB, handle it */ - if (_param_sys_hitl.get() <= 0) { - _mixing_output.update(); - } + _mixing_output.update(); if (hrt_elapsed_time(&_poll_last) >= 20_ms) { /* run at 50 */ @@ -540,13 +535,11 @@ void PX4IO::Run() io_publish_raw_rc(); } - if (_param_sys_hitl.get() <= 0) { - /* check updates on uORB topics and handle it */ - if (_t_actuator_armed.updated()) { - io_set_arming_state(); + /* check updates on uORB topics and handle it */ + if (_t_actuator_armed.updated()) { + io_set_arming_state(); - // TODO: throttle - } + // TODO: throttle } if (!_mixing_output.armed().armed) { @@ -814,14 +807,6 @@ PX4IO::io_set_arming_state() clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE; } - // XXX this is for future support in the commander - // but can be removed if unneeded - // if (armed.termination_failsafe) { - // set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE; - // } else { - // clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE; - // } - if (armed.ready_to_arm) { set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK; From 7f0ec2305c8b1efa239eeda5aed24f0b324ea5a7 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 21 Mar 2024 19:54:04 +0100 Subject: [PATCH 067/652] px4iofirmware: refactor to only have one PWM output code path This removes the duplication with unexpected differences and allows to consistently handle the output instead of overriding the output for some specific cases which leads to unexpected corner cases. E.g. disabled outputs suddenly outputing PWM in lockdown. --- src/modules/px4iofirmware/mixer.cpp | 32 +++++++++++------------------ 1 file changed, 12 insertions(+), 20 deletions(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index db6e14844a29..3b02242c8a96 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -219,9 +219,18 @@ mixer_tick() isr_debug(5, "> PWM disabled"); } - if (mixer_servos_armed - && (should_arm || should_arm_nothrottle || (source == MIX_FAILSAFE)) - && !(r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN)) { + const bool armed_output = (should_arm || should_arm_nothrottle || (source == MIX_FAILSAFE)) + && !(r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN); + const bool disarmed_output = !armed_output + && (should_always_enable_pwm || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN)); + + if (mixer_servos_armed && (armed_output || disarmed_output)) { + if (disarmed_output) { + for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) { + r_page_servos[i] = r_page_servo_disarmed[i]; + } + } + /* update the servo outputs. */ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) { up_pwm_servo_set(i, r_page_servos[i]); @@ -234,22 +243,5 @@ mixer_tick() } else if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) { sbus1_output(_sbus_fd, r_page_servos, PX4IO_SERVO_COUNT); } - - } else if (mixer_servos_armed && (should_always_enable_pwm || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN))) { - /* set the disarmed servo outputs. */ - for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) { - up_pwm_servo_set(i, r_page_servo_disarmed[i]); - /* copy values into reporting register */ - r_page_servos[i] = r_page_servo_disarmed[i]; - } - - /* set S.BUS1 or S.BUS2 outputs */ - if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) { - sbus1_output(_sbus_fd, r_page_servo_disarmed, PX4IO_SERVO_COUNT); - } - - if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) { - sbus2_output(_sbus_fd, r_page_servo_disarmed, PX4IO_SERVO_COUNT); - } } } From b714b5461ba3047ac0189e8481d41179a942a6df Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 21 Mar 2024 20:08:54 +0100 Subject: [PATCH 068/652] px4iofirmware: simplify lockdown logic --- src/modules/px4iofirmware/mixer.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 3b02242c8a96..82d332032780 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -219,10 +219,9 @@ mixer_tick() isr_debug(5, "> PWM disabled"); } - const bool armed_output = (should_arm || should_arm_nothrottle || (source == MIX_FAILSAFE)) - && !(r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN); - const bool disarmed_output = !armed_output - && (should_always_enable_pwm || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN)); + const bool armed_output = should_arm || should_arm_nothrottle || (source == MIX_FAILSAFE); + const bool disarmed_output = (!armed_output && should_always_enable_pwm) + || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN); if (mixer_servos_armed && (armed_output || disarmed_output)) { if (disarmed_output) { From ef5569fab3bfc196b18d4e290df5c6afe2b3dfe4 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 21 Mar 2024 20:14:03 +0100 Subject: [PATCH 069/652] px4iofirmware: reuse existing disarmed logic for lockdown and `should_always_enable_pwm` The existing disarmed logic already handles disabled outputs it makes sense to reuse it and not have lockdown handled differently resulting in unexpeced corner cases. --- src/modules/px4iofirmware/mixer.cpp | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 82d332032780..936c1265055e 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -176,6 +176,14 @@ mixer_tick() atomic_modify_clear(&r_status_flags, (PX4IO_P_STATUS_FLAGS_FAILSAFE)); } + const bool armed_output = should_arm || should_arm_nothrottle || (source == MIX_FAILSAFE); + const bool disarmed_output = (!armed_output && should_always_enable_pwm) + || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN); + + if (disarmed_output) { + source = MIX_DISARMED; + } + /* * Run the mixers. */ @@ -219,17 +227,7 @@ mixer_tick() isr_debug(5, "> PWM disabled"); } - const bool armed_output = should_arm || should_arm_nothrottle || (source == MIX_FAILSAFE); - const bool disarmed_output = (!armed_output && should_always_enable_pwm) - || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN); - if (mixer_servos_armed && (armed_output || disarmed_output)) { - if (disarmed_output) { - for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) { - r_page_servos[i] = r_page_servo_disarmed[i]; - } - } - /* update the servo outputs. */ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) { up_pwm_servo_set(i, r_page_servos[i]); From 8579175013a991fb295ebb19f2258f2f1ccdbb49 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 25 Mar 2024 19:43:37 +0100 Subject: [PATCH 070/652] Build new IO firmware binaries --- .../ark/fmu-v6x/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../extras/cubepilot_io-v2_default.bin | Bin 39928 -> 39940 bytes .../extras/cubepilot_io-v2_default.bin | Bin 39928 -> 39940 bytes .../durandal-v1/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../pix32v5/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../mro/x21-777/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes boards/mro/x21/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../px4/fmu-v2/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../px4/fmu-v3/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../fmu-v4pro/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../px4/fmu-v5/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../px4/fmu-v5x/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../px4/fmu-v6c/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes .../px4/fmu-v6x/extras/px4_io-v2_default.bin | Bin 40148 -> 40160 bytes 14 files changed, 0 insertions(+), 0 deletions(-) diff --git a/boards/ark/fmu-v6x/extras/px4_io-v2_default.bin b/boards/ark/fmu-v6x/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin b/boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin index b7fcd9dab24cf4eea06e4c40a6eca8b885ade3bf..fee2b669933de677ff8b5144ffa51771ce52f936 100755 GIT binary patch delta 3320 zcmYLMc~}%j7O$F~qlY6Lg9|dCGc;((2n>wzVwGVC?Hs^>8a2TKMFWTm8vVpC8pZ={ zujp=hBWsW(8`l_t)=x)2zR@-2*j*DQz?Zm5Hiw%yP6Nx#z8=lDfBfqA>eZ{N zSFc`GSBsZrJFm!E%P^i!mSF}L^9}eK#*0WUl>_BADg!U#+bBvIzWNlRHv@J84)HhC zcPSi3-VJ|WRDfZ0KKx4Rwey)MDWVSyN)dn@Mv?3O-CeDba@ru13zLKuMN5 z;WVPnmI$OHX>$_sPsA}N1Aj=~m{T=YG1};8wBPKLVZsH#%{;+O5f>JA^P_XV!gvAc znU{)Jk-)q}yqF}u?7%ss>g8YXw`9S58!qCT=Z9jvk(^(Uffw`NE!c1mvfC50|C6tWxNJl#oT(sk6AHp=LDb*JSvr&e0OWsB_2b|U?I7 z9QW`egO6s}4|_DODA&w_Sw-cXMu?>3p6PatD{p|7@m#!RsW+OLV#j1ENm~?KZ%hpM z!iSo~-x`r2r!y<5oRcEaBu2(SyV&GU03M1 zI1gr2B+$MaJW(}fx5@R*)_`xnSk5s51s?OT?ik7}7`Gh|CmEv|If*z&k?{U>N=BYL zhsjZU=((d-L{MdTe;Ot055qDcYQ)9H@l9fyuAD;`gP!EnmDn|Ip```3-Uy90?4SO8f3l5aBB;r4LgG|s)n_;xTJnc?^UU{SJfEm zRz-O6GzM_CmzX#%x6&U{m5=#AUIQp#?br)hZeJ4 zw@asg6D-vM@MPH*kmP|aHZRoePrcvQ z?sp0@wW*F00wJaD<8X0FlF9AvmqqA1vn9P;du=rrBSgwqc_r;wugy_pH^J!~+m{dL|JHDTc)U~ zM{vl)u!%N222WusrRi4}l%eifbx+!>xhYP#u_ChTuotCI?F1WK>c%=GOc{a%wN9_~ z`%3)jHigdb+w9M-Lx!wQ>1-hH1|B7kFVeA7q|0P763&VAB%jy7om8oN7)KHdsXW^e zYm2MILg_V}+}>;8zEQ>WBs^=147PlJ6&boaGg%{x1iy&&D(ftmFwGxh`?wbd*o{0! z_`*qFxhj&sJR{~KkglkaZqu`CyaAYS%U8{`jy}&Ov2q&{)M9ld(lKRBmE6QEo7Qn- zJ)*@+a`rhkmi@2qgFtQDyOnn<&spSO>%d3R{9oV4B%}N`zDP#PE1+DtVz!KKCLgZY zrI^-?=!^XHl^GcHRj=9be8Rt0Vaggdvcta7;itEuG>WjTMi?W1()+YTo=?HWi{KiX zgw4`7`7kN0=z=lym6!2ta;LH)F*r0>NZ%pp`**rEmPPv2N!0tJJ`Gu1)r@D5KvkbY z8f6;!WmV2oXGmuC>H3n9yeFs8kgpK93D^d_4>*6sJ}?G2cO>`8dEl8N1p^0xr-MEW z_{9j9`84lfxkG1&zcBU_k@NL5p+ndhw8N>xi>HC`1H} zF*I%fV~LePO&mzoppkfVSQ>CFNXtPZ@nBG+1nCvfNc z1T|40%>s=^5;})F?$Krh!;gcSiTt?QgZGo>H52ihcJ8L5_zC!wH zGQ-=+}?5k|BaMx&CBn;Dh2pF5`AAlJf@igz7kLFlf6iiMPKPvl>C7u=I?cIb}##- zSnUPNtHV)!X^ITVJHcUVjJCTXT-&pzF(CDh@+B7hpT!CZD;jhQdvxdFL4X zZ*qBOKCU67JI7-;No>f0r{dy<6ugVjLbaYpu6Ee1R;1D r>yP|~ymw+feM#iJD|hjxk6)t_>2WVRUA1kIC5|Uw^l5-FvI< zt?H`Uc3vT!Q#36BNTJ2R!8At|v;h>*EG7fLl}sWOIGPzo9k}E;VapI35!)P>{O&S9 z=&8U*5aBpD{E-TR9aSSzlyKG28nGT!SL+Bn!I3;t3ow!9=(6EW`kwAER5%PTWUJt? zW4WONV2LA^TR9B!90%hQ8OWnolD>eGjy=gbKUL!i!k%(8zA}pmoN}75GDtA8Bk)zu z52n!M={o$*nEowHam3_aQNwZiAU_d)raJ4395WO=iWus0J+2t9LR>77QMGv=&X_GJ z)0KwM`cTSjTrLDgz~bxWK*=vYYg zRd@1cQ4^~ z8CmBRW7c&L-=?hvr~NMv#cd>9Tseqsw5%`%*3;U;7{fehW}Y zyJyG3GU}Zj1w}M!js=%@#hi!m4K12$0;8jLu0OyU+E|nbMUEeeb^*+EteB^RsCg1+ z8>Y_|f#H^bI1^idE!Nkv(AxQt@G5PapS5V=K5gDLi6n8hP)n#eVu{u!`)JYU7fHnn z{4MOO*7$!7;(sJwSNwq0kVMwGJfZ)F^@+D!`6J={-zXRz9yktrT4l{dNJ1eBSs}ZrqgUqvnj-{ye5-E ze9fcc^}Is7?B%gl^n=sNizblk`$qaN-ZcqcE#5TM^(H8(9ZuM^A&o>7f(xSXB?O=^GC5gnn(m8Qd zi6CcRBc%nC*tE`UQNfhhQ-lQ?_0CA#pM>=rv`(84!=>fx9 zMZy$6Q24!Iw&bu*W6nj9tsH65<>~~TIW$gihH{*pa0cP1G5J(Z$bi!S`e{_TsI1PQ+Qia25s?(d5h7-A7*CDAy;6w)J)rR?w zU^2z=m3yQKNuivQ1~o7=urGm8(BTb0soB4Q=E_+I_Qf-D-U>0yZRaB#HB!93L?Gjd zxZj>FDw$p8prgUIkR_EywUeXg7U?Qda114*Q|baz>=l?f;f(#Ps!@6=sZEH=T-`}x z2$$8*svD)3Q4^g>#9BKUd%lkZF`cYoHO@0tifOhE*b7&poGgt+nH1Vkj*~cHWqxSf zHeX3>m}{L~_EUFVkiEM!)&8xjiq;*?L@e-r-b+AXSb%Q9zO-2;8<)7m&bE@$_+?s`L- z+V6{d2{#qjLy7CLss~QfA6|&y{Bb+3oSXAG=8QzIqeZmAe3JCh>R zNQwIYS89Sq&UmD~9qSb13ts2_W3}e=r1DmAng1Q>_`VukuQp@&t>M*sq~xZXv~01? z6gUK_@<_Z0>bpH8A!8u@OgmOru3LaF);e#Elu}+IBsO!nN1yM_Se!D$r1B;9(LH4B zRQ^1lLc11Et~g-+uH|~KqI4_now>hinEf;SyBdV!YNi|XdrcnKYhJzKeLPl;UfqvG zT<#%U(*rfT(_H*OtD_jn)Wf$Ky;Uy}Ut?b?VL% zJOJ`>lQ#$*kL}vEW-a#Y=bzg*2&>ILd#$#-ZudUEx@A@~B(PoS8&jGa1f7cM)*DJO zfq#2S1f1Ynt*BSc&kgPLxUOI_6~(3n=446X4=HTiC}gQiF(&NCOTDD@qaGOJ=<&Ed z_dr5GR~%nxo@<(j77@+Kl9r%tfb8=d4#bFFReI}DJlkYR+j>MI1rJ+FggerdT0Cij zj$sdUk@#hu*bgPGpeJJSAQ;kecUDLw*yF17WSLZYkL$EYHl5X+zLE2V^KVroFkQ=q zFfmxA?3DYMHr#+)ndGjgTU0Z`uc~g(` zmNK8Z{z=nI{)N||-?CEtu3a`=`4q#@i_0Qt=Q1U|xy+`TP)pc)N6zv@K#L8pn_wYz zzFx|v4JGkIF2+q0N}~ho(TPleO!TVA?wKjl=h)U=22+DB1dD7b>L#bplhq!THzDI ze8zyC@1U{F0X|IxN^4OgGvm`lqGUsj%tJ%+5NebbqekXFpGJeyT-3;X-=_&iX$ER! zzT?w`pfn9NT3PsJsQo^hNibM6wkFeutDNvx+E_Lgw$bjg7^tA`vR)YGxVJh8;A8sR zn&iOq&kQ{NflI@32VEc1l=5`#QcwH+;LK_L0)}8)Z{oIybX1n#P)`0kuI82iqCbhR zfL+6gelKD-;(f$z?DHTD9};#tVin>L;xoj59eXxZKz1ZPMb{zTMab@-Aj_`PkbglO zLdYSnAt#+xMhEimHI4pm1#abg-cXZ`A9M-S`qm;iLmS_k2VXig8>cdgfjS4j=`RqT z?hG*7+pOR&V4tnb^d*C`P-JG3s`+{8LMk2You}W!~URR+r>&Z?c%aW`3 z0vY|Wam4M7_`{#`$Q9g)mKTTQ_8E`tDYwr%9&Mh)M1J}aVK-+S%pezwrxjp9>;X@5b}VJRI@5KJhA}RktNqKke9-0~@Gc)r;Vyu~iw6LswMAz;3#? zsu0rXPgP^_CGEF;a`JZfc;3LrKM8BH9s`5LXb_5Y33Qj^=%bSy)9)M=k7Cd>ayi s=Z4|npJ>a`b?iP=?E6DuJhskfp@-ist{?jwd`dT0hr?BRuzJn^0N15iKmY&$ diff --git a/boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin b/boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin index b7fcd9dab24cf4eea06e4c40a6eca8b885ade3bf..fee2b669933de677ff8b5144ffa51771ce52f936 100755 GIT binary patch delta 3320 zcmYLMc~}%j7O$F~qlY6Lg9|dCGc;((2n>wzVwGVC?Hs^>8a2TKMFWTm8vVpC8pZ={ zujp=hBWsW(8`l_t)=x)2zR@-2*j*DQz?Zm5Hiw%yP6Nx#z8=lDfBfqA>eZ{N zSFc`GSBsZrJFm!E%P^i!mSF}L^9}eK#*0WUl>_BADg!U#+bBvIzWNlRHv@J84)HhC zcPSi3-VJ|WRDfZ0KKx4Rwey)MDWVSyN)dn@Mv?3O-CeDba@ru13zLKuMN5 z;WVPnmI$OHX>$_sPsA}N1Aj=~m{T=YG1};8wBPKLVZsH#%{;+O5f>JA^P_XV!gvAc znU{)Jk-)q}yqF}u?7%ss>g8YXw`9S58!qCT=Z9jvk(^(Uffw`NE!c1mvfC50|C6tWxNJl#oT(sk6AHp=LDb*JSvr&e0OWsB_2b|U?I7 z9QW`egO6s}4|_DODA&w_Sw-cXMu?>3p6PatD{p|7@m#!RsW+OLV#j1ENm~?KZ%hpM z!iSo~-x`r2r!y<5oRcEaBu2(SyV&GU03M1 zI1gr2B+$MaJW(}fx5@R*)_`xnSk5s51s?OT?ik7}7`Gh|CmEv|If*z&k?{U>N=BYL zhsjZU=((d-L{MdTe;Ot055qDcYQ)9H@l9fyuAD;`gP!EnmDn|Ip```3-Uy90?4SO8f3l5aBB;r4LgG|s)n_;xTJnc?^UU{SJfEm zRz-O6GzM_CmzX#%x6&U{m5=#AUIQp#?br)hZeJ4 zw@asg6D-vM@MPH*kmP|aHZRoePrcvQ z?sp0@wW*F00wJaD<8X0FlF9AvmqqA1vn9P;du=rrBSgwqc_r;wugy_pH^J!~+m{dL|JHDTc)U~ zM{vl)u!%N222WusrRi4}l%eifbx+!>xhYP#u_ChTuotCI?F1WK>c%=GOc{a%wN9_~ z`%3)jHigdb+w9M-Lx!wQ>1-hH1|B7kFVeA7q|0P763&VAB%jy7om8oN7)KHdsXW^e zYm2MILg_V}+}>;8zEQ>WBs^=147PlJ6&boaGg%{x1iy&&D(ftmFwGxh`?wbd*o{0! z_`*qFxhj&sJR{~KkglkaZqu`CyaAYS%U8{`jy}&Ov2q&{)M9ld(lKRBmE6QEo7Qn- zJ)*@+a`rhkmi@2qgFtQDyOnn<&spSO>%d3R{9oV4B%}N`zDP#PE1+DtVz!KKCLgZY zrI^-?=!^XHl^GcHRj=9be8Rt0Vaggdvcta7;itEuG>WjTMi?W1()+YTo=?HWi{KiX zgw4`7`7kN0=z=lym6!2ta;LH)F*r0>NZ%pp`**rEmPPv2N!0tJJ`Gu1)r@D5KvkbY z8f6;!WmV2oXGmuC>H3n9yeFs8kgpK93D^d_4>*6sJ}?G2cO>`8dEl8N1p^0xr-MEW z_{9j9`84lfxkG1&zcBU_k@NL5p+ndhw8N>xi>HC`1H} zF*I%fV~LePO&mzoppkfVSQ>CFNXtPZ@nBG+1nCvfNc z1T|40%>s=^5;})F?$Krh!;gcSiTt?QgZGo>H52ihcJ8L5_zC!wH zGQ-=+}?5k|BaMx&CBn;Dh2pF5`AAlJf@igz7kLFlf6iiMPKPvl>C7u=I?cIb}##- zSnUPNtHV)!X^ITVJHcUVjJCTXT-&pzF(CDh@+B7hpT!CZD;jhQdvxdFL4X zZ*qBOKCU67JI7-;No>f0r{dy<6ugVjLbaYpu6Ee1R;1D r>yP|~ymw+feM#iJD|hjxk6)t_>2WVRUA1kIC5|Uw^l5-FvI< zt?H`Uc3vT!Q#36BNTJ2R!8At|v;h>*EG7fLl}sWOIGPzo9k}E;VapI35!)P>{O&S9 z=&8U*5aBpD{E-TR9aSSzlyKG28nGT!SL+Bn!I3;t3ow!9=(6EW`kwAER5%PTWUJt? zW4WONV2LA^TR9B!90%hQ8OWnolD>eGjy=gbKUL!i!k%(8zA}pmoN}75GDtA8Bk)zu z52n!M={o$*nEowHam3_aQNwZiAU_d)raJ4395WO=iWus0J+2t9LR>77QMGv=&X_GJ z)0KwM`cTSjTrLDgz~bxWK*=vYYg zRd@1cQ4^~ z8CmBRW7c&L-=?hvr~NMv#cd>9Tseqsw5%`%*3;U;7{fehW}Y zyJyG3GU}Zj1w}M!js=%@#hi!m4K12$0;8jLu0OyU+E|nbMUEeeb^*+EteB^RsCg1+ z8>Y_|f#H^bI1^idE!Nkv(AxQt@G5PapS5V=K5gDLi6n8hP)n#eVu{u!`)JYU7fHnn z{4MOO*7$!7;(sJwSNwq0kVMwGJfZ)F^@+D!`6J={-zXRz9yktrT4l{dNJ1eBSs}ZrqgUqvnj-{ye5-E ze9fcc^}Is7?B%gl^n=sNizblk`$qaN-ZcqcE#5TM^(H8(9ZuM^A&o>7f(xSXB?O=^GC5gnn(m8Qd zi6CcRBc%nC*tE`UQNfhhQ-lQ?_0CA#pM>=rv`(84!=>fx9 zMZy$6Q24!Iw&bu*W6nj9tsH65<>~~TIW$gihH{*pa0cP1G5J(Z$bi!S`e{_TsI1PQ+Qia25s?(d5h7-A7*CDAy;6w)J)rR?w zU^2z=m3yQKNuivQ1~o7=urGm8(BTb0soB4Q=E_+I_Qf-D-U>0yZRaB#HB!93L?Gjd zxZj>FDw$p8prgUIkR_EywUeXg7U?Qda114*Q|baz>=l?f;f(#Ps!@6=sZEH=T-`}x z2$$8*svD)3Q4^g>#9BKUd%lkZF`cYoHO@0tifOhE*b7&poGgt+nH1Vkj*~cHWqxSf zHeX3>m}{L~_EUFVkiEM!)&8xjiq;*?L@e-r-b+AXSb%Q9zO-2;8<)7m&bE@$_+?s`L- z+V6{d2{#qjLy7CLss~QfA6|&y{Bb+3oSXAG=8QzIqeZmAe3JCh>R zNQwIYS89Sq&UmD~9qSb13ts2_W3}e=r1DmAng1Q>_`VukuQp@&t>M*sq~xZXv~01? z6gUK_@<_Z0>bpH8A!8u@OgmOru3LaF);e#Elu}+IBsO!nN1yM_Se!D$r1B;9(LH4B zRQ^1lLc11Et~g-+uH|~KqI4_now>hinEf;SyBdV!YNi|XdrcnKYhJzKeLPl;UfqvG zT<#%U(*rfT(_H*OtD_jn)Wf$Ky;Uy}Ut?b?VL% zJOJ`>lQ#$*kL}vEW-a#Y=bzg*2&>ILd#$#-ZudUEx@A@~B(PoS8&jGa1f7cM)*DJO zfq#2S1f1Ynt*BSc&kgPLxUOI_6~(3n=446X4=HTiC}gQiF(&NCOTDD@qaGOJ=<&Ed z_dr5GR~%nxo@<(j77@+Kl9r%tfb8=d4#bFFReI}DJlkYR+j>MI1rJ+FggerdT0Cij zj$sdUk@#hu*bgPGpeJJSAQ;kecUDLw*yF17WSLZYkL$EYHl5X+zLE2V^KVroFkQ=q zFfmxA?3DYMHr#+)ndGjgTU0Z`uc~g(` zmNK8Z{z=nI{)N||-?CEtu3a`=`4q#@i_0Qt=Q1U|xy+`TP)pc)N6zv@K#L8pn_wYz zzFx|v4JGkIF2+q0N}~ho(TPleO!TVA?wKjl=h)U=22+DB1dD7b>L#bplhq!THzDI ze8zyC@1U{F0X|IxN^4OgGvm`lqGUsj%tJ%+5NebbqekXFpGJeyT-3;X-=_&iX$ER! zzT?w`pfn9NT3PsJsQo^hNibM6wkFeutDNvx+E_Lgw$bjg7^tA`vR)YGxVJh8;A8sR zn&iOq&kQ{NflI@32VEc1l=5`#QcwH+;LK_L0)}8)Z{oIybX1n#P)`0kuI82iqCbhR zfL+6gelKD-;(f$z?DHTD9};#tVin>L;xoj59eXxZKz1ZPMb{zTMab@-Aj_`PkbglO zLdYSnAt#+xMhEimHI4pm1#abg-cXZ`A9M-S`qm;iLmS_k2VXig8>cdgfjS4j=`RqT z?hG*7+pOR&V4tnb^d*C`P-JG3s`+{8LMk2You}W!~URR+r>&Z?c%aW`3 z0vY|Wam4M7_`{#`$Q9g)mKTTQ_8E`tDYwr%9&Mh)M1J}aVK-+S%pezwrxjp9>;X@5b}VJRI@5KJhA}RktNqKke9-0~@Gc)r;Vyu~iw6LswMAz;3#? zsu0rXPgP^_CGEF;a`JZfc;3LrKM8BH9s`5LXb_5Y33Qj^=%bSy)9)M=k7Cd>ayi s=Z4|npJ>a`b?iP=?E6DuJhskfp@-ist{?jwd`dT0hr?BRuzJn^0N15iKmY&$ diff --git a/boards/holybro/durandal-v1/extras/px4_io-v2_default.bin b/boards/holybro/durandal-v1/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/holybro/pix32v5/extras/px4_io-v2_default.bin b/boards/holybro/pix32v5/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/mro/x21-777/extras/px4_io-v2_default.bin b/boards/mro/x21-777/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/mro/x21/extras/px4_io-v2_default.bin b/boards/mro/x21/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/px4/fmu-v2/extras/px4_io-v2_default.bin b/boards/px4/fmu-v2/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/px4/fmu-v3/extras/px4_io-v2_default.bin b/boards/px4/fmu-v3/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/px4/fmu-v4pro/extras/px4_io-v2_default.bin b/boards/px4/fmu-v4pro/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/px4/fmu-v5/extras/px4_io-v2_default.bin b/boards/px4/fmu-v5/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/px4/fmu-v5x/extras/px4_io-v2_default.bin b/boards/px4/fmu-v5x/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/px4/fmu-v6c/extras/px4_io-v2_default.bin b/boards/px4/fmu-v6c/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf diff --git a/boards/px4/fmu-v6x/extras/px4_io-v2_default.bin b/boards/px4/fmu-v6x/extras/px4_io-v2_default.bin index 5a0796406fc11c3476448b5284c5c519cb6a711d..145089ae0d7c21936cb60cc5c39501280771cf92 100755 GIT binary patch delta 3476 zcmYLMdsq`!7QZ)>$ApJGf(406;@~qpf>=RWB?K8s0!FmBT8lzaiPBZ5?JnQ9Re~=@ ztX22=25K#3*VeTH^ZB)@A75;(?RMMUB_dm`TJ72vDXSfjnjuKCXCnRfkKg>xJ?GqW z?>+b2nLF29vb!!>TPenWBxRVvN&Ien5#vmfLuJFWj!MOud^<%c!}FUFT?{A%yu^R3 zzDMEvq&56!8G4gHI_{wYi~R1GbUAM0U2$8nqU{|-$M9+K8jRyfo;DZ1K=x{n;R;?q zF;{_W`StqC80YgdnaU76hd+{>O5r)=it%&I@%z)XYQ>RLh~Ceio4=e2Pkay25>O;C zAHI-L<3y6SSPRd>#b4t@ero;|C5|NhOH%PlqO~V5Hecivq<=Ht@0}Wu3Ed)^(p1n~ z_?#%ulIx?-L=#GACnfgjYOko&{mDWJ4B2llS%v&a*foj-(`eWkEF2h)XjJMNI}FZ< zlTnSYg4g#WNQi$T6CR2o$7I445esP|5>$RHbo(!B<)o}Xgi;X1-0qX(P1b#8+P%X( z;VKqBCAmwt;s)};(wSIGzFV3cwZ`AmhnS}xTfyTEl2CL({S_?v35|5$lG{c0&~Bfh z1~G;zEc~5hEKA2LNaeDrxS1SU7ONJ)(`1f7Pe}W+N%%kHU&~VQ`y{Yz&n0~&;c5^}oO22*=b`~cq~ zH&5Loq&0(pIM8y?oiqeHhQ@AFR^ijI|=;2+`#Vm|{w?uo7ArT6C~g1TC#f z)?*g}#>h^_u?{Tqpk)!sUY)aX-N8HJI_DQ6GF}I0Y#M7^sm3A2(me%GCLndaadR*hO#pDj(Ggitv-aGR!m5DM?a#=`>`4^6Roy9 z+HKCeB!t(++v4-JT)Z{fz`3It#)%j`cfxGE5hgRFknED!$j)8{hHC6^_u2&%@<}go zl$dJ&Y}0c0oS~EB+?Y|3Ku0}{t7^<@m+MdG2fS9XoMQwE=EuV-VpH5~dCR{F^8K6=a&eKmJ*BDO&!J|NRufX_ojtY?Dp5L1xPIQ`y3fvC35 z`@(^6#ALwM$YE76; zZEP}mwscl!S6Z&*O5-wO#5{0VoFQ15ra z8E-SIyAjjYucUWc%lcL7r!{@ATc_U+o}c?+CS|XI^ojp9iwEAE7okswxw^ZBTdAz> zY2i*NH~0L(_6I995Lt_ti}KKYW-~m8Jy7TB7VhOj&5(0zoV${%UJ~cN{K!P5SG91G zPT5rnFM}me`Yqh$M^4Qq>n6JfYzJA%I?*j@O`5E#v#&RHtZsJ=;0W52UX$M5!f6#$ zk4|3-ldADoaxlT_Cgt+{l%86@x5{r9Wa{)9N(h9kb{&T|lq99QTm!NQeOH#GmuoM+ z#Kj1a@=YE|JHcbIEwQGHGVO%+*%oK)FrvEwxWvFXm&Et+rZmu0( zSP@w@*n?6sy1)moc3~Y7<_<%J=FhA0dn5cQ7KP65&G2W{Aj9k~>98QrD?Ca}SfXR+ z!bI^LB%BrLB(KN7om8oN7~2#UYI(6O))MD{@6AP=*wJg?ZmME>CXSgRgBIUM$Z)MI zjWx1J@QYZl%3lZr_K(I`KI?@5^~jwG-$3a*m`A>NF*W8ZkS?i_Zu!_-ybPFxm2X<0 z9G$^VVdWMisKrVL(lMpXMtM3@mf4xN7181aIXjMxWuJIA1*+Ox9rqk(&GPFyn4@TV z;@w5~@_*oiq;6dWJp0xy#@~~)_4SIFw-J4i?_8gXLH%HZ1;>z#iVBr5Y-D}ji=?$8 zA^aeWkCL!S`umr;wt=km}0pr$dqpm8WVWMhXVcqhW9881EgCvju}GpxHHI`e_luGs4_CkKaVO zfMKubvj%NLz^Tv{e7TQL0sj}c8TdZ%KH%@cJ|6h4FX!<&;9I_e!2`h8K_3Qu&6hu@ z0Pd;$~v#tZVv;q2bF#G4!8{QMAzwm8^fZwyJODZyD}Tg@uGg8#Z^0flez z<6ql`W54mCq{-l`18@DPedxP1$=^=i-L@aEAsO3q^EP}WZSOfGddqyB_cKiaZxK{k z1CnIX`@n?~|7wo;rUqUH`}_zz8^E)`C$-^TG}d0kySG0}O=xOG^tS9H+2~T)qLq*j z4j|>_6d%503l*C>Dxa*pIg3qW@$rE7{eXP3;v3Psosivm7?T^j6R?d8@6N^^GH=gR z97opfDZ)C^zGpgI^l$8$mli!Ti`BCZIEmK-sy1V%gB|heMuvKg7sA-_Y<(MM@fjp& zMac`F@p-S1+Cq7_bVE1IXj+4jrTME;8Yy yjc$XRCqhsR14o`AJ5Ih#*MQ>SuZrl#mxCTUJm&Fs<9oP?6gI`;HnP5H%l`mOL9ZeJ delta 3345 zcmYLL2~-qk68>v?hH0*Fj4a5A&d?$ta%D8&qLCxC%m9v}#M?*)moXTFan0lHQyJqy zt8s<>-FS@Xn&>`vSy!OfO$d*S#$@wym<0`%+IATgTe&}jyl+3LZ(?f0s``m5@% z|F8P%Kkl@vzHV2wtOnRbD}V!oxDz@6rqMiR4*s_>=`c-fWtf1_SxtmBBP~K&EnWz` z%fL7EROrvDp(gR|XC7+cCvoRElNwHn?J*lcbMho%SurzK2k;Cn)EB^fx?6t`mW##- z1sd2Wt}$K&m?b82)j^OX{xLP3fh77##;34Z+?S~j)a*V^*lpsOUoT`rWBy85g-AG} z82UUH2r)Est{(rTbFV>+m{9ad00hzd^U|S=>aCNwLQi-+F&-=Ox)XdV>5@$1kCrr* zE|S$bYGdT-NXkgfbfq;huwM=^{K3pfade+`Ej)t5DY4>oLGr-_%OL2r9 ziEwU0t8Yh$6#GOa-IIe3sw9^Tl2IlSctN`4y{K2yiu*x~h7#^}pBi4V?9FFgZ|0A` z4AO_RVE#tfLEoF73{mty^HU?1czgN?H)gRBEd)Ag!MVWm81fUA7%tP>3#`GHJSnw= zOQ`|rW13ZF!u(a2CBQ-2SQZ`l6I$lxhY^Xkmc`*R{JSh2PE%jm+VLr)&SIzKVxJ1A z;KSJ$NVyDkfV55Aw(uIj7P_=NnQ0hVPb128fkysRzm5=TF+EXU3}N&^`2)C0Z@p-S ziDJUyU;ro0T#^pk#fl|+0n)?=OZAYoROakKh5`u~ZZ$|{*aB>^{#G%z^jcMqRq|zo zcXIYh)TsTM=joi~c`H{m=t@45Nd{++ERM9qtk&5TKRWaiIjrFY{s!ut+TgE23L571 z757;!NoQSa(gv^+60{x&Zu2k7M-JDfK_z}vH8ooBf04o zpfhOais-uRIG?*)ZjxtZkd$9{JsWQmlvtbO>~NBt-Blo|7@NZ+EZ4%<@x`%@p9dp$ zI=JnF5dui7XXxoW1&^mKk)wp|n?nSaq;3NiT+JW(oV{)ab^ufyL6lw`>rbUDj zduV?uqv{U?H^2s*k)K1!#9ShsaFE3J`$-tn#TwV+K7Qm&XtfSG7E~kuvo8^O zvcQgfpN|u&=S8OM@aMr!U8|z%H0|}RMB428S04eDaXDIjS3(>l5xrmlf~N{lY2?x zZ2o=TM9WvttUF-2)pog0Ri%{Ui$7|a#?s*KX5nZ6(*uV6X0LmK&tUvLCWQF(cW|M- zgloAU!0xeB+}8$<6>0AkgE1-2>%Qg18B{3TRqu9lHy(N&cr3Q%FTT<&ED2cL(<~eg zSk$w%c&ml!4~K=aI(Tn>ejUPaH<{8b{H{bdg#ob=RzN;I@t?T#9ps^hZoX9 zx>NWCmKQ0!995T7%Sb*=PWxdzoD@#ien=+sAGFzo@8nr0@Tdqof*R;1sg+%*2U|NB zh*U8Q#_Xa!G70y(=XmqX8iUte8(k8ra+`qGR#1?Ic#bo{)f=#O|7O!kG=K&o?Z_pIJF=4u<_C6 zFM3JJ>8@lxiH{@F6B&#FN-Xoe?uVlh=EJ?&c$F#F*-YB=a{9QrPY>iTQBscl`9NZz zF}7D`hm0oi@x0nhq(HgaP7K^?ZmrtHRb+S0+(=mYoSJ`zkLI7aYkW1Wr|fs_&H3u< z28>0{ed69jUA9Yjv+k>`!vCYnxp1A%UQ@4O-@#iz{A^7+pm_KFug3XxVCi4;ty(wN-I`2WX*OA8J07Ki(3}6XUvg=Jcrh z8hx<#1bFHGSNb%H7nW|Ro-;Niy-LB?M zvh(oOy9|j25yKwDw-F79A0fStbP(I8XhiLJtjLtwm5@hw*Di$>;@#TW40MUc&07HO z(BoU8pq!rDvJWb0!PbJ{bss28cZSIBD%!YJmpIr?CjTve+|61%FZOx~>h_?n%%imN z;qtU?5x>|vgMkJLZ$<+Z$G`a+6Fp;8Ju%?cR6di3Lq7N4ed>vto3eWcJ-)LLwDkL( zlVAbW?3x4DXyL8|m`JO4Er4;fb5|n1wZGprGc#snDsSZNxQo8^Xtaimz`09!?WUFDq7X+T;F$TI-GYjNDMKk1!u3?7mXMW}nmWA=pn#o9f#kjV=~S z!9Y(5S<%N2{bCVRtmgIhz|x%dVfS@$P}su8eezqv&fY}WJfuP-Gg2wi45XRjzQ%)W zNJFcy4v7B)3U9|!%aJK?l5RM%AJ$QD?nl1S`RVuud_7OYx8a!OQ+ouoJo?)I0C;wH A(*OVf From b87c5285e285ecd58dc06b77f00358f35310eee6 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 15 Feb 2024 13:55:18 +0100 Subject: [PATCH 071/652] battery: weigh voltage based estimate more when it's low This is a minimal change to make it harder to crash a vehicle with an empty battery if the capacity was set wrong. The disadvantage is that the state of charge estimate will fluctuate more under load. We need better documentation and improvements to the estimation. --- src/lib/battery/battery.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index 8c833af1e024..f3a66fc0ed3c 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -239,10 +239,10 @@ float Battery::calculateStateOfChargeVoltageBased(const float voltage_v, const f void Battery::estimateStateOfCharge() { // choose which quantity we're using for final reporting - if (_params.capacity > 0.f && _battery_initialized) { + if ((_params.capacity > 0.f) && _battery_initialized) { // if battery capacity is known, fuse voltage measurement with used capacity // The lower the voltage the more adjust the estimate with it to avoid deep discharge - const float weight_v = 3e-4f * (1 - _state_of_charge_volt_based); + const float weight_v = 3e-2f * (1 - _state_of_charge_volt_based); _state_of_charge = (1 - weight_v) * _state_of_charge + weight_v * _state_of_charge_volt_based; // directly apply current capacity slope calculated using current _state_of_charge -= _discharged_mah_loop / _params.capacity; From 4c2112f46b017b581a037cf35027af15151f70d0 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Tue, 2 Apr 2024 16:12:21 -0700 Subject: [PATCH 072/652] boards/modalai/voxl2: added device specifier to gps start line --- boards/modalai/voxl2/target/voxl-px4-start | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/modalai/voxl2/target/voxl-px4-start b/boards/modalai/voxl2/target/voxl-px4-start index 4b0c132cfcfc..c994e0118a02 100755 --- a/boards/modalai/voxl2/target/voxl-px4-start +++ b/boards/modalai/voxl2/target/voxl-px4-start @@ -95,7 +95,7 @@ if [ "$GPS" != "NONE" ]; then gps start -d /dev/ttyHS2 # On M0054 and M0104 the GPS driver runs on SLPI DSP else - qshell gps start + qshell gps start -d 6 fi fi From 8ceeda730d12583a8709b54f07b7c9ffbe67a9b8 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 3 Apr 2024 11:14:30 +1100 Subject: [PATCH 073/652] Jenkinsfile - dual-deploy uorb graph and failsafe to vitepress (#22943) --- Jenkinsfile | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 0b0c8d1870b3..3a5947369e84 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -171,9 +171,11 @@ pipeline { sh('cp airframes.md PX4-user_guide/en/airframes/airframe_reference.md') sh('cp parameters.md PX4-user_guide/en/advanced_config/parameter_reference.md') sh('cp -R modules/*.md PX4-user_guide/en/modules/') - sh('cp -R graph_*.json PX4-user_guide/.vuepress/public/en/middleware/') + sh('cp -R graph_*.json PX4-user_guide/.vuepress/public/en/middleware/') // vuepress + sh('cp -R graph_*.json PX4-user_guide/public/middleware/') // vitepress sh('cp -R msg_docs/*.md PX4-user_guide/en/msg_docs/') - sh('cp -R failsafe_sim/* PX4-user_guide/.vuepress/public/en/config/failsafe') + sh('cp -R failsafe_sim/* PX4-user_guide/.vuepress/public/en/config/failsafe') // vuepress + sh('cp -R failsafe_sim/* PX4-user_guide/public/config/failsafe') // vitepress sh('cd PX4-user_guide; git status; git add .; git commit -a -m "Update PX4 Firmware metadata `date`" || true') sh('cd PX4-user_guide; git push origin main || true') sh('rm -rf PX4-user_guide') From 047e900c2a7655eaa3644a74942f89d35188bdc3 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Thu, 4 Apr 2024 15:07:37 +0200 Subject: [PATCH 074/652] px4io: Fix dependency problem caused by #22957 --- src/drivers/px4io/Kconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/px4io/Kconfig b/src/drivers/px4io/Kconfig index 16b114948578..052f088d701f 100644 --- a/src/drivers/px4io/Kconfig +++ b/src/drivers/px4io/Kconfig @@ -1,6 +1,6 @@ menuconfig DRIVERS_PX4IO bool "px4io" default n - depends on platform_nuttx + depends on PLATFORM_NUTTX ---help--- Enable support for px4io From 0a867b5d1de6040a93d9fdf15e226efa336ed5cf Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Thu, 4 Apr 2024 09:07:46 -0700 Subject: [PATCH 075/652] Serial: removed the validateBaudrate function from nuttx and posix platforms and just send out a warning it baudrate is non-standard (#22969) - Fix some Qurt platform build issues uncovered when changing the posix version of SerialImpl --- boards/modalai/fc-v2/default.px4board | 1 + boards/modalai/fc-v2/scripts/run_docker.sh | 5 + boards/modalai/voxl2/default.px4board | 1 + platforms/nuttx/src/px4/common/SerialImpl.cpp | 27 +--- .../src/px4/common/include/SerialImpl.hpp | 1 - platforms/posix/include/SerialImpl.hpp | 1 - platforms/posix/src/px4/common/SerialImpl.cpp | 27 +--- platforms/qurt/cmake/px4_impl_os.cmake | 6 - platforms/qurt/include/crc32.h | 83 +++++++++++ platforms/qurt/include/queue.h | 134 ++++++++++++++++++ platforms/qurt/include/system_config.h | 65 +++++++++ 11 files changed, 295 insertions(+), 56 deletions(-) create mode 100755 boards/modalai/fc-v2/scripts/run_docker.sh create mode 100644 platforms/qurt/include/crc32.h create mode 100644 platforms/qurt/include/queue.h create mode 100644 platforms/qurt/include/system_config.h diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index c4e7d3649597..6fa7ebabaf02 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -24,6 +24,7 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_CRSF_RC=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_COMMON_TELEMETRY=y CONFIG_MODULES_AIRSPEED_SELECTOR=y diff --git a/boards/modalai/fc-v2/scripts/run_docker.sh b/boards/modalai/fc-v2/scripts/run_docker.sh new file mode 100755 index 000000000000..bcc39c6dcd59 --- /dev/null +++ b/boards/modalai/fc-v2/scripts/run_docker.sh @@ -0,0 +1,5 @@ +#!/bin/bash + +# Run this from the px4 project top level directory +docker run -it --rm --privileged -v `pwd`:/usr/local/workspace px4io/px4-dev-nuttx-focal:2022-08-12 + diff --git a/boards/modalai/voxl2/default.px4board b/boards/modalai/voxl2/default.px4board index 8ac31695723f..20860e3fce47 100644 --- a/boards/modalai/voxl2/default.px4board +++ b/boards/modalai/voxl2/default.px4board @@ -6,6 +6,7 @@ CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_QSHELL_POSIX=y +CONFIG_DRIVERS_RC_CRSF_RC=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_VOXL2_IO=y CONFIG_MODULES_COMMANDER=y diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index 2a09b2ae3521..1094c78cc2e9 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -68,28 +68,11 @@ SerialImpl::~SerialImpl() } } -bool SerialImpl::validateBaudrate(uint32_t baudrate) -{ - return ((baudrate == 9600) || - (baudrate == 19200) || - (baudrate == 38400) || - (baudrate == 57600) || - (baudrate == 115200) || - (baudrate == 230400) || - (baudrate == 460800) || - (baudrate == 921600)); -} - bool SerialImpl::configure() { /* process baud rate */ int speed; - if (! validateBaudrate(_baudrate)) { - PX4_ERR("ERR: unknown baudrate: %lu", _baudrate); - return false; - } - switch (_baudrate) { case 9600: speed = B9600; break; @@ -116,8 +99,9 @@ bool SerialImpl::configure() case 921600: speed = B921600; break; default: - PX4_ERR("ERR: unknown baudrate: %lu", _baudrate); - return false; + speed = _baudrate; + PX4_WARN("Using non-standard baudrate: %lu", _baudrate); + break; } struct termios uart_config; @@ -374,11 +358,6 @@ uint32_t SerialImpl::getBaudrate() const bool SerialImpl::setBaudrate(uint32_t baudrate) { - if (! validateBaudrate(baudrate)) { - PX4_ERR("ERR: invalid baudrate: %lu", baudrate); - return false; - } - // check if already configured if ((baudrate == _baudrate) && _open) { return true; diff --git a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp index f92deba5ed3e..1253dfecef71 100644 --- a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp +++ b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp @@ -109,7 +109,6 @@ class SerialImpl StopBits _stopbits{StopBits::One}; FlowControl _flowcontrol{FlowControl::Disabled}; - bool validateBaudrate(uint32_t baudrate); bool configure(); bool _single_wire_mode{false}; diff --git a/platforms/posix/include/SerialImpl.hpp b/platforms/posix/include/SerialImpl.hpp index f92deba5ed3e..1253dfecef71 100644 --- a/platforms/posix/include/SerialImpl.hpp +++ b/platforms/posix/include/SerialImpl.hpp @@ -109,7 +109,6 @@ class SerialImpl StopBits _stopbits{StopBits::One}; FlowControl _flowcontrol{FlowControl::Disabled}; - bool validateBaudrate(uint32_t baudrate); bool configure(); bool _single_wire_mode{false}; diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 4c84e0078feb..248e414cc72f 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -66,28 +66,11 @@ SerialImpl::~SerialImpl() } } -bool SerialImpl::validateBaudrate(uint32_t baudrate) -{ - return ((baudrate == 9600) || - (baudrate == 19200) || - (baudrate == 38400) || - (baudrate == 57600) || - (baudrate == 115200) || - (baudrate == 230400) || - (baudrate == 460800) || - (baudrate == 921600)); -} - bool SerialImpl::configure() { /* process baud rate */ int speed; - if (! validateBaudrate(_baudrate)) { - PX4_ERR("ERR: unknown baudrate: %u", _baudrate); - return false; - } - switch (_baudrate) { case 9600: speed = B9600; break; @@ -114,8 +97,9 @@ bool SerialImpl::configure() case 921600: speed = B921600; break; default: - PX4_ERR("ERR: unknown baudrate: %d", _baudrate); - return false; + speed = _baudrate; + PX4_WARN("Using non-standard baudrate: %u", _baudrate); + break; } struct termios uart_config; @@ -366,11 +350,6 @@ uint32_t SerialImpl::getBaudrate() const bool SerialImpl::setBaudrate(uint32_t baudrate) { - if (! validateBaudrate(baudrate)) { - PX4_ERR("ERR: invalid baudrate: %u", baudrate); - return false; - } - // check if already configured if ((baudrate == _baudrate) && _open) { return true; diff --git a/platforms/qurt/cmake/px4_impl_os.cmake b/platforms/qurt/cmake/px4_impl_os.cmake index e0c2dbaba17f..dcc28e176a2e 100644 --- a/platforms/qurt/cmake/px4_impl_os.cmake +++ b/platforms/qurt/cmake/px4_impl_os.cmake @@ -124,13 +124,7 @@ endfunction() # function(px4_os_add_flags) - set(DSPAL_ROOT platforms/qurt/dspal) include_directories( - ${DSPAL_ROOT}/include - ${DSPAL_ROOT}/sys - ${DSPAL_ROOT}/sys/sys - - platforms/posix/include platforms/qurt/include ) diff --git a/platforms/qurt/include/crc32.h b/platforms/qurt/include/crc32.h new file mode 100644 index 000000000000..34e080b1c2e3 --- /dev/null +++ b/platforms/qurt/include/crc32.h @@ -0,0 +1,83 @@ +/**************************************************************************** + * include/crc.h + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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 __INCLUDE_CRC32_H +#define __INCLUDE_CRC32_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: crc32part + * + * Description: + * Continue CRC calculation on a part of the buffer. + * + ****************************************************************************/ + +EXTERN uint32_t crc32part(const uint8_t *src, size_t len, + uint32_t crc32val); + +/**************************************************************************** + * Name: crc32 + * + * Description: + * Return a 32-bit CRC of the contents of the 'src' buffer, length 'len' + * + ****************************************************************************/ + +EXTERN uint32_t crc32(const uint8_t *src, size_t len); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_CRC32_H */ diff --git a/platforms/qurt/include/queue.h b/platforms/qurt/include/queue.h new file mode 100644 index 000000000000..d6315ca1723c --- /dev/null +++ b/platforms/qurt/include/queue.h @@ -0,0 +1,134 @@ +/************************************************************************ + * include/queue.h + * + * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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 __INCLUDE_QUEUE_H +#define __INCLUDE_QUEUE_H + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#ifdef __cplusplus +#include // NULL +#else +#include // NULL +#endif + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +#define sq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0) +#define dq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0) + +#define sq_next(p) ((p)->flink) +#define dq_next(p) ((p)->flink) +#define dq_prev(p) ((p)->blink) + +#define sq_empty(q) ((q)->head == NULL) +#define dq_empty(q) ((q)->head == NULL) + +#define sq_peek(q) ((q)->head) +#define dq_peek(q) ((q)->head) + +// Required for Linux +#define FAR + +/************************************************************************ + * Global Type Declarations + ************************************************************************/ + +struct sq_entry_s { + FAR struct sq_entry_s *flink; +}; +typedef struct sq_entry_s sq_entry_t; + +struct dq_entry_s { + FAR struct dq_entry_s *flink; + FAR struct dq_entry_s *blink; +}; +typedef struct dq_entry_s dq_entry_t; + +struct sq_queue_s { + FAR sq_entry_t *head; + FAR sq_entry_t *tail; +}; +typedef struct sq_queue_s sq_queue_t; + +struct dq_queue_s { + FAR dq_entry_t *head; + FAR dq_entry_t *tail; +}; +typedef struct dq_queue_s dq_queue_t; + +/************************************************************************ + * Global Function Prototypes + ************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +EXTERN void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue); +EXTERN void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue); +EXTERN void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue); +EXTERN void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue); +EXTERN void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node, + sq_queue_t *queue); +EXTERN void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node, + dq_queue_t *queue); +EXTERN void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node, + dq_queue_t *queue); + +EXTERN FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue); +EXTERN void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue); +EXTERN void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue); +EXTERN FAR sq_entry_t *sq_remlast(sq_queue_t *queue); +EXTERN FAR dq_entry_t *dq_remlast(dq_queue_t *queue); +EXTERN FAR sq_entry_t *sq_remfirst(sq_queue_t *queue); +EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_QUEUE_H_ */ + diff --git a/platforms/qurt/include/system_config.h b/platforms/qurt/include/system_config.h new file mode 100644 index 000000000000..7d3162cbe0ce --- /dev/null +++ b/platforms/qurt/include/system_config.h @@ -0,0 +1,65 @@ +/**************************************************************************** + * + * Copyright (c) 2017 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file system_config.h + * + * Definitions used by all SITL and Linux targets + */ + +#pragma once + +#define PX4_CPU_UUID_BYTE_LENGTH 16 +#define PX4_CPU_UUID_WORD32_LENGTH 4 + +#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH +#define PX4_CPU_UUID_WORD32_UNIQUE_H 2 /* Most significant digits change the least */ +#define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */ +#define PX4_CPU_UUID_WORD32_UNIQUE_L 0 /* Least significant digits change the most */ +#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1) +#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1) + +#define BOARD_OVERRIDE_CPU_VERSION (-1) +#define board_mcu_version(rev, revstr, errata) BOARD_OVERRIDE_CPU_VERSION + +#define BOARD_HAS_NO_UUID + +#define CONFIG_NFILE_STREAMS 1 +#define CONFIG_SCHED_WORKQUEUE 1 +#define CONFIG_SCHED_HPWORK 1 +#define CONFIG_SCHED_LPWORK 1 + +/** time in ms between checks for work in work queues **/ +#define CONFIG_SCHED_WORKPERIOD 50000 + +#define CONFIG_SCHED_INSTRUMENTATION 1 From de9f3a32681cb458db9e509d4e0e17c4c8f08a18 Mon Sep 17 00:00:00 2001 From: henrykotze Date: Wed, 3 Apr 2024 11:33:32 +0200 Subject: [PATCH 076/652] gz-bridge: use correct prev_timestamp for dt calc - with the addition of the navsat plugin in PR#22638, the callback would reassign the previous timestamp used in the calculations of the angular_velocity causing derivative type noise in the groundtruth measurements --- src/modules/simulation/gz_bridge/GZBridge.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 2821213272c2..56c6d028a0cd 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -719,8 +719,6 @@ void GZBridge::navSatCallback(const gz::msgs::NavSat &nav_sat) updateClock(nav_sat.header().stamp().sec(), nav_sat.header().stamp().nsec()); } - _timestamp_prev = time_us; - // initialize gps position if (!_pos_ref.isInitialized()) { _pos_ref.initReference(nav_sat.latitude_deg(), nav_sat.longitude_deg(), hrt_absolute_time()); From 7fbbdc31e8a61525777d8edcf8f339a738abf138 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Thu, 4 Apr 2024 17:08:24 -0800 Subject: [PATCH 077/652] Memsic MMC5983MA magnetometer driver --- src/drivers/drv_sensor.h | 1 + src/drivers/magnetometer/CMakeLists.txt | 1 + src/drivers/magnetometer/Kconfig | 1 + src/drivers/magnetometer/memsic/Kconfig | 3 + .../memsic/mmc5983ma/CMakeLists.txt | 44 ++++ .../magnetometer/memsic/mmc5983ma/Kconfig | 5 + .../memsic/mmc5983ma/mmc5983ma.cpp | 215 ++++++++++++++++++ .../magnetometer/memsic/mmc5983ma/mmc5983ma.h | 104 +++++++++ .../memsic/mmc5983ma/mmc5983ma_i2c.cpp | 97 ++++++++ .../memsic/mmc5983ma/mmc5983ma_main.cpp | 117 ++++++++++ 10 files changed, 588 insertions(+) create mode 100644 src/drivers/magnetometer/memsic/Kconfig create mode 100644 src/drivers/magnetometer/memsic/mmc5983ma/CMakeLists.txt create mode 100644 src/drivers/magnetometer/memsic/mmc5983ma/Kconfig create mode 100644 src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.cpp create mode 100644 src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.h create mode 100644 src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_i2c.cpp create mode 100644 src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_main.cpp diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 549b7313c19f..fc6265ba4b60 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -63,6 +63,7 @@ #define DRV_MAG_DEVTYPE_IST8308 0x0B #define DRV_MAG_DEVTYPE_LIS2MDL 0x0C +#define DRV_MAG_DEVTYPE_MMC5983MA 0x0D #define DRV_IMU_DEVTYPE_LSM303D 0x11 diff --git a/src/drivers/magnetometer/CMakeLists.txt b/src/drivers/magnetometer/CMakeLists.txt index 7255574717b0..6eb5bbe49262 100644 --- a/src/drivers/magnetometer/CMakeLists.txt +++ b/src/drivers/magnetometer/CMakeLists.txt @@ -39,5 +39,6 @@ add_subdirectory(isentek) add_subdirectory(lis2mdl) add_subdirectory(lis3mdl) add_subdirectory(lsm303agr) +add_subdirectory(memsic) add_subdirectory(rm3100) add_subdirectory(vtrantech) diff --git a/src/drivers/magnetometer/Kconfig b/src/drivers/magnetometer/Kconfig index 12859150806c..99bb90f54e2c 100644 --- a/src/drivers/magnetometer/Kconfig +++ b/src/drivers/magnetometer/Kconfig @@ -14,6 +14,7 @@ menu "Magnetometer" select DRIVERS_MAGNETOMETER_LSM303AGR select DRIVERS_MAGNETOMETER_RM3100 select DRIVERS_MAGNETOMETER_VTRANTECH_VCM1193L + select DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA ---help--- Enable default set of magnetometer drivers rsource "*/Kconfig" diff --git a/src/drivers/magnetometer/memsic/Kconfig b/src/drivers/magnetometer/memsic/Kconfig new file mode 100644 index 000000000000..22e5aa4175e5 --- /dev/null +++ b/src/drivers/magnetometer/memsic/Kconfig @@ -0,0 +1,3 @@ +menu "Memsic" + rsource "*/Kconfig" +endmenu diff --git a/src/drivers/magnetometer/memsic/mmc5983ma/CMakeLists.txt b/src/drivers/magnetometer/memsic/mmc5983ma/CMakeLists.txt new file mode 100644 index 000000000000..3bba9619d707 --- /dev/null +++ b/src/drivers/magnetometer/memsic/mmc5983ma/CMakeLists.txt @@ -0,0 +1,44 @@ +############################################################################ +# +# 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_module( + MODULE drivers__magnetometer__memsic__mmc5983ma + MAIN mmc5983ma + COMPILE_FLAGS + SRCS + mmc5983ma_i2c.cpp + mmc5983ma_main.cpp + mmc5983ma.cpp + DEPENDS + drivers_magnetometer + px4_work_queue + ) diff --git a/src/drivers/magnetometer/memsic/mmc5983ma/Kconfig b/src/drivers/magnetometer/memsic/mmc5983ma/Kconfig new file mode 100644 index 000000000000..f3d1f3145793 --- /dev/null +++ b/src/drivers/magnetometer/memsic/mmc5983ma/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA + bool "mmc5983ma" + default n + ---help--- + Enable support for mmc5983ma diff --git a/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.cpp b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.cpp new file mode 100644 index 000000000000..11ec0ea7de19 --- /dev/null +++ b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.cpp @@ -0,0 +1,215 @@ +/**************************************************************************** + * + * 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 "mmc5983ma.h" + +using namespace time_literals; + +MMC5983MA::MMC5983MA(device::Device *interface, const I2CSPIDriverConfig &config) : + I2CSPIDriver(config), + _interface(interface), + _px4_mag(interface->get_device_id(), config.rotation), + _sample_count(perf_alloc(PC_COUNT, "mmc5983ma_read")), + _comms_errors(perf_alloc(PC_COUNT, "mmc5983ma_comms_errors")) +{} + +MMC5983MA::~MMC5983MA() +{ + perf_free(_sample_count); + perf_free(_comms_errors); + delete _interface; +} + +int MMC5983MA::init() +{ + // Start with a reset of the chip + write_register(MMC5983MA_ADDR_CTRL_REG2, MMC5983MA_CTRL_REG1_SW_RESET); + px4_usleep(20_ms); + + // Set measurement BW to 200HZ + write_register(MMC5983MA_ADDR_CTRL_REG1, MMC5983MA_CTRL_REG1_BW_200HZ); + + ScheduleNow(); + + return PX4_OK; +} + +void MMC5983MA::RunImpl() +{ + // The measure/collect loop uses the set/reset functionality of the chip to eliminate temperature related bias + // by reversing the polarity of the sensing element and taking the difference of the two measurements to eliminate + // the offset and then dividing by 2 to arrive at the true value of the field measurement. + // + // The measurement will contain not only the sensors response to the external magnetic field, H, but also the Offset. + // + // Output1 = +H + Offset + // Output2 = -H + Offset + // Measurment = (Output1 - Output2) / 2 + // + // Please refer to Page 18 of the datasheet + // https://www.memsic.com/Public/Uploads/uploadfile/files/20220119/MMC5983MADatasheetRevA.pdf + + switch (_state) { + case State::Measure: { + + uint8_t set_reset_flag = _sample_index == 0 ? MMC5983MA_CTRL_REG0_SET : MMC5983MA_CTRL_REG0_RESET; + write_register(MMC5983MA_ADDR_CTRL_REG0, MMC5983MA_CTRL_REG0_TM_M | set_reset_flag); + + _collect_retries = 0; + _state = State::Collect; + + // 200Hz BW is 4ms measurement time + ScheduleDelayed(5_ms); + return; + } + + case State::Collect: { + + uint8_t status = read_register(MMC5983MA_ADDR_STATUS_REG); + + if (status & MMC5983MA_STATUS_REG_MEAS_M_DONE) { + SensorData data = {}; + + if (read_register_block(&data) != PX4_OK) { + PX4_DEBUG("read failed"); + perf_count(_comms_errors); + _state = State::Measure; + _sample_index = 0; + ScheduleDelayed(100_ms); + return; + } + + // Measurement available + _measurements[_sample_index] = data; + _sample_index++; + + if (_sample_index > 1) { + publish_data(); + _sample_index = 0; + perf_count(_sample_count); + } + + _state = State::Measure; + + // Immediately schedule next measurement + ScheduleNow(); + return; + + } else { + PX4_DEBUG("not ready"); + perf_count(_comms_errors); + _collect_retries++; + _state = _collect_retries > 3 ? State::Measure : State::Collect; + ScheduleDelayed(5_ms); + return; + } + } + } // end switch/case +} + +void MMC5983MA::publish_data() +{ + uint32_t xraw_1 = (_measurements[0].xout0 << 10) | (_measurements[0].xout1 << 2) | (( + _measurements[0].xyzout2 & 0b11000000) >> 6); + uint32_t yraw_1 = (_measurements[0].yout0 << 10) | (_measurements[0].yout1 << 2) | (( + _measurements[0].xyzout2 & 0b00110000) >> 4); + uint32_t zraw_1 = (_measurements[0].zout0 << 10) | (_measurements[0].zout1 << 2) | (( + _measurements[0].xyzout2 & 0b00001100) >> 2); + + uint32_t xraw_2 = (_measurements[1].xout0 << 10) | (_measurements[1].xout1 << 2) | (( + _measurements[1].xyzout2 & 0b11000000) >> 6); + uint32_t yraw_2 = (_measurements[1].yout0 << 10) | (_measurements[1].yout1 << 2) | (( + _measurements[1].xyzout2 & 0b00110000) >> 4); + uint32_t zraw_2 = (_measurements[1].zout0 << 10) | (_measurements[1].zout1 << 2) | (( + _measurements[1].xyzout2 & 0b00001100) >> 2); + + // NOTE: Temperature conversions did not work + // float trawf = float(_measurements[0].tout + _measurements[1].tout) / 2.f; + // float temp_c = trawf * 0.8f - 75.f; + // _px4_mag.set_temperature(temp_c); + + // +/- 8 Gauss full scale range + // 18-bit mode scaling factor: 0.0625 mG/LSB + float x1 = -8.f + (float(xraw_1) * 0.0625f) / 1e3f; + float x2 = -8.f + (float(xraw_2) * 0.0625f) / 1e3f; + float y1 = -8.f + (float(yraw_1) * 0.0625f) / 1e3f; + float y2 = -8.f + (float(yraw_2) * 0.0625f) / 1e3f; + float z1 = -8.f + (float(zraw_1) * 0.0625f) / 1e3f; + float z2 = -8.f + (float(zraw_2) * 0.0625f) / 1e3f; + + // Remove the offset from the measurements (SET/RESET) + float x = (x1 - x2) / 2.f; + float y = -1.f * (y1 - y2) / 2.f; // Y axis is inverted to convert from LH to RH + float z = (z1 - z2) / 2.f; + + _px4_mag.update(hrt_absolute_time(), x, y, z); + _px4_mag.set_error_count(perf_event_count(_comms_errors)); +} + +uint8_t MMC5983MA::read_register_block(SensorData *data) +{ + uint8_t reg = MMC5983MA_ADDR_XOUT_0; + + if (_interface->read(reg, data, sizeof(SensorData)) != PX4_OK) { + perf_count(_comms_errors); + + return PX4_ERROR; + } + + return PX4_OK; +} + +uint8_t MMC5983MA::read_register(uint8_t reg) +{ + uint8_t value = 0; + + if (_interface->read(reg, &value, sizeof(value)) != PX4_OK) { + perf_count(_comms_errors); + } + + return value; +} + +void MMC5983MA::write_register(uint8_t reg, uint8_t value) +{ + if (_interface->write(reg, &value, sizeof(value)) != PX4_OK) { + perf_count(_comms_errors); + } +} + +void MMC5983MA::print_status() +{ + I2CSPIDriverBase::print_status(); + perf_print_counter(_sample_count); + perf_print_counter(_comms_errors); +} diff --git a/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.h b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.h new file mode 100644 index 000000000000..afa526dd1a60 --- /dev/null +++ b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma.h @@ -0,0 +1,104 @@ +/**************************************************************************** + * + * 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 + +// MMC5983MA Registers +#define MMC5983MA_ADDR_XOUT_0 0x00 +#define MMC5983MA_ADDR_STATUS_REG 0x08 +#define MMC5983MA_ADDR_CTRL_REG0 0x09 +#define MMC5983MA_ADDR_CTRL_REG1 0x0A +#define MMC5983MA_ADDR_CTRL_REG2 0x0B +#define MMC5983MA_ADDR_PRODUCT_ID 0x2F +// MMC5983MA Definitions +#define MMC5983MA_PRODUCT_ID 0x30 +#define MMC5983MA_STATUS_REG_MEAS_M_DONE (1 << 0) +#define MMC5983MA_CTRL_REG0_TM_M (1 << 0) +#define MMC5983MA_CTRL_REG0_SET (1 << 3) +#define MMC5983MA_CTRL_REG0_RESET (1 << 4) + +#define MMC5983MA_CTRL_REG1_BW_200HZ (0b00000001) +#define MMC5983MA_CTRL_REG1_SW_RESET (1 << 7) + +extern device::Device *MMC5983MA_I2C_interface(const I2CSPIDriverConfig &config); + +class MMC5983MA : public I2CSPIDriver +{ +public: + MMC5983MA(device::Device *interface, const I2CSPIDriverConfig &config); + virtual ~MMC5983MA(); + + struct SensorData { + uint8_t xout0; + uint8_t xout1; + uint8_t yout0; + uint8_t yout1; + uint8_t zout0; + uint8_t zout1; + uint8_t xyzout2; + uint8_t tout; + }; + + enum class State { + Measure, + Collect, + }; + + static I2CSPIDriverBase *instantiate(const I2CSPIDriverConfig &config, int runtime_instance); + static void print_usage(); + + int init(); + void print_status() override; + + void RunImpl(); + +private: + void publish_data(); + + // Read data + uint8_t read_register_block(SensorData *data); + uint8_t read_register(uint8_t reg); + void write_register(uint8_t reg, uint8_t value); + + device::Device *_interface; + PX4Magnetometer _px4_mag; + State _state = State::Measure; + int _sample_index = 0; + int _collect_retries = 0; + SensorData _measurements[2]; + perf_counter_t _sample_count; + perf_counter_t _comms_errors; +}; diff --git a/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_i2c.cpp b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_i2c.cpp new file mode 100644 index 000000000000..294fcb27af67 --- /dev/null +++ b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_i2c.cpp @@ -0,0 +1,97 @@ +/**************************************************************************** + * + * 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 "mmc5983ma.h" +#include + +class MMC5983MA_I2C : public device::I2C +{ +public: + MMC5983MA_I2C(const I2CSPIDriverConfig &config); + virtual ~MMC5983MA_I2C() = default; + + virtual int read(unsigned address, void *data, unsigned count) override; + virtual int write(unsigned address, void *data, unsigned count) override; + +protected: + virtual int probe(); +}; + +MMC5983MA_I2C::MMC5983MA_I2C(const I2CSPIDriverConfig &config) : + I2C(config) +{ +} + +int MMC5983MA_I2C::probe() +{ + uint8_t data = 0; + + if (read(MMC5983MA_ADDR_PRODUCT_ID, &data, 1)) { + DEVICE_DEBUG("read_reg fail"); + return -EIO; + } + + if (data != MMC5983MA_PRODUCT_ID) { + DEVICE_DEBUG("MMC5983MA bad ID: %02x", data); + return -EIO; + } + + _retries = 1; + + return OK; +} + +int MMC5983MA_I2C::read(unsigned address, void *data, unsigned count) +{ + uint8_t cmd = address; + return transfer(&cmd, 1, (uint8_t *)data, count); +} + +int MMC5983MA_I2C::write(unsigned address, void *data, unsigned count) +{ + uint8_t buf[32]; + + if (sizeof(buf) < (count + 1)) { + return -EIO; + } + + buf[0] = address; + memcpy(&buf[1], data, count); + + return transfer(&buf[0], count + 1, nullptr, 0); +} + +device::Device *MMC5983MA_I2C_interface(const I2CSPIDriverConfig &config) +{ + return new MMC5983MA_I2C(config); +} diff --git a/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_main.cpp b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_main.cpp new file mode 100644 index 000000000000..b8d6e81e3471 --- /dev/null +++ b/src/drivers/magnetometer/memsic/mmc5983ma/mmc5983ma_main.cpp @@ -0,0 +1,117 @@ +/**************************************************************************** + * + * 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 "mmc5983ma.h" +#include + +I2CSPIDriverBase *MMC5983MA::instantiate(const I2CSPIDriverConfig &config, int runtime_instance) +{ + device::Device *interface = MMC5983MA_I2C_interface(config); + + if (interface == nullptr) { + PX4_ERR("alloc failed"); + return nullptr; + } + + if (interface->init() != OK) { + delete interface; + PX4_DEBUG("no device on bus %i (devid 0x%x)", config.bus, config.spi_devid); + return nullptr; + } + + MMC5983MA *dev = new MMC5983MA(interface, config); + + if (dev == nullptr) { + delete interface; + return nullptr; + } + + if (OK != dev->init()) { + delete dev; + return nullptr; + } + + return dev; +} + +void MMC5983MA::print_usage() +{ + PRINT_MODULE_USAGE_NAME("mmc5983ma", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("magnetometer"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false); + PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x30); + PRINT_MODULE_USAGE_COMMAND("reset"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +extern "C" int mmc5983ma_main(int argc, char *argv[]) +{ + using ThisDriver = MMC5983MA; + int ch; + BusCLIArguments cli{true, false}; + cli.i2c_address = 0x30; + cli.default_i2c_frequency = 400000; + + while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { + switch (ch) { + case 'R': + cli.rotation = (enum Rotation)atoi(cli.optArg()); + break; + } + } + + const char *verb = cli.optArg(); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_MMC5983MA); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; +} From 3931379efeb8cb81dd44e33b03320c532f01b6e2 Mon Sep 17 00:00:00 2001 From: "Noe S. Sanchez" Date: Fri, 5 Apr 2024 19:29:44 -0600 Subject: [PATCH 078/652] msg: update VehicleCommand.msg MAV_CMD_DO_REPOSITION comment Added missing MAV_CMD_DO_REPOSITION parameters, from MAVlink Docs. --- msg/VehicleCommand.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/VehicleCommand.msg b/msg/VehicleCommand.msg index 801e5b279f61..b147bef09208 100644 --- a/msg/VehicleCommand.msg +++ b/msg/VehicleCommand.msg @@ -43,7 +43,7 @@ uint16 VEHICLE_CMD_DO_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode an uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1| Actuator 2| Actuator 3| Actuator 4| Actuator 5| Actuator 6| Index| uint16 VEHICLE_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonomous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_REPOSITION = 192 +uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |Ground speed [m/s] |Bitmask |Loiter radius [m] for planes |Yaw [deg] |Latitude |Longitude |Altitude | uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193 uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude| uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint| From 12fefbcfbd31df7603d0cd74c4a9f05374582585 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 1 Mar 2024 18:57:19 +0100 Subject: [PATCH 079/652] ekf2: use global definition of quaternion error --- src/modules/ekf2/EKF/covariance.cpp | 3 +- src/modules/ekf2/EKF/ekf.h | 7 +- src/modules/ekf2/EKF/ekf_helper.cpp | 26 +- .../EKF/python/ekf_derivation/derivation.py | 77 +- .../compute_drag_x_innov_var_and_h.h | 227 ++--- .../compute_drag_y_innov_var_and_h.h | 231 +++--- .../compute_flow_xy_innov_var_and_hx.h | 138 ++-- .../compute_flow_y_innov_var_and_h.h | 82 +- .../compute_gnss_yaw_pred_innov_var_and_h.h | 85 +- .../compute_gravity_xyz_innov_var_and_hx.h | 49 +- .../compute_gravity_y_innov_var_and_h.h | 14 +- .../compute_gravity_z_innov_var_and_h.h | 4 +- .../compute_mag_innov_innov_var_and_hx.h | 234 +++--- .../generated/compute_mag_y_innov_var_and_h.h | 82 +- .../generated/compute_mag_z_innov_var_and_h.h | 86 +- .../generated/compute_sideslip_h_and_k.h | 219 ++--- .../compute_sideslip_innov_and_innov_var.h | 141 ++-- .../generated/compute_yaw_innov_var_and_h.h | 21 +- .../generated/predict_covariance.h | 772 ++++++++++-------- src/modules/ekf2/EKF2.cpp | 2 +- src/modules/ekf2/test/test_EKF_flow.cpp | 6 +- .../ekf2/test/test_EKF_initialization.cpp | 2 +- .../test/test_EKF_yaw_fusion_generated.cpp | 5 +- 23 files changed, 1345 insertions(+), 1168 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index c6ba03f25622..482596070b96 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -279,8 +279,7 @@ void Ekf::resetQuatCov(const float yaw_noise) void Ekf::resetQuatCov(const Vector3f &rot_var_ned) { - matrix::SquareMatrix q_cov_ned = diag(rot_var_ned); - resetStateCovariance(_R_to_earth.T() * q_cov_ned * _R_to_earth); + P.uncorrelateCovarianceSetVariance(State::quat_nominal.idx, rot_var_ned); } #if defined(CONFIG_EKF2_MAGNETOMETER) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index bc087558e9eb..b8b02a06345a 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -254,7 +254,7 @@ class Ekf final : public EstimatorInterface // get the diagonal elements of the covariance matrix matrix::Vector covariances_diagonal() const { return P.diag(); } - matrix::Vector getQuaternionVariance() const { return getStateVariance(); } + matrix::Vector3f getRotVarBody() const; matrix::Vector3f getRotVarNed() const; float getYawVar() const; float getTiltVariance() const; @@ -1109,7 +1109,7 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_GRAVITY_FUSION void resetQuatCov(const float yaw_noise = NAN); - void resetQuatCov(const Vector3f &euler_noise_ned); + void resetQuatCov(const Vector3f &rot_var_ned); #if defined(CONFIG_EKF2_MAGNETOMETER) void resetMagCov(); @@ -1124,9 +1124,6 @@ class Ekf final : public EstimatorInterface void resetGyroBiasZCov(); - // uncorrelate quaternion states from other states - void uncorrelateQuatFromOtherStates(); - bool isTimedOut(uint64_t last_sensor_timestamp, uint64_t timeout_period) const { return (last_sensor_timestamp == 0) || (last_sensor_timestamp + timeout_period < _time_delayed_us); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index bb9e901f5760..48aa6cf41563 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -552,7 +552,7 @@ void Ekf::fuse(const VectorState &K, float innovation) { // quat_nominal Quatf delta_quat(matrix::AxisAnglef(K.slice(State::quat_nominal.idx, 0) * (-1.f * innovation))); - _state.quat_nominal *= delta_quat; + _state.quat_nominal = delta_quat * _state.quat_nominal; _state.quat_nominal.normalize(); _R_to_earth = Dcmf(_state.quat_nominal); @@ -586,11 +586,6 @@ void Ekf::fuse(const VectorState &K, float innovation) #endif // CONFIG_EKF2_WIND } -void Ekf::uncorrelateQuatFromOtherStates() -{ - P.uncorrelateCovarianceBlock(State::quat_nominal.idx); -} - void Ekf::updateDeadReckoningStatus() { updateHorizontalDeadReckoningstatus(); @@ -660,10 +655,16 @@ void Ekf::updateVerticalDeadReckoningStatus() } } -Vector3f Ekf::getRotVarNed() const +Vector3f Ekf::getRotVarBody() const { const matrix::SquareMatrix3f rot_cov_body = getStateCovariance(); - return matrix::SquareMatrix(_R_to_earth * rot_cov_body * _R_to_earth.T()).diag(); + return matrix::SquareMatrix3f(_R_to_earth.T() * rot_cov_body * _R_to_earth).diag(); +} + +Vector3f Ekf::getRotVarNed() const +{ + const matrix::SquareMatrix3f rot_cov_ned = getStateCovariance(); + return rot_cov_ned.diag(); } float Ekf::getYawVar() const @@ -707,12 +708,9 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) // save a copy of the quaternion state for later use in calculating the amount of reset change const Quatf quat_before_reset = _state.quat_nominal; - // save a copy of covariance in NED frame to restore it after the quat reset - Vector3f rot_var_ned_before_reset = getRotVarNed(); - // update the yaw angle variance if (PX4_ISFINITE(yaw_variance) && (yaw_variance > FLT_EPSILON)) { - rot_var_ned_before_reset(2) = yaw_variance; + P.uncorrelateCovarianceSetVariance<1>(2, yaw_variance); } // update transformation matrix from body to world frame using the current estimate @@ -725,10 +723,6 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) // update quaternion states _state.quat_nominal = quat_after_reset; - uncorrelateQuatFromOtherStates(); - - // restore covariance - resetQuatCov(rot_var_ned_before_reset); // add the reset amount to the output observer buffered data _output_predictor.resetQuaternion(q_error); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py index 5cbe1a127f3b..df3947e45977 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py @@ -148,7 +148,7 @@ def predict_covariance( for key in state.keys(): if key == "quat_nominal": # Create true quaternion using small angle approximation of the error rotation - state_t["quat_nominal"] = state["quat_nominal"] * sf.Rot3(sf.Quaternion(xyz=(state_error["theta"] / 2), w=1)) + state_t["quat_nominal"] = sf.Rot3(sf.Quaternion(xyz=(state_error["theta"] / 2), w=1)) * state["quat_nominal"] else: state_t[key] = state[key] + state_error[key] @@ -184,7 +184,7 @@ def predict_covariance( state_error_pred = Values() for key in state_error.keys(): if key == "theta": - delta_q = sf.Quaternion.from_storage(state_pred["quat_nominal"].to_storage()).conj() * sf.Quaternion.from_storage(state_t_pred["quat_nominal"].to_storage()) + delta_q = sf.Quaternion.from_storage(state_t_pred["quat_nominal"].to_storage()) * sf.Quaternion.from_storage(state_pred["quat_nominal"].to_storage()).conj() state_error_pred["theta"] = 2 * sf.V3(delta_q.x, delta_q.y, delta_q.z) # Use small angle approximation to obtain a simpler jacobian else: state_error_pred[key] = state_t_pred[key] - state_pred[key] @@ -216,6 +216,36 @@ def predict_covariance( return P_new +def jacobian_chain_rule(expr: sf.Scalar , state: State): + # First compute the jacobian in the parameter space + dh_dx = sf.V1(expr).jacobian(state, tangent_space=False) + + class MStorageTangent(sf.Matrix): + SHAPE = (State.storage_dim(), State.tangent_dim()) + + # Then compute the jarobian mapping infinitesimal elements of the parameter space to the error state + # Note that this jacobian only depends on the structure of the EKF + dx_derror = MStorageTangent() + q = sf.Quaternion.from_storage(state["quat_nominal"].to_storage()) + p = sf.Quaternion.symbolic('p') + + pq = p * q + qR = sf.M41(pq.to_storage()).jacobian(sf.M41(p.to_storage())) # Right quaternion product matrix + dx_derror[0:4, 0:3] = qR / 2 * sf.M43([[1, 0, 0], + [0, 1, 0], + [0, 0, 1], + [0, 0, 0]]) + + # The rest of the matrix is trivial + for i in range(4, State.storage_dim()): + for j in range(3, State.tangent_dim()): + if (i == j+1): + dx_derror[i, j] = 1 + + # Finally use the chain rule: dh/derror = dh/dx * dx/derror + H = dh_dx * dx_derror + return H + def compute_airspeed_innov_and_innov_var( state: VState, P: MTangent, @@ -231,7 +261,7 @@ def compute_airspeed_innov_and_innov_var( innov = airspeed_pred - airspeed - H = sf.V1(airspeed_pred).jacobian(state) + H = jacobian_chain_rule(airspeed_pred, state) innov_var = (H * P * H.T + R)[0,0] return (innov, innov_var) @@ -247,7 +277,7 @@ def compute_airspeed_h_and_k( wind = sf.V3(state["wind_vel"][0], state["wind_vel"][1], 0.0) vel_rel = state["vel"] - wind airspeed_pred = vel_rel.norm(epsilon=epsilon) - H = sf.V1(airspeed_pred).jacobian(state) + H = jacobian_chain_rule(airspeed_pred, state) K = P * H.T / sf.Max(innov_var, epsilon) @@ -309,7 +339,7 @@ def compute_sideslip_innov_and_innov_var( innov = sideslip_pred - 0.0 - H = sf.V1(sideslip_pred).jacobian(state) + H = jacobian_chain_rule(sideslip_pred, state) innov_var = (H * P * H.T + R)[0,0] return (innov, innov_var) @@ -324,7 +354,7 @@ def compute_sideslip_h_and_k( state = vstate_to_state(state) sideslip_pred = predict_sideslip(state, epsilon); - H = sf.V1(sideslip_pred).jacobian(state) + H = jacobian_chain_rule(sideslip_pred, state) K = P * H.T / sf.Max(innov_var, epsilon) @@ -351,11 +381,11 @@ def compute_mag_innov_innov_var_and_hx( innov = meas_pred - meas innov_var = sf.V3() - Hx = sf.V1(meas_pred[0]).jacobian(state) + Hx = jacobian_chain_rule(meas_pred[0], state) innov_var[0] = (Hx * P * Hx.T + R)[0,0] - Hy = sf.V1(meas_pred[1]).jacobian(state) + Hy = jacobian_chain_rule(meas_pred[1], state) innov_var[1] = (Hy * P * Hy.T + R)[0,0] - Hz = sf.V1(meas_pred[2]).jacobian(state) + Hz = jacobian_chain_rule(meas_pred[2], state) innov_var[2] = (Hz * P * Hz.T + R)[0,0] return (innov, innov_var, Hx.T) @@ -370,7 +400,7 @@ def compute_mag_y_innov_var_and_h( state = vstate_to_state(state) meas_pred = predict_mag_body(state); - H = sf.V1(meas_pred[1]).jacobian(state) + H = jacobian_chain_rule(meas_pred[1], state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -385,7 +415,7 @@ def compute_mag_z_innov_var_and_h( state = vstate_to_state(state) meas_pred = predict_mag_body(state); - H = sf.V1(meas_pred[2]).jacobian(state) + H = jacobian_chain_rule(meas_pred[2], state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -402,8 +432,11 @@ def compute_yaw_innov_var_and_h( delta_q = q * r.conj() # create a quaternion error of the measurement at the origin delta_meas_pred = 2 * delta_q.z # Use small angle approximation to obtain a simpler jacobian - H = sf.V1(delta_meas_pred).jacobian(state) + H = jacobian_chain_rule(delta_meas_pred, state) H = H.subs({r.w: q.w, r.x: q.x, r.y: q.y, r.z: q.z}) # assume innovation is small + + for i in range(State.tangent_dim()): + H[i] = sp.factor(H[i]).subs(q.w**2 + q.x**2 + q.y**2 + q.z**2, 1) # unit norm quaternion innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -418,7 +451,7 @@ def compute_mag_declination_pred_innov_var_and_h( state = vstate_to_state(state) meas_pred = sf.atan2(state["mag_I"][1], state["mag_I"][0], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state) + H = jacobian_chain_rule(meas_pred, state) innov_var = (H * P * H.T + R)[0,0] return (meas_pred, innov_var, H.T) @@ -450,9 +483,9 @@ def compute_flow_xy_innov_var_and_hx( meas_pred = predict_opt_flow(state, distance, epsilon); innov_var = sf.V2() - Hx = sf.V1(meas_pred[0]).jacobian(state) + Hx = jacobian_chain_rule(meas_pred[0], state) innov_var[0] = (Hx * P * Hx.T + R)[0,0] - Hy = sf.V1(meas_pred[1]).jacobian(state) + Hy = jacobian_chain_rule(meas_pred[1], state) innov_var[1] = (Hy * P * Hy.T + R)[0,0] return (innov_var, Hx.T) @@ -467,7 +500,7 @@ def compute_flow_y_innov_var_and_h( state = vstate_to_state(state) meas_pred = predict_opt_flow(state, distance, epsilon); - Hy = sf.V1(meas_pred[1]).jacobian(state) + Hy = jacobian_chain_rule(meas_pred[1], state) innov_var = (Hy * P * Hy.T + R)[0,0] return (innov_var, Hy.T) @@ -492,7 +525,7 @@ def compute_gnss_yaw_pred_innov_var_and_h( # Calculate the yaw angle from the projection meas_pred = sf.atan2(ant_vec_ef[1], ant_vec_ef[0], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state) + H = jacobian_chain_rule(meas_pred, state) innov_var = (H * P * H.T + R)[0,0] return (meas_pred, innov_var, H.T) @@ -529,7 +562,7 @@ def compute_drag_x_innov_var_and_h( state = vstate_to_state(state) meas_pred = predict_drag(state, rho, cd, cm, epsilon) - Hx = sf.V1(meas_pred[0]).jacobian(state) + Hx = jacobian_chain_rule(meas_pred[0], state) innov_var = (Hx * P * Hx.T + R)[0,0] return (innov_var, Hx.T) @@ -546,7 +579,7 @@ def compute_drag_y_innov_var_and_h( state = vstate_to_state(state) meas_pred = predict_drag(state, rho, cd, cm, epsilon) - Hy = sf.V1(meas_pred[1]).jacobian(state) + Hy = jacobian_chain_rule(meas_pred[1], state) innov_var = (Hy * P * Hy.T + R)[0,0] return (innov_var, Hy.T) @@ -575,7 +608,7 @@ def compute_gravity_xyz_innov_var_and_hx( # calculate observation jacobian (H), kalman gain (K), and innovation variance (S) # for each axis for i in range(3): - H[i] = sf.V1(meas_pred[i]).jacobian(state) + H[i] = jacobian_chain_rule(meas_pred[i], state) innov_var[i] = (H[i] * P * H[i].T + R)[0,0] return (innov_var, H[0].T) @@ -590,7 +623,7 @@ def compute_gravity_y_innov_var_and_h( meas_pred = predict_gravity_direction(state) # calculate observation jacobian (H), kalman gain (K), and innovation variance (S) - H = sf.V1(meas_pred[1]).jacobian(state) + H = jacobian_chain_rule(meas_pred[1], state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -605,7 +638,7 @@ def compute_gravity_z_innov_var_and_h( meas_pred = predict_gravity_direction(state) # calculate observation jacobian (H), kalman gain (K), and innovation variance (S) - H = sf.V1(meas_pred[2]).jacobian(state) + H = jacobian_chain_rule(meas_pred[2], state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h index 4a08ef76f169..1b7c762f2c14 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h @@ -34,95 +34,108 @@ void ComputeDragXInnovVarAndH(const matrix::Matrix& state, const Scalar cd, const Scalar cm, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, matrix::Matrix* const Hx = nullptr) { - // Total ops: 317 + // Total ops: 357 // Input arrays - // Intermediate terms (73) - const Scalar _tmp0 = 2 * state(3, 0); - const Scalar _tmp1 = _tmp0 * state(0, 0); - const Scalar _tmp2 = 2 * state(2, 0); - const Scalar _tmp3 = _tmp2 * state(1, 0); + // Intermediate terms (79) + const Scalar _tmp0 = 2 * state(0, 0); + const Scalar _tmp1 = _tmp0 * state(3, 0); + const Scalar _tmp2 = 2 * state(1, 0); + const Scalar _tmp3 = _tmp2 * state(2, 0); const Scalar _tmp4 = _tmp1 + _tmp3; const Scalar _tmp5 = _tmp4 * cm; - const Scalar _tmp6 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp7 = -2 * _tmp6; - const Scalar _tmp8 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp9 = -2 * _tmp8; - const Scalar _tmp10 = _tmp7 + _tmp9 + 1; - const Scalar _tmp11 = -state(22, 0) + state(4, 0); - const Scalar _tmp12 = -state(23, 0) + state(5, 0); - const Scalar _tmp13 = _tmp2 * state(0, 0); - const Scalar _tmp14 = -_tmp13; - const Scalar _tmp15 = _tmp0 * state(1, 0); - const Scalar _tmp16 = _tmp14 + _tmp15; - const Scalar _tmp17 = _tmp12 * _tmp4 + _tmp16 * state(6, 0); - const Scalar _tmp18 = _tmp10 * _tmp11 + _tmp17; - const Scalar _tmp19 = 2 * _tmp18; - const Scalar _tmp20 = _tmp19 * _tmp4; - const Scalar _tmp21 = _tmp0 * state(2, 0); - const Scalar _tmp22 = 2 * state(0, 0) * state(1, 0); - const Scalar _tmp23 = -_tmp22; - const Scalar _tmp24 = _tmp21 + _tmp23; - const Scalar _tmp25 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp26 = 1 - 2 * _tmp25; - const Scalar _tmp27 = _tmp26 + _tmp9; - const Scalar _tmp28 = _tmp13 + _tmp15; - const Scalar _tmp29 = _tmp11 * _tmp28 + _tmp12 * _tmp24; - const Scalar _tmp30 = _tmp27 * state(6, 0) + _tmp29; + const Scalar _tmp6 = -2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp7 = -2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp8 = _tmp6 + _tmp7 + 1; + const Scalar _tmp9 = -state(22, 0) + state(4, 0); + const Scalar _tmp10 = -state(23, 0) + state(5, 0); + const Scalar _tmp11 = 2 * state(2, 0); + const Scalar _tmp12 = _tmp11 * state(0, 0); + const Scalar _tmp13 = _tmp2 * state(3, 0); + const Scalar _tmp14 = -_tmp12 + _tmp13; + const Scalar _tmp15 = _tmp10 * _tmp4 + _tmp14 * state(6, 0) + _tmp8 * _tmp9; + const Scalar _tmp16 = 2 * _tmp15; + const Scalar _tmp17 = _tmp16 * _tmp4; + const Scalar _tmp18 = _tmp11 * state(3, 0); + const Scalar _tmp19 = _tmp2 * state(0, 0); + const Scalar _tmp20 = _tmp18 - _tmp19; + const Scalar _tmp21 = _tmp12 + _tmp13; + const Scalar _tmp22 = 1 - 2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp23 = _tmp22 + _tmp7; + const Scalar _tmp24 = _tmp10 * _tmp20 + _tmp21 * _tmp9 + _tmp23 * state(6, 0); + const Scalar _tmp25 = 2 * _tmp24; + const Scalar _tmp26 = _tmp20 * _tmp25; + const Scalar _tmp27 = _tmp22 + _tmp6; + const Scalar _tmp28 = -_tmp1 + _tmp3; + const Scalar _tmp29 = _tmp18 + _tmp19; + const Scalar _tmp30 = _tmp10 * _tmp27 + _tmp28 * _tmp9 + _tmp29 * state(6, 0); const Scalar _tmp31 = 2 * _tmp30; - const Scalar _tmp32 = _tmp24 * _tmp31; - const Scalar _tmp33 = _tmp26 + _tmp7; - const Scalar _tmp34 = -_tmp1; - const Scalar _tmp35 = _tmp3 + _tmp34; - const Scalar _tmp36 = _tmp21 + _tmp22; - const Scalar _tmp37 = _tmp11 * _tmp35 + _tmp36 * state(6, 0); - const Scalar _tmp38 = _tmp12 * _tmp33 + _tmp37; - const Scalar _tmp39 = 2 * _tmp38; - const Scalar _tmp40 = _tmp33 * _tmp39; - const Scalar _tmp41 = std::sqrt(Scalar(std::pow(_tmp18, Scalar(2)) + std::pow(_tmp30, Scalar(2)) + - std::pow(_tmp38, Scalar(2)) + epsilon)); - const Scalar _tmp42 = cd * rho; - const Scalar _tmp43 = Scalar(0.25) * _tmp18 * _tmp42 / _tmp41; - const Scalar _tmp44 = Scalar(0.5) * _tmp41 * _tmp42; - const Scalar _tmp45 = _tmp4 * _tmp44; - const Scalar _tmp46 = -_tmp43 * (_tmp20 + _tmp32 + _tmp40) - _tmp45 - _tmp5; - const Scalar _tmp47 = -_tmp25; - const Scalar _tmp48 = _tmp47 + _tmp6; - const Scalar _tmp49 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp50 = -_tmp49; - const Scalar _tmp51 = _tmp50 + _tmp8; - const Scalar _tmp52 = -_tmp3; - const Scalar _tmp53 = -_tmp15; - const Scalar _tmp54 = -_tmp6; - const Scalar _tmp55 = _tmp12 * (_tmp47 + _tmp49 + _tmp54 + _tmp8) + _tmp37; - const Scalar _tmp56 = -_tmp43 * (_tmp19 * _tmp55 + _tmp39 * (_tmp11 * (_tmp48 + _tmp51) + - _tmp12 * (_tmp34 + _tmp52) + - state(6, 0) * (_tmp13 + _tmp53))) - - _tmp44 * _tmp55 - _tmp55 * cm; - const Scalar _tmp57 = -_tmp43 * (-_tmp20 - _tmp32 - _tmp40) + _tmp45 + _tmp5; - const Scalar _tmp58 = _tmp10 * cm; - const Scalar _tmp59 = _tmp10 * _tmp19; - const Scalar _tmp60 = _tmp28 * _tmp31; - const Scalar _tmp61 = _tmp35 * _tmp39; - const Scalar _tmp62 = _tmp10 * _tmp44; - const Scalar _tmp63 = -_tmp43 * (-_tmp59 - _tmp60 - _tmp61) + _tmp58 + _tmp62; - const Scalar _tmp64 = -_tmp8; - const Scalar _tmp65 = -_tmp21; - const Scalar _tmp66 = _tmp49 + _tmp64; - const Scalar _tmp67 = - _tmp43 * (_tmp31 * (_tmp11 * (_tmp1 + _tmp52) + _tmp12 * (_tmp25 + _tmp50 + _tmp6 + _tmp64) + - state(6, 0) * (_tmp23 + _tmp65)) + - _tmp39 * (_tmp29 + state(6, 0) * (_tmp48 + _tmp66))); - const Scalar _tmp68 = _tmp25 + _tmp54; - const Scalar _tmp69 = - _tmp11 * (_tmp14 + _tmp53) + _tmp12 * (_tmp22 + _tmp65) + state(6, 0) * (_tmp51 + _tmp68); - const Scalar _tmp70 = - -_tmp43 * (_tmp19 * _tmp69 + _tmp31 * (_tmp11 * (_tmp66 + _tmp68) + _tmp17)) - - _tmp44 * _tmp69 - _tmp69 * cm; - const Scalar _tmp71 = -_tmp43 * (_tmp59 + _tmp60 + _tmp61) - _tmp58 - _tmp62; - const Scalar _tmp72 = -_tmp16 * _tmp44 - _tmp16 * cm - - _tmp43 * (_tmp16 * _tmp19 + _tmp27 * _tmp31 + _tmp36 * _tmp39); + const Scalar _tmp32 = _tmp27 * _tmp31; + const Scalar _tmp33 = std::sqrt(Scalar(std::pow(_tmp15, Scalar(2)) + std::pow(_tmp24, Scalar(2)) + + std::pow(_tmp30, Scalar(2)) + epsilon)); + const Scalar _tmp34 = cd * rho; + const Scalar _tmp35 = Scalar(0.25) * _tmp15 * _tmp34 / _tmp33; + const Scalar _tmp36 = Scalar(0.5) * _tmp33 * _tmp34; + const Scalar _tmp37 = _tmp36 * _tmp4; + const Scalar _tmp38 = -_tmp35 * (-_tmp17 - _tmp26 - _tmp32) + _tmp37 + _tmp5; + const Scalar _tmp39 = -_tmp35 * (_tmp17 + _tmp26 + _tmp32) - _tmp37 - _tmp5; + const Scalar _tmp40 = _tmp8 * cm; + const Scalar _tmp41 = _tmp16 * _tmp8; + const Scalar _tmp42 = _tmp21 * _tmp25; + const Scalar _tmp43 = _tmp28 * _tmp31; + const Scalar _tmp44 = _tmp36 * _tmp8; + const Scalar _tmp45 = -_tmp35 * (-_tmp41 - _tmp42 - _tmp43) + _tmp40 + _tmp44; + const Scalar _tmp46 = 2 * state(3, 0); + const Scalar _tmp47 = _tmp10 * _tmp46; + const Scalar _tmp48 = 2 * state(6, 0); + const Scalar _tmp49 = _tmp48 * state(2, 0); + const Scalar _tmp50 = _tmp47 - _tmp49; + const Scalar _tmp51 = _tmp10 * _tmp2; + const Scalar _tmp52 = _tmp11 * _tmp9; + const Scalar _tmp53 = _tmp46 * _tmp9; + const Scalar _tmp54 = _tmp2 * state(6, 0); + const Scalar _tmp55 = + -_tmp35 * (_tmp16 * _tmp50 + _tmp25 * (-_tmp51 + _tmp52) + _tmp31 * (-_tmp53 + _tmp54)) - + _tmp36 * _tmp50 - _tmp50 * cm; + const Scalar _tmp56 = (Scalar(1) / Scalar(2)) * _tmp55; + const Scalar _tmp57 = _tmp10 * _tmp11; + const Scalar _tmp58 = _tmp48 * state(3, 0); + const Scalar _tmp59 = _tmp57 + _tmp58; + const Scalar _tmp60 = _tmp0 * _tmp10; + const Scalar _tmp61 = 4 * state(6, 0); + const Scalar _tmp62 = 4 * _tmp10; + const Scalar _tmp63 = _tmp48 * state(0, 0); + const Scalar _tmp64 = + -_tmp35 * (_tmp16 * _tmp59 + _tmp25 * (_tmp53 - _tmp60 - _tmp61 * state(1, 0)) + + _tmp31 * (_tmp52 - _tmp62 * state(1, 0) + _tmp63)) - + _tmp36 * _tmp59 - _tmp59 * cm; + const Scalar _tmp65 = (Scalar(1) / Scalar(2)) * state(2, 0); + const Scalar _tmp66 = 4 * _tmp9; + const Scalar _tmp67 = _tmp54 + _tmp60 - _tmp66 * state(3, 0); + const Scalar _tmp68 = _tmp2 * _tmp9; + const Scalar _tmp69 = _tmp0 * _tmp9; + const Scalar _tmp70 = -Scalar(1) / Scalar(2) * _tmp35 * + (_tmp16 * _tmp67 + _tmp25 * (_tmp57 + _tmp68) + + _tmp31 * (_tmp49 - _tmp62 * state(3, 0) - _tmp69)) - + Scalar(1) / Scalar(2) * _tmp36 * _tmp67 - + Scalar(1) / Scalar(2) * _tmp67 * cm; + const Scalar _tmp71 = _tmp51 - _tmp63 - _tmp66 * state(2, 0); + const Scalar _tmp72 = -Scalar(1) / Scalar(2) * _tmp35 * + (_tmp16 * _tmp71 + _tmp25 * (_tmp47 - _tmp61 * state(2, 0) + _tmp69) + + _tmp31 * (_tmp58 + _tmp68)) - + Scalar(1) / Scalar(2) * _tmp36 * _tmp71 - + Scalar(1) / Scalar(2) * _tmp71 * cm; + const Scalar _tmp73 = + -_tmp56 * state(3, 0) - _tmp64 * _tmp65 + _tmp70 * state(0, 0) + _tmp72 * state(1, 0); + const Scalar _tmp74 = (Scalar(1) / Scalar(2)) * _tmp64; + const Scalar _tmp75 = + -_tmp55 * _tmp65 - _tmp70 * state(1, 0) + _tmp72 * state(0, 0) + _tmp74 * state(3, 0); + const Scalar _tmp76 = + -_tmp56 * state(1, 0) + _tmp70 * state(2, 0) - _tmp72 * state(3, 0) + _tmp74 * state(0, 0); + const Scalar _tmp77 = -_tmp35 * (_tmp41 + _tmp42 + _tmp43) - _tmp40 - _tmp44; + const Scalar _tmp78 = -_tmp14 * _tmp36 - _tmp14 * cm - + _tmp35 * (_tmp14 * _tmp16 + _tmp23 * _tmp25 + _tmp29 * _tmp31); // Output terms (2) if (innov_var != nullptr) { @@ -130,22 +143,22 @@ void ComputeDragXInnovVarAndH(const matrix::Matrix& state, _innov_var = R + - _tmp46 * (-P(0, 4) * _tmp67 + P(1, 4) * _tmp70 + P(2, 4) * _tmp56 + P(21, 4) * _tmp63 + - P(22, 4) * _tmp57 + P(3, 4) * _tmp71 + P(4, 4) * _tmp46 + P(5, 4) * _tmp72) + - _tmp56 * (-P(0, 2) * _tmp67 + P(1, 2) * _tmp70 + P(2, 2) * _tmp56 + P(21, 2) * _tmp63 + - P(22, 2) * _tmp57 + P(3, 2) * _tmp71 + P(4, 2) * _tmp46 + P(5, 2) * _tmp72) + - _tmp57 * (-P(0, 22) * _tmp67 + P(1, 22) * _tmp70 + P(2, 22) * _tmp56 + P(21, 22) * _tmp63 + - P(22, 22) * _tmp57 + P(3, 22) * _tmp71 + P(4, 22) * _tmp46 + P(5, 22) * _tmp72) + - _tmp63 * (-P(0, 21) * _tmp67 + P(1, 21) * _tmp70 + P(2, 21) * _tmp56 + P(21, 21) * _tmp63 + - P(22, 21) * _tmp57 + P(3, 21) * _tmp71 + P(4, 21) * _tmp46 + P(5, 21) * _tmp72) - - _tmp67 * (-P(0, 0) * _tmp67 + P(1, 0) * _tmp70 + P(2, 0) * _tmp56 + P(21, 0) * _tmp63 + - P(22, 0) * _tmp57 + P(3, 0) * _tmp71 + P(4, 0) * _tmp46 + P(5, 0) * _tmp72) + - _tmp70 * (-P(0, 1) * _tmp67 + P(1, 1) * _tmp70 + P(2, 1) * _tmp56 + P(21, 1) * _tmp63 + - P(22, 1) * _tmp57 + P(3, 1) * _tmp71 + P(4, 1) * _tmp46 + P(5, 1) * _tmp72) + - _tmp71 * (-P(0, 3) * _tmp67 + P(1, 3) * _tmp70 + P(2, 3) * _tmp56 + P(21, 3) * _tmp63 + - P(22, 3) * _tmp57 + P(3, 3) * _tmp71 + P(4, 3) * _tmp46 + P(5, 3) * _tmp72) + - _tmp72 * (-P(0, 5) * _tmp67 + P(1, 5) * _tmp70 + P(2, 5) * _tmp56 + P(21, 5) * _tmp63 + - P(22, 5) * _tmp57 + P(3, 5) * _tmp71 + P(4, 5) * _tmp46 + P(5, 5) * _tmp72); + _tmp38 * (P(0, 22) * _tmp76 + P(1, 22) * _tmp75 + P(2, 22) * _tmp73 + P(21, 22) * _tmp45 + + P(22, 22) * _tmp38 + P(3, 22) * _tmp77 + P(4, 22) * _tmp39 + P(5, 22) * _tmp78) + + _tmp39 * (P(0, 4) * _tmp76 + P(1, 4) * _tmp75 + P(2, 4) * _tmp73 + P(21, 4) * _tmp45 + + P(22, 4) * _tmp38 + P(3, 4) * _tmp77 + P(4, 4) * _tmp39 + P(5, 4) * _tmp78) + + _tmp45 * (P(0, 21) * _tmp76 + P(1, 21) * _tmp75 + P(2, 21) * _tmp73 + P(21, 21) * _tmp45 + + P(22, 21) * _tmp38 + P(3, 21) * _tmp77 + P(4, 21) * _tmp39 + P(5, 21) * _tmp78) + + _tmp73 * (P(0, 2) * _tmp76 + P(1, 2) * _tmp75 + P(2, 2) * _tmp73 + P(21, 2) * _tmp45 + + P(22, 2) * _tmp38 + P(3, 2) * _tmp77 + P(4, 2) * _tmp39 + P(5, 2) * _tmp78) + + _tmp75 * (P(0, 1) * _tmp76 + P(1, 1) * _tmp75 + P(2, 1) * _tmp73 + P(21, 1) * _tmp45 + + P(22, 1) * _tmp38 + P(3, 1) * _tmp77 + P(4, 1) * _tmp39 + P(5, 1) * _tmp78) + + _tmp76 * (P(0, 0) * _tmp76 + P(1, 0) * _tmp75 + P(2, 0) * _tmp73 + P(21, 0) * _tmp45 + + P(22, 0) * _tmp38 + P(3, 0) * _tmp77 + P(4, 0) * _tmp39 + P(5, 0) * _tmp78) + + _tmp77 * (P(0, 3) * _tmp76 + P(1, 3) * _tmp75 + P(2, 3) * _tmp73 + P(21, 3) * _tmp45 + + P(22, 3) * _tmp38 + P(3, 3) * _tmp77 + P(4, 3) * _tmp39 + P(5, 3) * _tmp78) + + _tmp78 * (P(0, 5) * _tmp76 + P(1, 5) * _tmp75 + P(2, 5) * _tmp73 + P(21, 5) * _tmp45 + + P(22, 5) * _tmp38 + P(3, 5) * _tmp77 + P(4, 5) * _tmp39 + P(5, 5) * _tmp78); } if (Hx != nullptr) { @@ -153,14 +166,14 @@ void ComputeDragXInnovVarAndH(const matrix::Matrix& state, _hx.setZero(); - _hx(0, 0) = -_tmp67; - _hx(1, 0) = _tmp70; - _hx(2, 0) = _tmp56; - _hx(3, 0) = _tmp71; - _hx(4, 0) = _tmp46; - _hx(5, 0) = _tmp72; - _hx(21, 0) = _tmp63; - _hx(22, 0) = _tmp57; + _hx(0, 0) = _tmp76; + _hx(1, 0) = _tmp75; + _hx(2, 0) = _tmp73; + _hx(3, 0) = _tmp77; + _hx(4, 0) = _tmp39; + _hx(5, 0) = _tmp78; + _hx(21, 0) = _tmp45; + _hx(22, 0) = _tmp38; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h index c504d0db636a..505f4ed4deed 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h @@ -34,97 +34,108 @@ void ComputeDragYInnovVarAndH(const matrix::Matrix& state, const Scalar cd, const Scalar cm, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, matrix::Matrix* const Hy = nullptr) { - // Total ops: 317 + // Total ops: 360 // Input arrays - // Intermediate terms (73) - const Scalar _tmp0 = 2 * state(2, 0) * state(3, 0); - const Scalar _tmp1 = 2 * state(1, 0); - const Scalar _tmp2 = _tmp1 * state(0, 0); - const Scalar _tmp3 = _tmp0 + _tmp2; - const Scalar _tmp4 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp5 = -2 * _tmp4; - const Scalar _tmp6 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp7 = -2 * _tmp6; - const Scalar _tmp8 = _tmp5 + _tmp7 + 1; + // Intermediate terms (76) + const Scalar _tmp0 = 2 * state(0, 0); + const Scalar _tmp1 = _tmp0 * state(3, 0); + const Scalar _tmp2 = 2 * state(1, 0); + const Scalar _tmp3 = _tmp2 * state(2, 0); + const Scalar _tmp4 = -_tmp1 + _tmp3; + const Scalar _tmp5 = _tmp4 * cm; + const Scalar _tmp6 = -2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp7 = -2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp8 = _tmp6 + _tmp7 + 1; const Scalar _tmp9 = -state(22, 0) + state(4, 0); - const Scalar _tmp10 = 2 * state(0, 0); - const Scalar _tmp11 = _tmp10 * state(3, 0); - const Scalar _tmp12 = _tmp1 * state(2, 0); - const Scalar _tmp13 = _tmp11 + _tmp12; - const Scalar _tmp14 = -state(23, 0) + state(5, 0); - const Scalar _tmp15 = _tmp10 * state(2, 0); - const Scalar _tmp16 = -_tmp15; - const Scalar _tmp17 = _tmp1 * state(3, 0); - const Scalar _tmp18 = _tmp16 + _tmp17; - const Scalar _tmp19 = _tmp13 * _tmp14 + _tmp18 * state(6, 0); - const Scalar _tmp20 = _tmp19 + _tmp8 * _tmp9; - const Scalar _tmp21 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp22 = 1 - 2 * _tmp21; - const Scalar _tmp23 = _tmp22 + _tmp7; - const Scalar _tmp24 = -_tmp2; - const Scalar _tmp25 = _tmp0 + _tmp24; - const Scalar _tmp26 = _tmp15 + _tmp17; - const Scalar _tmp27 = _tmp14 * _tmp25 + _tmp26 * _tmp9; - const Scalar _tmp28 = _tmp23 * state(6, 0) + _tmp27; - const Scalar _tmp29 = _tmp22 + _tmp5; - const Scalar _tmp30 = -_tmp11; - const Scalar _tmp31 = _tmp12 + _tmp30; - const Scalar _tmp32 = _tmp3 * state(6, 0) + _tmp31 * _tmp9; - const Scalar _tmp33 = _tmp14 * _tmp29 + _tmp32; - const Scalar _tmp34 = std::sqrt(Scalar(std::pow(_tmp20, Scalar(2)) + std::pow(_tmp28, Scalar(2)) + - std::pow(_tmp33, Scalar(2)) + epsilon)); - const Scalar _tmp35 = cd * rho; - const Scalar _tmp36 = Scalar(0.5) * _tmp34 * _tmp35; - const Scalar _tmp37 = 2 * _tmp20; - const Scalar _tmp38 = 2 * _tmp28; - const Scalar _tmp39 = 2 * _tmp33; - const Scalar _tmp40 = Scalar(0.25) * _tmp33 * _tmp35 / _tmp34; - const Scalar _tmp41 = - -_tmp3 * _tmp36 - _tmp3 * cm - _tmp40 * (_tmp18 * _tmp37 + _tmp23 * _tmp38 + _tmp3 * _tmp39); - const Scalar _tmp42 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp43 = -_tmp42; - const Scalar _tmp44 = -_tmp6; - const Scalar _tmp45 = -_tmp12; - const Scalar _tmp46 = -_tmp0; - const Scalar _tmp47 = -_tmp21; - const Scalar _tmp48 = _tmp4 + _tmp47; - const Scalar _tmp49 = _tmp42 + _tmp44; - const Scalar _tmp50 = _tmp27 + state(6, 0) * (_tmp48 + _tmp49); - const Scalar _tmp51 = - -_tmp36 * _tmp50 - - _tmp40 * (_tmp38 * (_tmp14 * (_tmp21 + _tmp4 + _tmp43 + _tmp44) + _tmp9 * (_tmp11 + _tmp45) + - state(6, 0) * (_tmp24 + _tmp46)) + - _tmp39 * _tmp50) - - _tmp50 * cm; - const Scalar _tmp52 = _tmp43 + _tmp6; - const Scalar _tmp53 = -_tmp17; - const Scalar _tmp54 = - _tmp14 * (_tmp30 + _tmp45) + _tmp9 * (_tmp48 + _tmp52) + state(6, 0) * (_tmp15 + _tmp53); - const Scalar _tmp55 = -_tmp4; + const Scalar _tmp10 = _tmp1 + _tmp3; + const Scalar _tmp11 = -state(23, 0) + state(5, 0); + const Scalar _tmp12 = _tmp0 * state(2, 0); + const Scalar _tmp13 = _tmp2 * state(3, 0); + const Scalar _tmp14 = -_tmp12 + _tmp13; + const Scalar _tmp15 = _tmp10 * _tmp11 + _tmp14 * state(6, 0) + _tmp8 * _tmp9; + const Scalar _tmp16 = 2 * state(3, 0); + const Scalar _tmp17 = _tmp16 * state(2, 0); + const Scalar _tmp18 = _tmp2 * state(0, 0); + const Scalar _tmp19 = _tmp17 - _tmp18; + const Scalar _tmp20 = _tmp12 + _tmp13; + const Scalar _tmp21 = 1 - 2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp22 = _tmp21 + _tmp7; + const Scalar _tmp23 = _tmp11 * _tmp19 + _tmp20 * _tmp9 + _tmp22 * state(6, 0); + const Scalar _tmp24 = _tmp21 + _tmp6; + const Scalar _tmp25 = _tmp17 + _tmp18; + const Scalar _tmp26 = _tmp11 * _tmp24 + _tmp25 * state(6, 0) + _tmp4 * _tmp9; + const Scalar _tmp27 = std::sqrt(Scalar(std::pow(_tmp15, Scalar(2)) + std::pow(_tmp23, Scalar(2)) + + std::pow(_tmp26, Scalar(2)) + epsilon)); + const Scalar _tmp28 = cd * rho; + const Scalar _tmp29 = Scalar(0.5) * _tmp27 * _tmp28; + const Scalar _tmp30 = _tmp29 * _tmp4; + const Scalar _tmp31 = 2 * _tmp15; + const Scalar _tmp32 = _tmp31 * _tmp8; + const Scalar _tmp33 = 2 * _tmp23; + const Scalar _tmp34 = _tmp20 * _tmp33; + const Scalar _tmp35 = 2 * _tmp26; + const Scalar _tmp36 = _tmp35 * _tmp4; + const Scalar _tmp37 = Scalar(0.25) * _tmp26 * _tmp28 / _tmp27; + const Scalar _tmp38 = _tmp30 - _tmp37 * (-_tmp32 - _tmp34 - _tmp36) + _tmp5; + const Scalar _tmp39 = -_tmp30 - _tmp37 * (_tmp32 + _tmp34 + _tmp36) - _tmp5; + const Scalar _tmp40 = _tmp24 * cm; + const Scalar _tmp41 = _tmp10 * _tmp31; + const Scalar _tmp42 = _tmp19 * _tmp33; + const Scalar _tmp43 = _tmp24 * _tmp35; + const Scalar _tmp44 = _tmp24 * _tmp29; + const Scalar _tmp45 = -_tmp37 * (_tmp41 + _tmp42 + _tmp43) - _tmp40 - _tmp44; + const Scalar _tmp46 = _tmp16 * _tmp9; + const Scalar _tmp47 = _tmp0 * _tmp11; + const Scalar _tmp48 = state(1, 0) * state(6, 0); + const Scalar _tmp49 = 2 * state(2, 0); + const Scalar _tmp50 = _tmp11 * _tmp49; + const Scalar _tmp51 = _tmp16 * state(6, 0); + const Scalar _tmp52 = 4 * _tmp11; + const Scalar _tmp53 = _tmp49 * _tmp9; + const Scalar _tmp54 = _tmp0 * state(6, 0); + const Scalar _tmp55 = -_tmp52 * state(1, 0) + _tmp53 + _tmp54; const Scalar _tmp56 = - -_tmp36 * _tmp54 - - _tmp40 * (_tmp37 * (_tmp14 * (_tmp42 + _tmp47 + _tmp55 + _tmp6) + _tmp32) + _tmp39 * _tmp54) - - _tmp54 * cm; - const Scalar _tmp57 = _tmp29 * cm; - const Scalar _tmp58 = _tmp13 * _tmp37; - const Scalar _tmp59 = _tmp25 * _tmp38; - const Scalar _tmp60 = _tmp29 * _tmp39; - const Scalar _tmp61 = _tmp29 * _tmp36; - const Scalar _tmp62 = -_tmp40 * (-_tmp58 - _tmp59 - _tmp60) + _tmp57 + _tmp61; - const Scalar _tmp63 = _tmp21 + _tmp55; - const Scalar _tmp64 = _tmp40 * (_tmp37 * (_tmp14 * (_tmp2 + _tmp46) + _tmp9 * (_tmp16 + _tmp53) + - state(6, 0) * (_tmp52 + _tmp63)) + - _tmp38 * (_tmp19 + _tmp9 * (_tmp49 + _tmp63))); - const Scalar _tmp65 = -_tmp40 * (_tmp58 + _tmp59 + _tmp60) - _tmp57 - _tmp61; - const Scalar _tmp66 = _tmp31 * cm; - const Scalar _tmp67 = _tmp31 * _tmp36; - const Scalar _tmp68 = _tmp37 * _tmp8; - const Scalar _tmp69 = _tmp26 * _tmp38; - const Scalar _tmp70 = _tmp31 * _tmp39; - const Scalar _tmp71 = -_tmp40 * (_tmp68 + _tmp69 + _tmp70) - _tmp66 - _tmp67; - const Scalar _tmp72 = -_tmp40 * (-_tmp68 - _tmp69 - _tmp70) + _tmp66 + _tmp67; + -Scalar(1) / Scalar(2) * _tmp29 * _tmp55 - + Scalar(1) / Scalar(2) * _tmp37 * + (_tmp31 * (_tmp50 + _tmp51) + _tmp33 * (_tmp46 - _tmp47 - 4 * _tmp48) + _tmp35 * _tmp55) - + Scalar(1) / Scalar(2) * _tmp55 * cm; + const Scalar _tmp57 = 2 * _tmp48; + const Scalar _tmp58 = -_tmp46 + _tmp57; + const Scalar _tmp59 = _tmp11 * _tmp2; + const Scalar _tmp60 = _tmp11 * _tmp16; + const Scalar _tmp61 = state(2, 0) * state(6, 0); + const Scalar _tmp62 = 2 * _tmp61; + const Scalar _tmp63 = + -Scalar(1) / Scalar(2) * _tmp29 * _tmp58 - + Scalar(1) / Scalar(2) * _tmp37 * + (_tmp31 * (_tmp60 - _tmp62) + _tmp33 * (_tmp53 - _tmp59) + _tmp35 * _tmp58) - + Scalar(1) / Scalar(2) * _tmp58 * cm; + const Scalar _tmp64 = _tmp2 * _tmp9; + const Scalar _tmp65 = _tmp51 + _tmp64; + const Scalar _tmp66 = _tmp0 * _tmp9; + const Scalar _tmp67 = 4 * _tmp9; + const Scalar _tmp68 = -Scalar(1) / Scalar(2) * _tmp29 * _tmp65 - + Scalar(1) / Scalar(2) * _tmp37 * + (_tmp31 * (-_tmp54 + _tmp59 - _tmp67 * state(2, 0)) + + _tmp33 * (_tmp60 - 4 * _tmp61 + _tmp66) + _tmp35 * _tmp65) - + Scalar(1) / Scalar(2) * _tmp65 * cm; + const Scalar _tmp69 = -_tmp52 * state(3, 0) + _tmp62 - _tmp66; + const Scalar _tmp70 = -Scalar(1) / Scalar(2) * _tmp29 * _tmp69 - + Scalar(1) / Scalar(2) * _tmp37 * + (_tmp31 * (_tmp47 + _tmp57 - _tmp67 * state(3, 0)) + + _tmp33 * (_tmp50 + _tmp64) + _tmp35 * _tmp69) - + Scalar(1) / Scalar(2) * _tmp69 * cm; + const Scalar _tmp71 = + -_tmp56 * state(2, 0) - _tmp63 * state(3, 0) + _tmp68 * state(1, 0) + _tmp70 * state(0, 0); + const Scalar _tmp72 = + _tmp56 * state(3, 0) - _tmp63 * state(2, 0) + _tmp68 * state(0, 0) - _tmp70 * state(1, 0); + const Scalar _tmp73 = + _tmp56 * state(0, 0) - _tmp63 * state(1, 0) - _tmp68 * state(3, 0) + _tmp70 * state(2, 0); + const Scalar _tmp74 = -_tmp37 * (-_tmp41 - _tmp42 - _tmp43) + _tmp40 + _tmp44; + const Scalar _tmp75 = -_tmp25 * _tmp29 - _tmp25 * cm - + _tmp37 * (_tmp14 * _tmp31 + _tmp22 * _tmp33 + _tmp25 * _tmp35); // Output terms (2) if (innov_var != nullptr) { @@ -132,22 +143,22 @@ void ComputeDragYInnovVarAndH(const matrix::Matrix& state, _innov_var = R + - _tmp41 * (P(0, 5) * _tmp51 - P(1, 5) * _tmp64 + P(2, 5) * _tmp56 + P(21, 5) * _tmp72 + - P(22, 5) * _tmp62 + P(3, 5) * _tmp71 + P(4, 5) * _tmp65 + P(5, 5) * _tmp41) + - _tmp51 * (P(0, 0) * _tmp51 - P(1, 0) * _tmp64 + P(2, 0) * _tmp56 + P(21, 0) * _tmp72 + - P(22, 0) * _tmp62 + P(3, 0) * _tmp71 + P(4, 0) * _tmp65 + P(5, 0) * _tmp41) + - _tmp56 * (P(0, 2) * _tmp51 - P(1, 2) * _tmp64 + P(2, 2) * _tmp56 + P(21, 2) * _tmp72 + - P(22, 2) * _tmp62 + P(3, 2) * _tmp71 + P(4, 2) * _tmp65 + P(5, 2) * _tmp41) + - _tmp62 * (P(0, 22) * _tmp51 - P(1, 22) * _tmp64 + P(2, 22) * _tmp56 + P(21, 22) * _tmp72 + - P(22, 22) * _tmp62 + P(3, 22) * _tmp71 + P(4, 22) * _tmp65 + P(5, 22) * _tmp41) - - _tmp64 * (P(0, 1) * _tmp51 - P(1, 1) * _tmp64 + P(2, 1) * _tmp56 + P(21, 1) * _tmp72 + - P(22, 1) * _tmp62 + P(3, 1) * _tmp71 + P(4, 1) * _tmp65 + P(5, 1) * _tmp41) + - _tmp65 * (P(0, 4) * _tmp51 - P(1, 4) * _tmp64 + P(2, 4) * _tmp56 + P(21, 4) * _tmp72 + - P(22, 4) * _tmp62 + P(3, 4) * _tmp71 + P(4, 4) * _tmp65 + P(5, 4) * _tmp41) + - _tmp71 * (P(0, 3) * _tmp51 - P(1, 3) * _tmp64 + P(2, 3) * _tmp56 + P(21, 3) * _tmp72 + - P(22, 3) * _tmp62 + P(3, 3) * _tmp71 + P(4, 3) * _tmp65 + P(5, 3) * _tmp41) + - _tmp72 * (P(0, 21) * _tmp51 - P(1, 21) * _tmp64 + P(2, 21) * _tmp56 + P(21, 21) * _tmp72 + - P(22, 21) * _tmp62 + P(3, 21) * _tmp71 + P(4, 21) * _tmp65 + P(5, 21) * _tmp41); + _tmp38 * (P(0, 21) * _tmp73 + P(1, 21) * _tmp72 + P(2, 21) * _tmp71 + P(21, 21) * _tmp38 + + P(22, 21) * _tmp74 + P(3, 21) * _tmp39 + P(4, 21) * _tmp45 + P(5, 21) * _tmp75) + + _tmp39 * (P(0, 3) * _tmp73 + P(1, 3) * _tmp72 + P(2, 3) * _tmp71 + P(21, 3) * _tmp38 + + P(22, 3) * _tmp74 + P(3, 3) * _tmp39 + P(4, 3) * _tmp45 + P(5, 3) * _tmp75) + + _tmp45 * (P(0, 4) * _tmp73 + P(1, 4) * _tmp72 + P(2, 4) * _tmp71 + P(21, 4) * _tmp38 + + P(22, 4) * _tmp74 + P(3, 4) * _tmp39 + P(4, 4) * _tmp45 + P(5, 4) * _tmp75) + + _tmp71 * (P(0, 2) * _tmp73 + P(1, 2) * _tmp72 + P(2, 2) * _tmp71 + P(21, 2) * _tmp38 + + P(22, 2) * _tmp74 + P(3, 2) * _tmp39 + P(4, 2) * _tmp45 + P(5, 2) * _tmp75) + + _tmp72 * (P(0, 1) * _tmp73 + P(1, 1) * _tmp72 + P(2, 1) * _tmp71 + P(21, 1) * _tmp38 + + P(22, 1) * _tmp74 + P(3, 1) * _tmp39 + P(4, 1) * _tmp45 + P(5, 1) * _tmp75) + + _tmp73 * (P(0, 0) * _tmp73 + P(1, 0) * _tmp72 + P(2, 0) * _tmp71 + P(21, 0) * _tmp38 + + P(22, 0) * _tmp74 + P(3, 0) * _tmp39 + P(4, 0) * _tmp45 + P(5, 0) * _tmp75) + + _tmp74 * (P(0, 22) * _tmp73 + P(1, 22) * _tmp72 + P(2, 22) * _tmp71 + P(21, 22) * _tmp38 + + P(22, 22) * _tmp74 + P(3, 22) * _tmp39 + P(4, 22) * _tmp45 + P(5, 22) * _tmp75) + + _tmp75 * (P(0, 5) * _tmp73 + P(1, 5) * _tmp72 + P(2, 5) * _tmp71 + P(21, 5) * _tmp38 + + P(22, 5) * _tmp74 + P(3, 5) * _tmp39 + P(4, 5) * _tmp45 + P(5, 5) * _tmp75); } if (Hy != nullptr) { @@ -155,14 +166,14 @@ void ComputeDragYInnovVarAndH(const matrix::Matrix& state, _hy.setZero(); - _hy(0, 0) = _tmp51; - _hy(1, 0) = -_tmp64; - _hy(2, 0) = _tmp56; - _hy(3, 0) = _tmp71; - _hy(4, 0) = _tmp65; - _hy(5, 0) = _tmp41; - _hy(21, 0) = _tmp72; - _hy(22, 0) = _tmp62; + _hy(0, 0) = _tmp73; + _hy(1, 0) = _tmp72; + _hy(2, 0) = _tmp71; + _hy(3, 0) = _tmp39; + _hy(4, 0) = _tmp45; + _hy(5, 0) = _tmp75; + _hy(21, 0) = _tmp38; + _hy(22, 0) = _tmp74; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h index 11dfaacfcc0f..856096baf1a4 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h @@ -32,77 +32,88 @@ void ComputeFlowXyInnovVarAndHx(const matrix::Matrix& state, const Scalar R, const Scalar epsilon, matrix::Matrix* const innov_var = nullptr, matrix::Matrix* const H = nullptr) { - // Total ops: 196 + // Total ops: 275 // Input arrays - // Intermediate terms (33) - const Scalar _tmp0 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp2 = 1 - 2 * _tmp1; - const Scalar _tmp3 = + // Intermediate terms (42) + const Scalar _tmp0 = 2 * state(4, 0); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = _tmp1 * state(6, 0); + const Scalar _tmp3 = -_tmp0 * state(3, 0) + _tmp2; + const Scalar _tmp4 = Scalar(1.0) / (distance + epsilon * (2 * math::min(0, (((distance) > 0) - ((distance) < 0))) + 1)); - const Scalar _tmp4 = _tmp3 * (-2 * _tmp0 + _tmp2); - const Scalar _tmp5 = 2 * state(2, 0); - const Scalar _tmp6 = _tmp5 * state(0, 0); - const Scalar _tmp7 = 2 * state(1, 0) * state(3, 0); - const Scalar _tmp8 = _tmp5 * state(3, 0); + const Scalar _tmp5 = (Scalar(1) / Scalar(2)) * _tmp4; + const Scalar _tmp6 = _tmp5 * state(2, 0); + const Scalar _tmp7 = 2 * state(3, 0) * state(6, 0); + const Scalar _tmp8 = _tmp5 * (_tmp0 * state(1, 0) + _tmp7); const Scalar _tmp9 = 2 * state(0, 0); - const Scalar _tmp10 = _tmp9 * state(1, 0); - const Scalar _tmp11 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp12 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp13 = -_tmp0; - const Scalar _tmp14 = _tmp12 + _tmp13; - const Scalar _tmp15 = _tmp3 * (state(4, 0) * (_tmp6 + _tmp7) + state(5, 0) * (-_tmp10 + _tmp8) + - state(6, 0) * (_tmp1 - _tmp11 + _tmp14)); - const Scalar _tmp16 = _tmp9 * state(3, 0); - const Scalar _tmp17 = -_tmp16; - const Scalar _tmp18 = _tmp5 * state(1, 0); - const Scalar _tmp19 = _tmp17 + _tmp18; - const Scalar _tmp20 = _tmp19 * _tmp3; - const Scalar _tmp21 = _tmp10 + _tmp8; - const Scalar _tmp22 = _tmp21 * _tmp3; - const Scalar _tmp23 = -_tmp7; - const Scalar _tmp24 = -_tmp12; - const Scalar _tmp25 = _tmp3 * (state(4, 0) * (_tmp1 + _tmp11 + _tmp13 + _tmp24) + - state(5, 0) * (_tmp17 - _tmp18) + state(6, 0) * (_tmp23 + _tmp6)); - const Scalar _tmp26 = _tmp3 * (-2 * _tmp11 + _tmp2); - const Scalar _tmp27 = -_tmp6; - const Scalar _tmp28 = -_tmp1 + _tmp11; - const Scalar _tmp29 = _tmp3 * (state(4, 0) * (_tmp23 + _tmp27) + state(5, 0) * (_tmp10 - _tmp8) + - state(6, 0) * (_tmp0 + _tmp24 + _tmp28)); - const Scalar _tmp30 = - _tmp3 * (_tmp19 * state(4, 0) + _tmp21 * state(6, 0) + state(5, 0) * (_tmp14 + _tmp28)); - const Scalar _tmp31 = _tmp3 * (_tmp16 + _tmp18); - const Scalar _tmp32 = _tmp3 * (_tmp27 + _tmp7); + const Scalar _tmp10 = state(3, 0) * state(5, 0); + const Scalar _tmp11 = 2 * state(2, 0); + const Scalar _tmp12 = _tmp11 * state(6, 0); + const Scalar _tmp13 = -4 * _tmp10 + _tmp12 - _tmp9 * state(4, 0); + const Scalar _tmp14 = _tmp5 * state(1, 0); + const Scalar _tmp15 = _tmp9 * state(6, 0); + const Scalar _tmp16 = _tmp0 * state(2, 0) + _tmp15 - 4 * state(1, 0) * state(5, 0); + const Scalar _tmp17 = _tmp5 * state(3, 0); + const Scalar _tmp18 = -_tmp13 * _tmp14 + _tmp16 * _tmp17 - _tmp3 * _tmp6 + _tmp8 * state(0, 0); + const Scalar _tmp19 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp20 = _tmp4 * (_tmp19 - 2 * std::pow(state(1, 0), Scalar(2))); + const Scalar _tmp21 = _tmp3 * _tmp5; + const Scalar _tmp22 = _tmp5 * state(0, 0); + const Scalar _tmp23 = + _tmp13 * _tmp6 + _tmp16 * _tmp22 - _tmp21 * state(1, 0) - _tmp8 * state(3, 0); + const Scalar _tmp24 = + _tmp13 * _tmp22 - _tmp16 * _tmp6 - _tmp21 * state(3, 0) + _tmp8 * state(1, 0); + const Scalar _tmp25 = _tmp9 * state(3, 0); + const Scalar _tmp26 = _tmp1 * state(2, 0); + const Scalar _tmp27 = _tmp4 * (-_tmp25 + _tmp26); + const Scalar _tmp28 = _tmp4 * (_tmp11 * state(3, 0) + _tmp9 * state(1, 0)); + const Scalar _tmp29 = _tmp4 * (_tmp19 - 2 * std::pow(state(2, 0), Scalar(2))); + const Scalar _tmp30 = 4 * state(4, 0); + const Scalar _tmp31 = _tmp2 - _tmp30 * state(3, 0) + _tmp9 * state(5, 0); + const Scalar _tmp32 = 2 * state(5, 0); + const Scalar _tmp33 = -_tmp15 - _tmp30 * state(2, 0) + _tmp32 * state(1, 0); + const Scalar _tmp34 = _tmp32 * state(2, 0) + _tmp7; + const Scalar _tmp35 = 2 * _tmp10 - _tmp12; + const Scalar _tmp36 = _tmp35 * _tmp5; + const Scalar _tmp37 = _tmp17 * _tmp33 - _tmp22 * _tmp34 - _tmp31 * _tmp6 + _tmp36 * state(1, 0); + const Scalar _tmp38 = -_tmp14 * _tmp33 - _tmp22 * _tmp31 + _tmp34 * _tmp6 + _tmp36 * state(3, 0); + const Scalar _tmp39 = _tmp14 * _tmp31 - _tmp17 * _tmp34 - _tmp22 * _tmp33 + _tmp35 * _tmp6; + const Scalar _tmp40 = _tmp4 * (_tmp25 + _tmp26); + const Scalar _tmp41 = _tmp4 * (_tmp1 * state(3, 0) - _tmp9 * state(2, 0)); // Output terms (2) if (innov_var != nullptr) { matrix::Matrix& _innov_var = (*innov_var); _innov_var(0, 0) = R + - _tmp15 * (P(0, 0) * _tmp15 + P(2, 0) * _tmp25 + P(3, 0) * _tmp20 + - P(4, 0) * _tmp4 + P(5, 0) * _tmp22) + - _tmp20 * (P(0, 3) * _tmp15 + P(2, 3) * _tmp25 + P(3, 3) * _tmp20 + - P(4, 3) * _tmp4 + P(5, 3) * _tmp22) + - _tmp22 * (P(0, 5) * _tmp15 + P(2, 5) * _tmp25 + P(3, 5) * _tmp20 + - P(4, 5) * _tmp4 + P(5, 5) * _tmp22) + - _tmp25 * (P(0, 2) * _tmp15 + P(2, 2) * _tmp25 + P(3, 2) * _tmp20 + - P(4, 2) * _tmp4 + P(5, 2) * _tmp22) + - _tmp4 * (P(0, 4) * _tmp15 + P(2, 4) * _tmp25 + P(3, 4) * _tmp20 + - P(4, 4) * _tmp4 + P(5, 4) * _tmp22); + _tmp18 * (P(0, 1) * _tmp23 + P(1, 1) * _tmp18 + P(2, 1) * _tmp24 + + P(3, 1) * _tmp27 + P(4, 1) * _tmp20 + P(5, 1) * _tmp28) + + _tmp20 * (P(0, 4) * _tmp23 + P(1, 4) * _tmp18 + P(2, 4) * _tmp24 + + P(3, 4) * _tmp27 + P(4, 4) * _tmp20 + P(5, 4) * _tmp28) + + _tmp23 * (P(0, 0) * _tmp23 + P(1, 0) * _tmp18 + P(2, 0) * _tmp24 + + P(3, 0) * _tmp27 + P(4, 0) * _tmp20 + P(5, 0) * _tmp28) + + _tmp24 * (P(0, 2) * _tmp23 + P(1, 2) * _tmp18 + P(2, 2) * _tmp24 + + P(3, 2) * _tmp27 + P(4, 2) * _tmp20 + P(5, 2) * _tmp28) + + _tmp27 * (P(0, 3) * _tmp23 + P(1, 3) * _tmp18 + P(2, 3) * _tmp24 + + P(3, 3) * _tmp27 + P(4, 3) * _tmp20 + P(5, 3) * _tmp28) + + _tmp28 * (P(0, 5) * _tmp23 + P(1, 5) * _tmp18 + P(2, 5) * _tmp24 + + P(3, 5) * _tmp27 + P(4, 5) * _tmp20 + P(5, 5) * _tmp28); _innov_var(1, 0) = R - - _tmp26 * (-P(1, 3) * _tmp29 - P(2, 3) * _tmp30 - P(3, 3) * _tmp26 - - P(4, 3) * _tmp31 - P(5, 3) * _tmp32) - - _tmp29 * (-P(1, 1) * _tmp29 - P(2, 1) * _tmp30 - P(3, 1) * _tmp26 - - P(4, 1) * _tmp31 - P(5, 1) * _tmp32) - - _tmp30 * (-P(1, 2) * _tmp29 - P(2, 2) * _tmp30 - P(3, 2) * _tmp26 - - P(4, 2) * _tmp31 - P(5, 2) * _tmp32) - - _tmp31 * (-P(1, 4) * _tmp29 - P(2, 4) * _tmp30 - P(3, 4) * _tmp26 - - P(4, 4) * _tmp31 - P(5, 4) * _tmp32) - - _tmp32 * (-P(1, 5) * _tmp29 - P(2, 5) * _tmp30 - P(3, 5) * _tmp26 - - P(4, 5) * _tmp31 - P(5, 5) * _tmp32); + _tmp29 * (P(0, 3) * _tmp37 + P(1, 3) * _tmp39 + P(2, 3) * _tmp38 - + P(3, 3) * _tmp29 - P(4, 3) * _tmp40 - P(5, 3) * _tmp41) + + _tmp37 * (P(0, 0) * _tmp37 + P(1, 0) * _tmp39 + P(2, 0) * _tmp38 - + P(3, 0) * _tmp29 - P(4, 0) * _tmp40 - P(5, 0) * _tmp41) + + _tmp38 * (P(0, 2) * _tmp37 + P(1, 2) * _tmp39 + P(2, 2) * _tmp38 - + P(3, 2) * _tmp29 - P(4, 2) * _tmp40 - P(5, 2) * _tmp41) + + _tmp39 * (P(0, 1) * _tmp37 + P(1, 1) * _tmp39 + P(2, 1) * _tmp38 - + P(3, 1) * _tmp29 - P(4, 1) * _tmp40 - P(5, 1) * _tmp41) - + _tmp40 * (P(0, 4) * _tmp37 + P(1, 4) * _tmp39 + P(2, 4) * _tmp38 - + P(3, 4) * _tmp29 - P(4, 4) * _tmp40 - P(5, 4) * _tmp41) - + _tmp41 * (P(0, 5) * _tmp37 + P(1, 5) * _tmp39 + P(2, 5) * _tmp38 - + P(3, 5) * _tmp29 - P(4, 5) * _tmp40 - P(5, 5) * _tmp41); } if (H != nullptr) { @@ -110,11 +121,12 @@ void ComputeFlowXyInnovVarAndHx(const matrix::Matrix& state, _h.setZero(); - _h(0, 0) = _tmp15; - _h(2, 0) = _tmp25; - _h(3, 0) = _tmp20; - _h(4, 0) = _tmp4; - _h(5, 0) = _tmp22; + _h(0, 0) = _tmp23; + _h(1, 0) = _tmp18; + _h(2, 0) = _tmp24; + _h(3, 0) = _tmp27; + _h(4, 0) = _tmp20; + _h(5, 0) = _tmp28; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h index 3e00a2f60490..2de18c1f1877 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h @@ -32,51 +32,56 @@ void ComputeFlowYInnovVarAndH(const matrix::Matrix& state, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, matrix::Matrix* const H = nullptr) { - // Total ops: 116 + // Total ops: 151 // Input arrays - // Intermediate terms (19) - const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp2 = + // Intermediate terms (21) + const Scalar _tmp0 = Scalar(1.0) / (distance + epsilon * (2 * math::min(0, (((distance) > 0) - ((distance) < 0))) + 1)); - const Scalar _tmp3 = _tmp2 * (-2 * _tmp0 - 2 * _tmp1 + 1); - const Scalar _tmp4 = -2 * state(0, 0) * state(2, 0); - const Scalar _tmp5 = 2 * state(3, 0); - const Scalar _tmp6 = _tmp5 * state(1, 0); - const Scalar _tmp7 = _tmp5 * state(2, 0); + const Scalar _tmp1 = + _tmp0 * (-2 * std::pow(state(2, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1); + const Scalar _tmp2 = 4 * state(4, 0); + const Scalar _tmp3 = 2 * state(0, 0); + const Scalar _tmp4 = 2 * state(6, 0); + const Scalar _tmp5 = -_tmp2 * state(3, 0) + _tmp3 * state(5, 0) + _tmp4 * state(1, 0); + const Scalar _tmp6 = (Scalar(1) / Scalar(2)) * _tmp0; + const Scalar _tmp7 = _tmp5 * _tmp6; const Scalar _tmp8 = 2 * state(1, 0); - const Scalar _tmp9 = _tmp8 * state(0, 0); - const Scalar _tmp10 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp11 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp12 = -_tmp0 + _tmp1; - const Scalar _tmp13 = _tmp2 * (state(4, 0) * (_tmp4 - _tmp6) + state(5, 0) * (-_tmp7 + _tmp9) + - state(6, 0) * (-_tmp10 + _tmp11 + _tmp12)); - const Scalar _tmp14 = _tmp5 * state(0, 0); - const Scalar _tmp15 = _tmp8 * state(2, 0); - const Scalar _tmp16 = - _tmp2 * (state(4, 0) * (-_tmp14 + _tmp15) + state(5, 0) * (_tmp10 - _tmp11 + _tmp12) + - state(6, 0) * (_tmp7 + _tmp9)); - const Scalar _tmp17 = _tmp2 * (_tmp14 + _tmp15); - const Scalar _tmp18 = _tmp2 * (_tmp4 + _tmp6); + const Scalar _tmp9 = -_tmp2 * state(2, 0) - _tmp4 * state(0, 0) + _tmp8 * state(5, 0); + const Scalar _tmp10 = _tmp6 * _tmp9; + const Scalar _tmp11 = 2 * state(5, 0); + const Scalar _tmp12 = _tmp6 * (_tmp11 * state(2, 0) + _tmp4 * state(3, 0)); + const Scalar _tmp13 = _tmp11 * state(3, 0) - _tmp4 * state(2, 0); + const Scalar _tmp14 = _tmp6 * state(1, 0); + const Scalar _tmp15 = + _tmp10 * state(3, 0) - _tmp12 * state(0, 0) + _tmp13 * _tmp14 - _tmp7 * state(2, 0); + const Scalar _tmp16 = _tmp13 * _tmp6; + const Scalar _tmp17 = + _tmp12 * state(2, 0) - _tmp14 * _tmp9 + _tmp16 * state(3, 0) - _tmp7 * state(0, 0); + const Scalar _tmp18 = + -_tmp10 * state(0, 0) - _tmp12 * state(3, 0) + _tmp14 * _tmp5 + _tmp16 * state(2, 0); + const Scalar _tmp19 = _tmp0 * (_tmp3 * state(3, 0) + _tmp8 * state(2, 0)); + const Scalar _tmp20 = _tmp0 * (-_tmp3 * state(2, 0) + _tmp8 * state(3, 0)); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); _innov_var = R - - _tmp13 * (-P(1, 1) * _tmp13 - P(2, 1) * _tmp16 - P(3, 1) * _tmp3 - - P(4, 1) * _tmp17 - P(5, 1) * _tmp18) - - _tmp16 * (-P(1, 2) * _tmp13 - P(2, 2) * _tmp16 - P(3, 2) * _tmp3 - - P(4, 2) * _tmp17 - P(5, 2) * _tmp18) - - _tmp17 * (-P(1, 4) * _tmp13 - P(2, 4) * _tmp16 - P(3, 4) * _tmp3 - - P(4, 4) * _tmp17 - P(5, 4) * _tmp18) - - _tmp18 * (-P(1, 5) * _tmp13 - P(2, 5) * _tmp16 - P(3, 5) * _tmp3 - - P(4, 5) * _tmp17 - P(5, 5) * _tmp18) - - _tmp3 * (-P(1, 3) * _tmp13 - P(2, 3) * _tmp16 - P(3, 3) * _tmp3 - - P(4, 3) * _tmp17 - P(5, 3) * _tmp18); + _tmp1 * (P(0, 3) * _tmp15 + P(1, 3) * _tmp18 + P(2, 3) * _tmp17 - P(3, 3) * _tmp1 - + P(4, 3) * _tmp19 - P(5, 3) * _tmp20) + + _tmp15 * (P(0, 0) * _tmp15 + P(1, 0) * _tmp18 + P(2, 0) * _tmp17 - + P(3, 0) * _tmp1 - P(4, 0) * _tmp19 - P(5, 0) * _tmp20) + + _tmp17 * (P(0, 2) * _tmp15 + P(1, 2) * _tmp18 + P(2, 2) * _tmp17 - + P(3, 2) * _tmp1 - P(4, 2) * _tmp19 - P(5, 2) * _tmp20) + + _tmp18 * (P(0, 1) * _tmp15 + P(1, 1) * _tmp18 + P(2, 1) * _tmp17 - + P(3, 1) * _tmp1 - P(4, 1) * _tmp19 - P(5, 1) * _tmp20) - + _tmp19 * (P(0, 4) * _tmp15 + P(1, 4) * _tmp18 + P(2, 4) * _tmp17 - + P(3, 4) * _tmp1 - P(4, 4) * _tmp19 - P(5, 4) * _tmp20) - + _tmp20 * (P(0, 5) * _tmp15 + P(1, 5) * _tmp18 + P(2, 5) * _tmp17 - + P(3, 5) * _tmp1 - P(4, 5) * _tmp19 - P(5, 5) * _tmp20); } if (H != nullptr) { @@ -84,11 +89,12 @@ void ComputeFlowYInnovVarAndH(const matrix::Matrix& state, _h.setZero(); - _h(1, 0) = -_tmp13; - _h(2, 0) = -_tmp16; - _h(3, 0) = -_tmp3; - _h(4, 0) = -_tmp17; - _h(5, 0) = -_tmp18; + _h(0, 0) = _tmp15; + _h(1, 0) = _tmp18; + _h(2, 0) = _tmp17; + _h(3, 0) = -_tmp1; + _h(4, 0) = -_tmp19; + _h(5, 0) = -_tmp20; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h index d1be17dc3556..d11b74d3e395 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h @@ -34,57 +34,62 @@ void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix& state, const Scalar epsilon, Scalar* const meas_pred = nullptr, Scalar* const innov_var = nullptr, matrix::Matrix* const H = nullptr) { - // Total ops: 95 + // Total ops: 114 // Input arrays - // Intermediate terms (28) - const Scalar _tmp0 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp2 = 1 - 2 * _tmp1; - const Scalar _tmp3 = std::sin(antenna_yaw_offset); - const Scalar _tmp4 = 2 * state(0, 0); - const Scalar _tmp5 = _tmp4 * state(3, 0); - const Scalar _tmp6 = 2 * state(2, 0); - const Scalar _tmp7 = _tmp6 * state(1, 0); - const Scalar _tmp8 = std::cos(antenna_yaw_offset); - const Scalar _tmp9 = _tmp3 * (-2 * _tmp0 + _tmp2) + _tmp8 * (_tmp5 + _tmp7); - const Scalar _tmp10 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp11 = -_tmp5; - const Scalar _tmp12 = _tmp11 + _tmp7; - const Scalar _tmp13 = _tmp12 * _tmp3 + _tmp8 * (-2 * _tmp10 + _tmp2); - const Scalar _tmp14 = _tmp13 + epsilon * ((((_tmp13) > 0) - ((_tmp13) < 0)) + Scalar(0.5)); - const Scalar _tmp15 = _tmp6 * state(0, 0); - const Scalar _tmp16 = 2 * state(1, 0) * state(3, 0); - const Scalar _tmp17 = std::pow(_tmp14, Scalar(2)); - const Scalar _tmp18 = _tmp9 / _tmp17; - const Scalar _tmp19 = _tmp6 * state(3, 0); - const Scalar _tmp20 = _tmp4 * state(1, 0); - const Scalar _tmp21 = Scalar(1.0) / (_tmp14); - const Scalar _tmp22 = _tmp17 / (_tmp17 + std::pow(_tmp9, Scalar(2))); - const Scalar _tmp23 = - _tmp22 * (-_tmp18 * _tmp8 * (-_tmp15 - _tmp16) + _tmp21 * _tmp8 * (-_tmp19 + _tmp20)); - const Scalar _tmp24 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp25 = -_tmp0 + _tmp10; - const Scalar _tmp26 = - _tmp22 * (-_tmp18 * (_tmp12 * _tmp8 + _tmp3 * (_tmp1 - _tmp24 + _tmp25)) + - _tmp21 * (_tmp3 * (_tmp11 - _tmp7) + _tmp8 * (-_tmp1 + _tmp24 + _tmp25))); + // Intermediate terms (29) + const Scalar _tmp0 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp1 = std::sin(antenna_yaw_offset); + const Scalar _tmp2 = 2 * state(0, 0) * state(3, 0); + const Scalar _tmp3 = 2 * state(1, 0) * state(2, 0); + const Scalar _tmp4 = std::cos(antenna_yaw_offset); + const Scalar _tmp5 = + _tmp1 * (_tmp0 - 2 * std::pow(state(1, 0), Scalar(2))) + _tmp4 * (_tmp2 + _tmp3); + const Scalar _tmp6 = + _tmp1 * (-_tmp2 + _tmp3) + _tmp4 * (_tmp0 - 2 * std::pow(state(2, 0), Scalar(2))); + const Scalar _tmp7 = _tmp6 + epsilon * ((((_tmp6) > 0) - ((_tmp6) < 0)) + Scalar(0.5)); + const Scalar _tmp8 = 2 * _tmp1; + const Scalar _tmp9 = std::pow(_tmp7, Scalar(2)); + const Scalar _tmp10 = _tmp5 / _tmp9; + const Scalar _tmp11 = _tmp10 * _tmp8; + const Scalar _tmp12 = 4 * _tmp1; + const Scalar _tmp13 = 2 * _tmp4; + const Scalar _tmp14 = Scalar(1.0) / (_tmp7); + const Scalar _tmp15 = + -_tmp11 * state(2, 0) + _tmp14 * (-_tmp12 * state(1, 0) + _tmp13 * state(2, 0)); + const Scalar _tmp16 = (Scalar(1) / Scalar(2)) * _tmp9 / (std::pow(_tmp5, Scalar(2)) + _tmp9); + const Scalar _tmp17 = _tmp15 * _tmp16; + const Scalar _tmp18 = _tmp13 * _tmp14; + const Scalar _tmp19 = _tmp11 * state(3, 0) + _tmp18 * state(3, 0); + const Scalar _tmp20 = _tmp16 * _tmp19; + const Scalar _tmp21 = 4 * _tmp4; + const Scalar _tmp22 = -_tmp10 * (-_tmp21 * state(3, 0) - _tmp8 * state(0, 0)) + + _tmp14 * (-_tmp12 * state(3, 0) + _tmp13 * state(0, 0)); + const Scalar _tmp23 = _tmp16 * state(2, 0); + const Scalar _tmp24 = + _tmp16 * (-_tmp10 * (-_tmp21 * state(2, 0) + _tmp8 * state(1, 0)) + _tmp18 * state(1, 0)); + const Scalar _tmp25 = + _tmp17 * state(0, 0) - _tmp20 * state(1, 0) + _tmp22 * _tmp23 - _tmp24 * state(3, 0); + const Scalar _tmp26 = _tmp16 * _tmp22; const Scalar _tmp27 = - _tmp22 * (-_tmp18 * _tmp3 * (_tmp15 + _tmp16) + _tmp21 * _tmp3 * (_tmp19 - _tmp20)); + _tmp17 * state(3, 0) - _tmp19 * _tmp23 + _tmp24 * state(0, 0) - _tmp26 * state(1, 0); + const Scalar _tmp28 = + -_tmp15 * _tmp23 - _tmp20 * state(3, 0) + _tmp24 * state(1, 0) + _tmp26 * state(0, 0); // Output terms (3) if (meas_pred != nullptr) { Scalar& _meas_pred = (*meas_pred); - _meas_pred = std::atan2(_tmp9, _tmp14); + _meas_pred = std::atan2(_tmp5, _tmp7); } if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = R + _tmp23 * (P(0, 1) * _tmp27 + P(1, 1) * _tmp23 + P(2, 1) * _tmp26) + - _tmp26 * (P(0, 2) * _tmp27 + P(1, 2) * _tmp23 + P(2, 2) * _tmp26) + - _tmp27 * (P(0, 0) * _tmp27 + P(1, 0) * _tmp23 + P(2, 0) * _tmp26); + _innov_var = R + _tmp25 * (P(0, 0) * _tmp25 + P(1, 0) * _tmp27 + P(2, 0) * _tmp28) + + _tmp27 * (P(0, 1) * _tmp25 + P(1, 1) * _tmp27 + P(2, 1) * _tmp28) + + _tmp28 * (P(0, 2) * _tmp25 + P(1, 2) * _tmp27 + P(2, 2) * _tmp28); } if (H != nullptr) { @@ -92,9 +97,9 @@ void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix& state, _h.setZero(); - _h(0, 0) = _tmp27; - _h(1, 0) = _tmp23; - _h(2, 0) = _tmp26; + _h(0, 0) = _tmp25; + _h(1, 0) = _tmp27; + _h(2, 0) = _tmp28; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h index f3f074e82db7..6d47ae4ab435 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h @@ -29,38 +29,35 @@ void ComputeGravityXyzInnovVarAndHx(const matrix::Matrix& state, const matrix::Matrix& P, const Scalar R, matrix::Matrix* const innov_var = nullptr, matrix::Matrix* const Hx = nullptr) { - // Total ops: 51 + // Total ops: 53 // Input arrays - // Intermediate terms (16) - const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp2 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp3 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp4 = _tmp0 + _tmp1 - _tmp2 - _tmp3; - const Scalar _tmp5 = 2 * state(2, 0); - const Scalar _tmp6 = _tmp5 * state(3, 0); - const Scalar _tmp7 = 2 * state(1, 0); - const Scalar _tmp8 = _tmp7 * state(0, 0); - const Scalar _tmp9 = -_tmp6 - _tmp8; - const Scalar _tmp10 = -_tmp0 - _tmp1 + _tmp2 + _tmp3; - const Scalar _tmp11 = _tmp5 * state(0, 0); - const Scalar _tmp12 = _tmp7 * state(3, 0); - const Scalar _tmp13 = -_tmp11 + _tmp12; - const Scalar _tmp14 = _tmp6 + _tmp8; - const Scalar _tmp15 = _tmp11 - _tmp12; + // Intermediate terms (13) + const Scalar _tmp0 = 2 * state(0, 0); + const Scalar _tmp1 = -_tmp0 * state(3, 0); + const Scalar _tmp2 = 2 * state(2, 0); + const Scalar _tmp3 = _tmp2 * state(1, 0); + const Scalar _tmp4 = _tmp1 - _tmp3; + const Scalar _tmp5 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp6 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp7 = std::pow(state(1, 0), Scalar(2)) - std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp8 = -_tmp5 + _tmp6 + _tmp7; + const Scalar _tmp9 = _tmp1 + _tmp3; + const Scalar _tmp10 = _tmp5 - _tmp6 + _tmp7; + const Scalar _tmp11 = _tmp0 * state(1, 0) - _tmp2 * state(3, 0); + const Scalar _tmp12 = _tmp2 * state(0, 0) + 2 * state(1, 0) * state(3, 0); // Output terms (2) if (innov_var != nullptr) { matrix::Matrix& _innov_var = (*innov_var); - _innov_var(0, 0) = R + _tmp4 * (P(1, 1) * _tmp4 + P(2, 1) * _tmp9) + - _tmp9 * (P(1, 2) * _tmp4 + P(2, 2) * _tmp9); - _innov_var(1, 0) = R + _tmp10 * (P(0, 0) * _tmp10 + P(2, 0) * _tmp13) + - _tmp13 * (P(0, 2) * _tmp10 + P(2, 2) * _tmp13); - _innov_var(2, 0) = R + _tmp14 * (P(0, 0) * _tmp14 + P(1, 0) * _tmp15) + - _tmp15 * (P(0, 1) * _tmp14 + P(1, 1) * _tmp15); + _innov_var(0, 0) = R + _tmp4 * (P(0, 0) * _tmp4 + P(1, 0) * _tmp8) + + _tmp8 * (P(0, 1) * _tmp4 + P(1, 1) * _tmp8); + _innov_var(1, 0) = R + _tmp10 * (P(0, 0) * _tmp10 + P(1, 0) * _tmp9) + + _tmp9 * (P(0, 1) * _tmp10 + P(1, 1) * _tmp9); + _innov_var(2, 0) = R + _tmp11 * (P(0, 0) * _tmp11 + P(1, 0) * _tmp12) + + _tmp12 * (P(0, 1) * _tmp11 + P(1, 1) * _tmp12); } if (Hx != nullptr) { @@ -68,8 +65,8 @@ void ComputeGravityXyzInnovVarAndHx(const matrix::Matrix& state, _hx.setZero(); - _hx(1, 0) = _tmp4; - _hx(2, 0) = _tmp9; + _hx(0, 0) = _tmp4; + _hx(1, 0) = _tmp8; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h index 2c3a11b682e5..9aeb442d6970 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h @@ -34,16 +34,16 @@ void ComputeGravityYInnovVarAndH(const matrix::Matrix& state, // Input arrays // Intermediate terms (2) - const Scalar _tmp0 = -std::pow(state(0, 0), Scalar(2)) + std::pow(state(1, 0), Scalar(2)) + - std::pow(state(2, 0), Scalar(2)) - std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = -2 * state(0, 0) * state(2, 0) + 2 * state(1, 0) * state(3, 0); + const Scalar _tmp0 = -2 * state(0, 0) * state(3, 0) + 2 * state(1, 0) * state(2, 0); + const Scalar _tmp1 = -std::pow(state(0, 0), Scalar(2)) + std::pow(state(1, 0), Scalar(2)) - + std::pow(state(2, 0), Scalar(2)) + std::pow(state(3, 0), Scalar(2)); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = R + _tmp0 * (P(0, 0) * _tmp0 + P(2, 0) * _tmp1) + - _tmp1 * (P(0, 2) * _tmp0 + P(2, 2) * _tmp1); + _innov_var = R + _tmp0 * (P(0, 1) * _tmp1 + P(1, 1) * _tmp0) + + _tmp1 * (P(0, 0) * _tmp1 + P(1, 0) * _tmp0); } if (Hy != nullptr) { @@ -51,8 +51,8 @@ void ComputeGravityYInnovVarAndH(const matrix::Matrix& state, _hy.setZero(); - _hy(0, 0) = _tmp0; - _hy(2, 0) = _tmp1; + _hy(0, 0) = _tmp1; + _hy(1, 0) = _tmp0; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h index 43d48e128321..e62e3e7212c3 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h @@ -36,8 +36,8 @@ void ComputeGravityZInnovVarAndH(const matrix::Matrix& state, // Intermediate terms (4) const Scalar _tmp0 = 2 * state(2, 0); const Scalar _tmp1 = 2 * state(1, 0); - const Scalar _tmp2 = _tmp0 * state(3, 0) + _tmp1 * state(0, 0); - const Scalar _tmp3 = _tmp0 * state(0, 0) - _tmp1 * state(3, 0); + const Scalar _tmp2 = -_tmp0 * state(3, 0) + _tmp1 * state(0, 0); + const Scalar _tmp3 = _tmp0 * state(0, 0) + _tmp1 * state(3, 0); // Output terms (2) if (innov_var != nullptr) { diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h index dde9a8cd9ee9..bdad52b5a5b9 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h @@ -35,114 +35,153 @@ void ComputeMagInnovInnovVarAndHx(const matrix::Matrix& state, matrix::Matrix* const innov = nullptr, matrix::Matrix* const innov_var = nullptr, matrix::Matrix* const Hx = nullptr) { - // Total ops: 314 + // Total ops: 461 // Unused inputs (void)epsilon; // Input arrays - // Intermediate terms (47) - const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = -2 * _tmp0; - const Scalar _tmp2 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp3 = -2 * _tmp2; - const Scalar _tmp4 = _tmp1 + _tmp3 + 1; - const Scalar _tmp5 = 2 * state(0, 0); - const Scalar _tmp6 = _tmp5 * state(3, 0); - const Scalar _tmp7 = 2 * state(1, 0); - const Scalar _tmp8 = _tmp7 * state(2, 0); - const Scalar _tmp9 = _tmp6 + _tmp8; - const Scalar _tmp10 = _tmp5 * state(2, 0); - const Scalar _tmp11 = -_tmp10; - const Scalar _tmp12 = _tmp7 * state(3, 0); - const Scalar _tmp13 = _tmp11 + _tmp12; - const Scalar _tmp14 = _tmp13 * state(18, 0) + _tmp9 * state(17, 0); - const Scalar _tmp15 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp16 = 1 - 2 * _tmp15; - const Scalar _tmp17 = _tmp1 + _tmp16; - const Scalar _tmp18 = 2 * state(2, 0) * state(3, 0); - const Scalar _tmp19 = _tmp7 * state(0, 0); - const Scalar _tmp20 = _tmp18 + _tmp19; - const Scalar _tmp21 = -_tmp6; - const Scalar _tmp22 = _tmp21 + _tmp8; - const Scalar _tmp23 = _tmp20 * state(18, 0) + _tmp22 * state(16, 0); - const Scalar _tmp24 = _tmp16 + _tmp3; - const Scalar _tmp25 = -_tmp19; - const Scalar _tmp26 = _tmp18 + _tmp25; - const Scalar _tmp27 = _tmp10 + _tmp12; - const Scalar _tmp28 = _tmp26 * state(17, 0) + _tmp27 * state(16, 0); - const Scalar _tmp29 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp30 = -_tmp29; - const Scalar _tmp31 = _tmp2 + _tmp30; - const Scalar _tmp32 = -_tmp0; - const Scalar _tmp33 = _tmp15 + _tmp32; - const Scalar _tmp34 = -_tmp18; - const Scalar _tmp35 = -_tmp12; - const Scalar _tmp36 = state(16, 0) * (_tmp11 + _tmp35) + state(17, 0) * (_tmp19 + _tmp34) + - state(18, 0) * (_tmp31 + _tmp33); - const Scalar _tmp37 = -_tmp15; - const Scalar _tmp38 = _tmp23 + state(17, 0) * (_tmp2 + _tmp29 + _tmp32 + _tmp37); - const Scalar _tmp39 = _tmp0 + _tmp37; - const Scalar _tmp40 = -_tmp8; - const Scalar _tmp41 = state(16, 0) * (_tmp31 + _tmp39) + state(17, 0) * (_tmp21 + _tmp40) + - state(18, 0) * (_tmp10 + _tmp35); - const Scalar _tmp42 = -_tmp2; - const Scalar _tmp43 = _tmp29 + _tmp42; - const Scalar _tmp44 = _tmp28 + state(18, 0) * (_tmp39 + _tmp43); - const Scalar _tmp45 = _tmp14 + state(16, 0) * (_tmp33 + _tmp43); - const Scalar _tmp46 = state(16, 0) * (_tmp40 + _tmp6) + - state(17, 0) * (_tmp0 + _tmp15 + _tmp30 + _tmp42) + - state(18, 0) * (_tmp25 + _tmp34); + // Intermediate terms (68) + const Scalar _tmp0 = -2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp1 = 1 - 2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp2 = _tmp0 + _tmp1; + const Scalar _tmp3 = 2 * state(3, 0); + const Scalar _tmp4 = _tmp3 * state(0, 0); + const Scalar _tmp5 = 2 * state(2, 0); + const Scalar _tmp6 = _tmp5 * state(1, 0); + const Scalar _tmp7 = _tmp4 + _tmp6; + const Scalar _tmp8 = _tmp5 * state(0, 0); + const Scalar _tmp9 = 2 * state(1, 0); + const Scalar _tmp10 = _tmp9 * state(3, 0); + const Scalar _tmp11 = _tmp10 - _tmp8; + const Scalar _tmp12 = -2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp13 = _tmp0 + _tmp12 + 1; + const Scalar _tmp14 = _tmp5 * state(3, 0); + const Scalar _tmp15 = _tmp9 * state(0, 0); + const Scalar _tmp16 = _tmp14 + _tmp15; + const Scalar _tmp17 = -_tmp4 + _tmp6; + const Scalar _tmp18 = _tmp1 + _tmp12; + const Scalar _tmp19 = _tmp14 - _tmp15; + const Scalar _tmp20 = _tmp10 + _tmp8; + const Scalar _tmp21 = _tmp3 * state(18, 0); + const Scalar _tmp22 = _tmp5 * state(17, 0); + const Scalar _tmp23 = _tmp21 + _tmp22; + const Scalar _tmp24 = (Scalar(1) / Scalar(2)) * state(2, 0); + const Scalar _tmp25 = 2 * state(17, 0); + const Scalar _tmp26 = _tmp25 * state(3, 0); + const Scalar _tmp27 = _tmp5 * state(18, 0); + const Scalar _tmp28 = _tmp26 - _tmp27; + const Scalar _tmp29 = (Scalar(1) / Scalar(2)) * _tmp28; + const Scalar _tmp30 = 4 * state(2, 0); + const Scalar _tmp31 = _tmp9 * state(17, 0); + const Scalar _tmp32 = 2 * state(0, 0); + const Scalar _tmp33 = _tmp32 * state(18, 0); + const Scalar _tmp34 = -_tmp30 * state(16, 0) + _tmp31 - _tmp33; + const Scalar _tmp35 = (Scalar(1) / Scalar(2)) * state(1, 0); + const Scalar _tmp36 = _tmp9 * state(18, 0); + const Scalar _tmp37 = _tmp25 * state(0, 0); + const Scalar _tmp38 = (Scalar(1) / Scalar(2)) * _tmp36 + (Scalar(1) / Scalar(2)) * _tmp37 - + 2 * state(16, 0) * state(3, 0); + const Scalar _tmp39 = + -_tmp23 * _tmp24 - _tmp29 * state(3, 0) + _tmp34 * _tmp35 + _tmp38 * state(0, 0); + const Scalar _tmp40 = (Scalar(1) / Scalar(2)) * _tmp23; + const Scalar _tmp41 = (Scalar(1) / Scalar(2)) * state(0, 0); + const Scalar _tmp42 = + -_tmp24 * _tmp28 + _tmp34 * _tmp41 - _tmp38 * state(1, 0) + _tmp40 * state(3, 0); + const Scalar _tmp43 = (Scalar(1) / Scalar(2)) * state(3, 0); + const Scalar _tmp44 = + -_tmp29 * state(1, 0) - _tmp34 * _tmp43 + _tmp38 * state(2, 0) + _tmp40 * state(0, 0); + const Scalar _tmp45 = _tmp3 * state(16, 0); + const Scalar _tmp46 = _tmp36 - _tmp45; + const Scalar _tmp47 = (Scalar(1) / Scalar(2)) * _tmp46; + const Scalar _tmp48 = _tmp9 * state(16, 0); + const Scalar _tmp49 = (Scalar(1) / Scalar(2)) * _tmp21 + (Scalar(1) / Scalar(2)) * _tmp48; + const Scalar _tmp50 = _tmp5 * state(16, 0); + const Scalar _tmp51 = 4 * state(17, 0); + const Scalar _tmp52 = _tmp33 + _tmp50 - _tmp51 * state(1, 0); + const Scalar _tmp53 = _tmp32 * state(16, 0); + const Scalar _tmp54 = _tmp27 - _tmp51 * state(3, 0) - _tmp53; + const Scalar _tmp55 = + _tmp24 * _tmp54 + _tmp41 * _tmp52 - _tmp47 * state(1, 0) - _tmp49 * state(3, 0); + const Scalar _tmp56 = + -_tmp24 * _tmp52 + _tmp41 * _tmp54 - _tmp47 * state(3, 0) + _tmp49 * state(1, 0); + const Scalar _tmp57 = -_tmp24 * _tmp46 - _tmp35 * _tmp54 + _tmp43 * _tmp52 + _tmp49 * state(0, 0); + const Scalar _tmp58 = -_tmp31 + _tmp50; + const Scalar _tmp59 = (Scalar(1) / Scalar(2)) * _tmp58; + const Scalar _tmp60 = _tmp22 + _tmp48; + const Scalar _tmp61 = (Scalar(1) / Scalar(2)) * _tmp60; + const Scalar _tmp62 = _tmp26 - _tmp30 * state(18, 0) + _tmp53; + const Scalar _tmp63 = -Scalar(1) / Scalar(2) * _tmp37 + (Scalar(1) / Scalar(2)) * _tmp45 - + 2 * state(1, 0) * state(18, 0); + const Scalar _tmp64 = + _tmp35 * _tmp62 - _tmp59 * state(3, 0) + _tmp61 * state(0, 0) - _tmp63 * state(2, 0); + const Scalar _tmp65 = (Scalar(1) / Scalar(2)) * _tmp62; + const Scalar _tmp66 = + _tmp24 * _tmp60 - _tmp59 * state(1, 0) + _tmp63 * state(0, 0) - _tmp65 * state(3, 0); + const Scalar _tmp67 = + -_tmp24 * _tmp58 - _tmp61 * state(1, 0) + _tmp63 * state(3, 0) + _tmp65 * state(0, 0); // Output terms (3) if (innov != nullptr) { matrix::Matrix& _innov = (*innov); - _innov(0, 0) = _tmp14 + _tmp4 * state(16, 0) - meas(0, 0) + state(19, 0); - _innov(1, 0) = _tmp17 * state(17, 0) + _tmp23 - meas(1, 0) + state(20, 0); - _innov(2, 0) = _tmp24 * state(18, 0) + _tmp28 - meas(2, 0) + state(21, 0); + _innov(0, 0) = _tmp11 * state(18, 0) + _tmp2 * state(16, 0) + _tmp7 * state(17, 0) - + meas(0, 0) + state(19, 0); + _innov(1, 0) = _tmp13 * state(17, 0) + _tmp16 * state(18, 0) + _tmp17 * state(16, 0) - + meas(1, 0) + state(20, 0); + _innov(2, 0) = _tmp18 * state(18, 0) + _tmp19 * state(17, 0) + _tmp20 * state(16, 0) - + meas(2, 0) + state(21, 0); } if (innov_var != nullptr) { matrix::Matrix& _innov_var = (*innov_var); - _innov_var(0, 0) = P(1, 18) * _tmp36 + P(15, 18) * _tmp4 + P(16, 18) * _tmp9 + - P(17, 18) * _tmp13 + P(18, 18) + P(2, 18) * _tmp38 + R + - _tmp13 * (P(1, 17) * _tmp36 + P(15, 17) * _tmp4 + P(16, 17) * _tmp9 + - P(17, 17) * _tmp13 + P(18, 17) + P(2, 17) * _tmp38) + - _tmp36 * (P(1, 1) * _tmp36 + P(15, 1) * _tmp4 + P(16, 1) * _tmp9 + - P(17, 1) * _tmp13 + P(18, 1) + P(2, 1) * _tmp38) + - _tmp38 * (P(1, 2) * _tmp36 + P(15, 2) * _tmp4 + P(16, 2) * _tmp9 + - P(17, 2) * _tmp13 + P(18, 2) + P(2, 2) * _tmp38) + - _tmp4 * (P(1, 15) * _tmp36 + P(15, 15) * _tmp4 + P(16, 15) * _tmp9 + - P(17, 15) * _tmp13 + P(18, 15) + P(2, 15) * _tmp38) + - _tmp9 * (P(1, 16) * _tmp36 + P(15, 16) * _tmp4 + P(16, 16) * _tmp9 + - P(17, 16) * _tmp13 + P(18, 16) + P(2, 16) * _tmp38); - _innov_var(1, 0) = P(0, 19) * _tmp44 + P(15, 19) * _tmp22 + P(16, 19) * _tmp17 + - P(17, 19) * _tmp20 + P(19, 19) + P(2, 19) * _tmp41 + R + - _tmp17 * (P(0, 16) * _tmp44 + P(15, 16) * _tmp22 + P(16, 16) * _tmp17 + - P(17, 16) * _tmp20 + P(19, 16) + P(2, 16) * _tmp41) + - _tmp20 * (P(0, 17) * _tmp44 + P(15, 17) * _tmp22 + P(16, 17) * _tmp17 + - P(17, 17) * _tmp20 + P(19, 17) + P(2, 17) * _tmp41) + - _tmp22 * (P(0, 15) * _tmp44 + P(15, 15) * _tmp22 + P(16, 15) * _tmp17 + - P(17, 15) * _tmp20 + P(19, 15) + P(2, 15) * _tmp41) + - _tmp41 * (P(0, 2) * _tmp44 + P(15, 2) * _tmp22 + P(16, 2) * _tmp17 + - P(17, 2) * _tmp20 + P(19, 2) + P(2, 2) * _tmp41) + - _tmp44 * (P(0, 0) * _tmp44 + P(15, 0) * _tmp22 + P(16, 0) * _tmp17 + - P(17, 0) * _tmp20 + P(19, 0) + P(2, 0) * _tmp41); - _innov_var(2, 0) = P(0, 20) * _tmp46 + P(1, 20) * _tmp45 + P(15, 20) * _tmp27 + - P(16, 20) * _tmp26 + P(17, 20) * _tmp24 + P(20, 20) + R + - _tmp24 * (P(0, 17) * _tmp46 + P(1, 17) * _tmp45 + P(15, 17) * _tmp27 + - P(16, 17) * _tmp26 + P(17, 17) * _tmp24 + P(20, 17)) + - _tmp26 * (P(0, 16) * _tmp46 + P(1, 16) * _tmp45 + P(15, 16) * _tmp27 + - P(16, 16) * _tmp26 + P(17, 16) * _tmp24 + P(20, 16)) + - _tmp27 * (P(0, 15) * _tmp46 + P(1, 15) * _tmp45 + P(15, 15) * _tmp27 + - P(16, 15) * _tmp26 + P(17, 15) * _tmp24 + P(20, 15)) + - _tmp45 * (P(0, 1) * _tmp46 + P(1, 1) * _tmp45 + P(15, 1) * _tmp27 + - P(16, 1) * _tmp26 + P(17, 1) * _tmp24 + P(20, 1)) + - _tmp46 * (P(0, 0) * _tmp46 + P(1, 0) * _tmp45 + P(15, 0) * _tmp27 + - P(16, 0) * _tmp26 + P(17, 0) * _tmp24 + P(20, 0)); + _innov_var(0, 0) = + P(0, 18) * _tmp44 + P(1, 18) * _tmp42 + P(15, 18) * _tmp2 + P(16, 18) * _tmp7 + + P(17, 18) * _tmp11 + P(18, 18) + P(2, 18) * _tmp39 + R + + _tmp11 * (P(0, 17) * _tmp44 + P(1, 17) * _tmp42 + P(15, 17) * _tmp2 + P(16, 17) * _tmp7 + + P(17, 17) * _tmp11 + P(18, 17) + P(2, 17) * _tmp39) + + _tmp2 * (P(0, 15) * _tmp44 + P(1, 15) * _tmp42 + P(15, 15) * _tmp2 + P(16, 15) * _tmp7 + + P(17, 15) * _tmp11 + P(18, 15) + P(2, 15) * _tmp39) + + _tmp39 * (P(0, 2) * _tmp44 + P(1, 2) * _tmp42 + P(15, 2) * _tmp2 + P(16, 2) * _tmp7 + + P(17, 2) * _tmp11 + P(18, 2) + P(2, 2) * _tmp39) + + _tmp42 * (P(0, 1) * _tmp44 + P(1, 1) * _tmp42 + P(15, 1) * _tmp2 + P(16, 1) * _tmp7 + + P(17, 1) * _tmp11 + P(18, 1) + P(2, 1) * _tmp39) + + _tmp44 * (P(0, 0) * _tmp44 + P(1, 0) * _tmp42 + P(15, 0) * _tmp2 + P(16, 0) * _tmp7 + + P(17, 0) * _tmp11 + P(18, 0) + P(2, 0) * _tmp39) + + _tmp7 * (P(0, 16) * _tmp44 + P(1, 16) * _tmp42 + P(15, 16) * _tmp2 + P(16, 16) * _tmp7 + + P(17, 16) * _tmp11 + P(18, 16) + P(2, 16) * _tmp39); + _innov_var(1, 0) = + P(0, 19) * _tmp55 + P(1, 19) * _tmp57 + P(15, 19) * _tmp17 + P(16, 19) * _tmp13 + + P(17, 19) * _tmp16 + P(19, 19) + P(2, 19) * _tmp56 + R + + _tmp13 * (P(0, 16) * _tmp55 + P(1, 16) * _tmp57 + P(15, 16) * _tmp17 + P(16, 16) * _tmp13 + + P(17, 16) * _tmp16 + P(19, 16) + P(2, 16) * _tmp56) + + _tmp16 * (P(0, 17) * _tmp55 + P(1, 17) * _tmp57 + P(15, 17) * _tmp17 + P(16, 17) * _tmp13 + + P(17, 17) * _tmp16 + P(19, 17) + P(2, 17) * _tmp56) + + _tmp17 * (P(0, 15) * _tmp55 + P(1, 15) * _tmp57 + P(15, 15) * _tmp17 + P(16, 15) * _tmp13 + + P(17, 15) * _tmp16 + P(19, 15) + P(2, 15) * _tmp56) + + _tmp55 * (P(0, 0) * _tmp55 + P(1, 0) * _tmp57 + P(15, 0) * _tmp17 + P(16, 0) * _tmp13 + + P(17, 0) * _tmp16 + P(19, 0) + P(2, 0) * _tmp56) + + _tmp56 * (P(0, 2) * _tmp55 + P(1, 2) * _tmp57 + P(15, 2) * _tmp17 + P(16, 2) * _tmp13 + + P(17, 2) * _tmp16 + P(19, 2) + P(2, 2) * _tmp56) + + _tmp57 * (P(0, 1) * _tmp55 + P(1, 1) * _tmp57 + P(15, 1) * _tmp17 + P(16, 1) * _tmp13 + + P(17, 1) * _tmp16 + P(19, 1) + P(2, 1) * _tmp56); + _innov_var(2, 0) = + P(0, 20) * _tmp66 + P(1, 20) * _tmp67 + P(15, 20) * _tmp20 + P(16, 20) * _tmp19 + + P(17, 20) * _tmp18 + P(2, 20) * _tmp64 + P(20, 20) + R + + _tmp18 * (P(0, 17) * _tmp66 + P(1, 17) * _tmp67 + P(15, 17) * _tmp20 + P(16, 17) * _tmp19 + + P(17, 17) * _tmp18 + P(2, 17) * _tmp64 + P(20, 17)) + + _tmp19 * (P(0, 16) * _tmp66 + P(1, 16) * _tmp67 + P(15, 16) * _tmp20 + P(16, 16) * _tmp19 + + P(17, 16) * _tmp18 + P(2, 16) * _tmp64 + P(20, 16)) + + _tmp20 * (P(0, 15) * _tmp66 + P(1, 15) * _tmp67 + P(15, 15) * _tmp20 + P(16, 15) * _tmp19 + + P(17, 15) * _tmp18 + P(2, 15) * _tmp64 + P(20, 15)) + + _tmp64 * (P(0, 2) * _tmp66 + P(1, 2) * _tmp67 + P(15, 2) * _tmp20 + P(16, 2) * _tmp19 + + P(17, 2) * _tmp18 + P(2, 2) * _tmp64 + P(20, 2)) + + _tmp66 * (P(0, 0) * _tmp66 + P(1, 0) * _tmp67 + P(15, 0) * _tmp20 + P(16, 0) * _tmp19 + + P(17, 0) * _tmp18 + P(2, 0) * _tmp64 + P(20, 0)) + + _tmp67 * (P(0, 1) * _tmp66 + P(1, 1) * _tmp67 + P(15, 1) * _tmp20 + P(16, 1) * _tmp19 + + P(17, 1) * _tmp18 + P(2, 1) * _tmp64 + P(20, 1)); } if (Hx != nullptr) { @@ -150,11 +189,12 @@ void ComputeMagInnovInnovVarAndHx(const matrix::Matrix& state, _hx.setZero(); - _hx(1, 0) = _tmp36; - _hx(2, 0) = _tmp38; - _hx(15, 0) = _tmp4; - _hx(16, 0) = _tmp9; - _hx(17, 0) = _tmp13; + _hx(0, 0) = _tmp44; + _hx(1, 0) = _tmp42; + _hx(2, 0) = _tmp39; + _hx(15, 0) = _tmp2; + _hx(16, 0) = _tmp7; + _hx(17, 0) = _tmp11; _hx(18, 0) = 1; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h index 9f22c4f1fac7..a490ca61eabc 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h @@ -30,7 +30,7 @@ void ComputeMagYInnovVarAndH(const matrix::Matrix& state, const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, matrix::Matrix* const H = nullptr) { - // Total ops: 110 + // Total ops: 159 // Unused inputs (void)epsilon; @@ -38,43 +38,50 @@ void ComputeMagYInnovVarAndH(const matrix::Matrix& state, // Input arrays // Intermediate terms (18) - const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp2 = -2 * _tmp0 - 2 * _tmp1 + 1; - const Scalar _tmp3 = 2 * state(2, 0); - const Scalar _tmp4 = _tmp3 * state(3, 0); - const Scalar _tmp5 = 2 * state(0, 0); - const Scalar _tmp6 = _tmp5 * state(1, 0); - const Scalar _tmp7 = _tmp4 + _tmp6; - const Scalar _tmp8 = -_tmp5 * state(3, 0); - const Scalar _tmp9 = _tmp3 * state(1, 0); - const Scalar _tmp10 = _tmp8 + _tmp9; - const Scalar _tmp11 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp12 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp13 = _tmp0 - _tmp1; - const Scalar _tmp14 = _tmp3 * state(0, 0); - const Scalar _tmp15 = 2 * state(1, 0) * state(3, 0); - const Scalar _tmp16 = state(16, 0) * (-_tmp11 + _tmp12 + _tmp13) + - state(17, 0) * (_tmp8 - _tmp9) + state(18, 0) * (_tmp14 - _tmp15); - const Scalar _tmp17 = state(16, 0) * (_tmp14 + _tmp15) + state(17, 0) * (_tmp4 - _tmp6) + - state(18, 0) * (_tmp11 - _tmp12 + _tmp13); + const Scalar _tmp0 = 2 * state(2, 0); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = _tmp0 * state(3, 0) + _tmp1 * state(0, 0); + const Scalar _tmp3 = 2 * state(3, 0); + const Scalar _tmp4 = _tmp0 * state(1, 0) - _tmp3 * state(0, 0); + const Scalar _tmp5 = + -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; + const Scalar _tmp6 = _tmp1 * state(18, 0) - _tmp3 * state(16, 0); + const Scalar _tmp7 = (Scalar(1) / Scalar(2)) * _tmp6; + const Scalar _tmp8 = (Scalar(1) / Scalar(2)) * _tmp1 * state(16, 0) + + (Scalar(1) / Scalar(2)) * _tmp3 * state(18, 0); + const Scalar _tmp9 = 4 * state(17, 0); + const Scalar _tmp10 = 2 * state(0, 0); + const Scalar _tmp11 = _tmp0 * state(16, 0) + _tmp10 * state(18, 0) - _tmp9 * state(1, 0); + const Scalar _tmp12 = (Scalar(1) / Scalar(2)) * _tmp11; + const Scalar _tmp13 = (Scalar(1) / Scalar(2)) * _tmp0 * state(18, 0) - + Scalar(1) / Scalar(2) * _tmp10 * state(16, 0) - + Scalar(1) / Scalar(2) * _tmp9 * state(3, 0); + const Scalar _tmp14 = + _tmp12 * state(0, 0) + _tmp13 * state(2, 0) - _tmp7 * state(1, 0) - _tmp8 * state(3, 0); + const Scalar _tmp15 = (Scalar(1) / Scalar(2)) * state(2, 0); + const Scalar _tmp16 = + -_tmp11 * _tmp15 + _tmp13 * state(0, 0) - _tmp7 * state(3, 0) + _tmp8 * state(1, 0); + const Scalar _tmp17 = + _tmp12 * state(3, 0) - _tmp13 * state(1, 0) - _tmp15 * _tmp6 + _tmp8 * state(0, 0); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = P(0, 19) * _tmp17 + P(15, 19) * _tmp10 + P(16, 19) * _tmp2 + P(17, 19) * _tmp7 + - P(19, 19) + P(2, 19) * _tmp16 + R + - _tmp10 * (P(0, 15) * _tmp17 + P(15, 15) * _tmp10 + P(16, 15) * _tmp2 + - P(17, 15) * _tmp7 + P(19, 15) + P(2, 15) * _tmp16) + - _tmp16 * (P(0, 2) * _tmp17 + P(15, 2) * _tmp10 + P(16, 2) * _tmp2 + - P(17, 2) * _tmp7 + P(19, 2) + P(2, 2) * _tmp16) + - _tmp17 * (P(0, 0) * _tmp17 + P(15, 0) * _tmp10 + P(16, 0) * _tmp2 + - P(17, 0) * _tmp7 + P(19, 0) + P(2, 0) * _tmp16) + - _tmp2 * (P(0, 16) * _tmp17 + P(15, 16) * _tmp10 + P(16, 16) * _tmp2 + - P(17, 16) * _tmp7 + P(19, 16) + P(2, 16) * _tmp16) + - _tmp7 * (P(0, 17) * _tmp17 + P(15, 17) * _tmp10 + P(16, 17) * _tmp2 + - P(17, 17) * _tmp7 + P(19, 17) + P(2, 17) * _tmp16); + _innov_var = P(0, 19) * _tmp14 + P(1, 19) * _tmp17 + P(15, 19) * _tmp4 + P(16, 19) * _tmp5 + + P(17, 19) * _tmp2 + P(19, 19) + P(2, 19) * _tmp16 + R + + _tmp14 * (P(0, 0) * _tmp14 + P(1, 0) * _tmp17 + P(15, 0) * _tmp4 + + P(16, 0) * _tmp5 + P(17, 0) * _tmp2 + P(19, 0) + P(2, 0) * _tmp16) + + _tmp16 * (P(0, 2) * _tmp14 + P(1, 2) * _tmp17 + P(15, 2) * _tmp4 + + P(16, 2) * _tmp5 + P(17, 2) * _tmp2 + P(19, 2) + P(2, 2) * _tmp16) + + _tmp17 * (P(0, 1) * _tmp14 + P(1, 1) * _tmp17 + P(15, 1) * _tmp4 + + P(16, 1) * _tmp5 + P(17, 1) * _tmp2 + P(19, 1) + P(2, 1) * _tmp16) + + _tmp2 * (P(0, 17) * _tmp14 + P(1, 17) * _tmp17 + P(15, 17) * _tmp4 + + P(16, 17) * _tmp5 + P(17, 17) * _tmp2 + P(19, 17) + P(2, 17) * _tmp16) + + _tmp4 * (P(0, 15) * _tmp14 + P(1, 15) * _tmp17 + P(15, 15) * _tmp4 + + P(16, 15) * _tmp5 + P(17, 15) * _tmp2 + P(19, 15) + P(2, 15) * _tmp16) + + _tmp5 * (P(0, 16) * _tmp14 + P(1, 16) * _tmp17 + P(15, 16) * _tmp4 + + P(16, 16) * _tmp5 + P(17, 16) * _tmp2 + P(19, 16) + P(2, 16) * _tmp16); } if (H != nullptr) { @@ -82,11 +89,12 @@ void ComputeMagYInnovVarAndH(const matrix::Matrix& state, _h.setZero(); - _h(0, 0) = _tmp17; + _h(0, 0) = _tmp14; + _h(1, 0) = _tmp17; _h(2, 0) = _tmp16; - _h(15, 0) = _tmp10; - _h(16, 0) = _tmp2; - _h(17, 0) = _tmp7; + _h(15, 0) = _tmp4; + _h(16, 0) = _tmp5; + _h(17, 0) = _tmp2; _h(19, 0) = 1; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h index 0563f1df9e22..0abdc1d9ca7f 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h @@ -30,51 +30,58 @@ void ComputeMagZInnovVarAndH(const matrix::Matrix& state, const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, matrix::Matrix* const H = nullptr) { - // Total ops: 110 + // Total ops: 161 // Unused inputs (void)epsilon; // Input arrays - // Intermediate terms (18) - const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp2 = -2 * _tmp0 - 2 * _tmp1 + 1; - const Scalar _tmp3 = 2 * state(2, 0); - const Scalar _tmp4 = _tmp3 * state(3, 0); - const Scalar _tmp5 = 2 * state(0, 0); - const Scalar _tmp6 = -_tmp5 * state(1, 0); - const Scalar _tmp7 = _tmp4 + _tmp6; - const Scalar _tmp8 = _tmp3 * state(0, 0); - const Scalar _tmp9 = 2 * state(1, 0) * state(3, 0); - const Scalar _tmp10 = _tmp8 + _tmp9; - const Scalar _tmp11 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp12 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp13 = -_tmp0 + _tmp1; - const Scalar _tmp14 = _tmp5 * state(3, 0); - const Scalar _tmp15 = _tmp3 * state(1, 0); - const Scalar _tmp16 = state(16, 0) * (-_tmp11 + _tmp12 + _tmp13) + - state(17, 0) * (_tmp14 + _tmp15) + state(18, 0) * (-_tmp8 + _tmp9); - const Scalar _tmp17 = state(16, 0) * (_tmp14 - _tmp15) + - state(17, 0) * (_tmp11 - _tmp12 + _tmp13) + state(18, 0) * (-_tmp4 + _tmp6); + // Intermediate terms (15) + const Scalar _tmp0 = 2 * state(16, 0); + const Scalar _tmp1 = 2 * state(17, 0); + const Scalar _tmp2 = + (Scalar(1) / Scalar(2)) * _tmp0 * state(2, 0) - Scalar(1) / Scalar(2) * _tmp1 * state(1, 0); + const Scalar _tmp3 = 2 * state(1, 0); + const Scalar _tmp4 = (Scalar(1) / Scalar(2)) * _tmp1 * state(2, 0) + + (Scalar(1) / Scalar(2)) * _tmp3 * state(16, 0); + const Scalar _tmp5 = 4 * state(18, 0); + const Scalar _tmp6 = (Scalar(1) / Scalar(2)) * _tmp0 * state(0, 0) + + (Scalar(1) / Scalar(2)) * _tmp1 * state(3, 0) - + Scalar(1) / Scalar(2) * _tmp5 * state(2, 0); + const Scalar _tmp7 = (Scalar(1) / Scalar(2)) * _tmp0 * state(3, 0) - + Scalar(1) / Scalar(2) * _tmp1 * state(0, 0) - + Scalar(1) / Scalar(2) * _tmp5 * state(1, 0); + const Scalar _tmp8 = + -_tmp2 * state(3, 0) + _tmp4 * state(0, 0) + _tmp6 * state(1, 0) - _tmp7 * state(2, 0); + const Scalar _tmp9 = + -_tmp2 * state(1, 0) + _tmp4 * state(2, 0) - _tmp6 * state(3, 0) + _tmp7 * state(0, 0); + const Scalar _tmp10 = + -_tmp2 * state(2, 0) - _tmp4 * state(1, 0) + _tmp6 * state(0, 0) + _tmp7 * state(3, 0); + const Scalar _tmp11 = + -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(2, 0), Scalar(2)) + 1; + const Scalar _tmp12 = 2 * state(2, 0); + const Scalar _tmp13 = _tmp12 * state(3, 0) - _tmp3 * state(0, 0); + const Scalar _tmp14 = _tmp12 * state(0, 0) + _tmp3 * state(3, 0); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = P(0, 20) * _tmp17 + P(1, 20) * _tmp16 + P(15, 20) * _tmp10 + P(16, 20) * _tmp7 + - P(17, 20) * _tmp2 + P(20, 20) + R + - _tmp10 * (P(0, 15) * _tmp17 + P(1, 15) * _tmp16 + P(15, 15) * _tmp10 + - P(16, 15) * _tmp7 + P(17, 15) * _tmp2 + P(20, 15)) + - _tmp16 * (P(0, 1) * _tmp17 + P(1, 1) * _tmp16 + P(15, 1) * _tmp10 + - P(16, 1) * _tmp7 + P(17, 1) * _tmp2 + P(20, 1)) + - _tmp17 * (P(0, 0) * _tmp17 + P(1, 0) * _tmp16 + P(15, 0) * _tmp10 + - P(16, 0) * _tmp7 + P(17, 0) * _tmp2 + P(20, 0)) + - _tmp2 * (P(0, 17) * _tmp17 + P(1, 17) * _tmp16 + P(15, 17) * _tmp10 + - P(16, 17) * _tmp7 + P(17, 17) * _tmp2 + P(20, 17)) + - _tmp7 * (P(0, 16) * _tmp17 + P(1, 16) * _tmp16 + P(15, 16) * _tmp10 + - P(16, 16) * _tmp7 + P(17, 16) * _tmp2 + P(20, 16)); + _innov_var = P(0, 20) * _tmp9 + P(1, 20) * _tmp10 + P(15, 20) * _tmp14 + P(16, 20) * _tmp13 + + P(17, 20) * _tmp11 + P(2, 20) * _tmp8 + P(20, 20) + R + + _tmp10 * (P(0, 1) * _tmp9 + P(1, 1) * _tmp10 + P(15, 1) * _tmp14 + + P(16, 1) * _tmp13 + P(17, 1) * _tmp11 + P(2, 1) * _tmp8 + P(20, 1)) + + _tmp11 * (P(0, 17) * _tmp9 + P(1, 17) * _tmp10 + P(15, 17) * _tmp14 + + P(16, 17) * _tmp13 + P(17, 17) * _tmp11 + P(2, 17) * _tmp8 + P(20, 17)) + + _tmp13 * (P(0, 16) * _tmp9 + P(1, 16) * _tmp10 + P(15, 16) * _tmp14 + + P(16, 16) * _tmp13 + P(17, 16) * _tmp11 + P(2, 16) * _tmp8 + P(20, 16)) + + _tmp14 * (P(0, 15) * _tmp9 + P(1, 15) * _tmp10 + P(15, 15) * _tmp14 + + P(16, 15) * _tmp13 + P(17, 15) * _tmp11 + P(2, 15) * _tmp8 + P(20, 15)) + + _tmp8 * (P(0, 2) * _tmp9 + P(1, 2) * _tmp10 + P(15, 2) * _tmp14 + + P(16, 2) * _tmp13 + P(17, 2) * _tmp11 + P(2, 2) * _tmp8 + P(20, 2)) + + _tmp9 * (P(0, 0) * _tmp9 + P(1, 0) * _tmp10 + P(15, 0) * _tmp14 + + P(16, 0) * _tmp13 + P(17, 0) * _tmp11 + P(2, 0) * _tmp8 + P(20, 0)); } if (H != nullptr) { @@ -82,11 +89,12 @@ void ComputeMagZInnovVarAndH(const matrix::Matrix& state, _h.setZero(); - _h(0, 0) = _tmp17; - _h(1, 0) = _tmp16; - _h(15, 0) = _tmp10; - _h(16, 0) = _tmp7; - _h(17, 0) = _tmp2; + _h(0, 0) = _tmp9; + _h(1, 0) = _tmp10; + _h(2, 0) = _tmp8; + _h(15, 0) = _tmp14; + _h(16, 0) = _tmp13; + _h(17, 0) = _tmp11; _h(20, 0) = 1; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h index 30acca8d22cc..1cd242c727e5 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h @@ -30,63 +30,66 @@ void ComputeSideslipHAndK(const matrix::Matrix& state, const matrix::Matrix& P, const Scalar innov_var, const Scalar epsilon, matrix::Matrix* const H = nullptr, matrix::Matrix* const K = nullptr) { - // Total ops: 469 + // Total ops: 497 // Input arrays - // Intermediate terms (46) - const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp2 = 1 - 2 * _tmp1; - const Scalar _tmp3 = -2 * _tmp0 + _tmp2; - const Scalar _tmp4 = -state(22, 0) + state(4, 0); - const Scalar _tmp5 = 2 * state(0, 0); - const Scalar _tmp6 = _tmp5 * state(3, 0); - const Scalar _tmp7 = 2 * state(2, 0); - const Scalar _tmp8 = _tmp7 * state(1, 0); - const Scalar _tmp9 = _tmp6 + _tmp8; - const Scalar _tmp10 = -state(23, 0) + state(5, 0); - const Scalar _tmp11 = _tmp7 * state(0, 0); - const Scalar _tmp12 = -_tmp11; - const Scalar _tmp13 = 2 * state(1, 0) * state(3, 0); - const Scalar _tmp14 = _tmp12 + _tmp13; - const Scalar _tmp15 = _tmp10 * _tmp9 + _tmp14 * state(6, 0) + _tmp3 * _tmp4; - const Scalar _tmp16 = - _tmp15 + epsilon * (2 * math::min(0, (((_tmp15) > 0) - ((_tmp15) < 0))) + 1); - const Scalar _tmp17 = Scalar(1.0) / (_tmp16); - const Scalar _tmp18 = _tmp7 * state(3, 0); - const Scalar _tmp19 = _tmp5 * state(1, 0); - const Scalar _tmp20 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp21 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp22 = -_tmp21; - const Scalar _tmp23 = _tmp20 + _tmp22; - const Scalar _tmp24 = _tmp17 * (_tmp10 * (_tmp18 - _tmp19) + _tmp4 * (_tmp11 + _tmp13) + - state(6, 0) * (-_tmp0 + _tmp1 + _tmp23)); - const Scalar _tmp25 = -_tmp13; - const Scalar _tmp26 = -_tmp20; - const Scalar _tmp27 = _tmp0 - _tmp1; - const Scalar _tmp28 = _tmp2 - 2 * _tmp21; - const Scalar _tmp29 = -_tmp6; - const Scalar _tmp30 = _tmp29 + _tmp8; - const Scalar _tmp31 = _tmp18 + _tmp19; - const Scalar _tmp32 = _tmp30 * _tmp4 + _tmp31 * state(6, 0); - const Scalar _tmp33 = (_tmp10 * _tmp28 + _tmp32) / std::pow(_tmp16, Scalar(2)); - const Scalar _tmp34 = _tmp33 * (_tmp10 * (-_tmp18 + _tmp19) + _tmp4 * (_tmp12 + _tmp25) + - state(6, 0) * (_tmp21 + _tmp26 + _tmp27)); - const Scalar _tmp35 = - _tmp17 * (_tmp10 * (_tmp29 - _tmp8) + _tmp4 * (_tmp0 + _tmp1 + _tmp22 + _tmp26) + - state(6, 0) * (_tmp11 + _tmp25)) - - _tmp33 * (_tmp10 * (_tmp23 + _tmp27) + _tmp32); - const Scalar _tmp36 = _tmp3 * _tmp33; - const Scalar _tmp37 = _tmp17 * _tmp30; - const Scalar _tmp38 = -_tmp36 + _tmp37; - const Scalar _tmp39 = _tmp33 * _tmp9; - const Scalar _tmp40 = _tmp17 * _tmp28; - const Scalar _tmp41 = -_tmp39 + _tmp40; - const Scalar _tmp42 = -_tmp14 * _tmp33 + _tmp17 * _tmp31; - const Scalar _tmp43 = _tmp36 - _tmp37; - const Scalar _tmp44 = _tmp39 - _tmp40; - const Scalar _tmp45 = Scalar(1.0) / (math::max(epsilon, innov_var)); + // Intermediate terms (45) + const Scalar _tmp0 = -state(23, 0) + state(5, 0); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = -state(22, 0) + state(4, 0); + const Scalar _tmp3 = 2 * state(6, 0); + const Scalar _tmp4 = _tmp3 * state(0, 0); + const Scalar _tmp5 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp6 = _tmp5 - 2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp7 = 2 * state(0, 0); + const Scalar _tmp8 = _tmp7 * state(3, 0); + const Scalar _tmp9 = 2 * state(2, 0); + const Scalar _tmp10 = _tmp9 * state(1, 0); + const Scalar _tmp11 = _tmp10 + _tmp8; + const Scalar _tmp12 = _tmp1 * state(3, 0) - _tmp9 * state(0, 0); + const Scalar _tmp13 = _tmp0 * _tmp11 + _tmp12 * state(6, 0) + _tmp2 * _tmp6; + const Scalar _tmp14 = + _tmp13 + epsilon * (2 * math::min(0, (((_tmp13) > 0) - ((_tmp13) < 0))) + 1); + const Scalar _tmp15 = _tmp5 - 2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp16 = _tmp10 - _tmp8; + const Scalar _tmp17 = _tmp7 * state(1, 0) + _tmp9 * state(3, 0); + const Scalar _tmp18 = + (_tmp0 * _tmp15 + _tmp16 * _tmp2 + _tmp17 * state(6, 0)) / std::pow(_tmp14, Scalar(2)); + const Scalar _tmp19 = _tmp3 * state(3, 0); + const Scalar _tmp20 = Scalar(1.0) / (_tmp14); + const Scalar _tmp21 = -_tmp18 * (_tmp0 * _tmp1 - 4 * _tmp2 * state(2, 0) - _tmp4) + + _tmp20 * (_tmp1 * _tmp2 + _tmp19); + const Scalar _tmp22 = (Scalar(1) / Scalar(2)) * state(3, 0); + const Scalar _tmp23 = + -Scalar(1) / Scalar(2) * _tmp18 * (_tmp0 * _tmp9 + _tmp19) + + (Scalar(1) / Scalar(2)) * _tmp20 * (-4 * _tmp0 * state(1, 0) + _tmp2 * _tmp9 + _tmp4); + const Scalar _tmp24 = 2 * state(3, 0); + const Scalar _tmp25 = _tmp3 * state(2, 0); + const Scalar _tmp26 = _tmp3 * state(1, 0); + const Scalar _tmp27 = -_tmp18 * (_tmp0 * _tmp24 - _tmp25) + _tmp20 * (-_tmp2 * _tmp24 + _tmp26); + const Scalar _tmp28 = (Scalar(1) / Scalar(2)) * _tmp27; + const Scalar _tmp29 = 4 * state(3, 0); + const Scalar _tmp30 = + -Scalar(1) / Scalar(2) * _tmp18 * (_tmp0 * _tmp7 - _tmp2 * _tmp29 + _tmp26) + + (Scalar(1) / Scalar(2)) * _tmp20 * (-_tmp0 * _tmp29 - _tmp2 * _tmp7 + _tmp25); + const Scalar _tmp31 = + -_tmp21 * _tmp22 + _tmp23 * state(0, 0) - _tmp28 * state(1, 0) + _tmp30 * state(2, 0); + const Scalar _tmp32 = (Scalar(1) / Scalar(2)) * _tmp21; + const Scalar _tmp33 = + _tmp23 * state(3, 0) - _tmp28 * state(2, 0) - _tmp30 * state(1, 0) + _tmp32 * state(0, 0); + const Scalar _tmp34 = + -_tmp22 * _tmp27 - _tmp23 * state(2, 0) + _tmp30 * state(0, 0) + _tmp32 * state(1, 0); + const Scalar _tmp35 = _tmp18 * _tmp6; + const Scalar _tmp36 = _tmp16 * _tmp20; + const Scalar _tmp37 = -_tmp35 + _tmp36; + const Scalar _tmp38 = _tmp11 * _tmp18; + const Scalar _tmp39 = _tmp15 * _tmp20; + const Scalar _tmp40 = -_tmp38 + _tmp39; + const Scalar _tmp41 = -_tmp12 * _tmp18 + _tmp17 * _tmp20; + const Scalar _tmp42 = _tmp35 - _tmp36; + const Scalar _tmp43 = _tmp38 - _tmp39; + const Scalar _tmp44 = Scalar(1.0) / (math::max(epsilon, innov_var)); // Output terms (2) if (H != nullptr) { @@ -94,88 +97,88 @@ void ComputeSideslipHAndK(const matrix::Matrix& state, _h.setZero(); - _h(0, 0) = _tmp24; - _h(1, 0) = -_tmp34; - _h(2, 0) = _tmp35; - _h(3, 0) = _tmp38; - _h(4, 0) = _tmp41; - _h(5, 0) = _tmp42; - _h(21, 0) = _tmp43; - _h(22, 0) = _tmp44; + _h(0, 0) = _tmp31; + _h(1, 0) = _tmp33; + _h(2, 0) = _tmp34; + _h(3, 0) = _tmp37; + _h(4, 0) = _tmp40; + _h(5, 0) = _tmp41; + _h(21, 0) = _tmp42; + _h(22, 0) = _tmp43; } if (K != nullptr) { matrix::Matrix& _k = (*K); _k(0, 0) = - _tmp45 * (P(0, 0) * _tmp24 - P(0, 1) * _tmp34 + P(0, 2) * _tmp35 + P(0, 21) * _tmp43 + - P(0, 22) * _tmp44 + P(0, 3) * _tmp38 + P(0, 4) * _tmp41 + P(0, 5) * _tmp42); + _tmp44 * (P(0, 0) * _tmp31 + P(0, 1) * _tmp33 + P(0, 2) * _tmp34 + P(0, 21) * _tmp42 + + P(0, 22) * _tmp43 + P(0, 3) * _tmp37 + P(0, 4) * _tmp40 + P(0, 5) * _tmp41); _k(1, 0) = - _tmp45 * (P(1, 0) * _tmp24 - P(1, 1) * _tmp34 + P(1, 2) * _tmp35 + P(1, 21) * _tmp43 + - P(1, 22) * _tmp44 + P(1, 3) * _tmp38 + P(1, 4) * _tmp41 + P(1, 5) * _tmp42); + _tmp44 * (P(1, 0) * _tmp31 + P(1, 1) * _tmp33 + P(1, 2) * _tmp34 + P(1, 21) * _tmp42 + + P(1, 22) * _tmp43 + P(1, 3) * _tmp37 + P(1, 4) * _tmp40 + P(1, 5) * _tmp41); _k(2, 0) = - _tmp45 * (P(2, 0) * _tmp24 - P(2, 1) * _tmp34 + P(2, 2) * _tmp35 + P(2, 21) * _tmp43 + - P(2, 22) * _tmp44 + P(2, 3) * _tmp38 + P(2, 4) * _tmp41 + P(2, 5) * _tmp42); + _tmp44 * (P(2, 0) * _tmp31 + P(2, 1) * _tmp33 + P(2, 2) * _tmp34 + P(2, 21) * _tmp42 + + P(2, 22) * _tmp43 + P(2, 3) * _tmp37 + P(2, 4) * _tmp40 + P(2, 5) * _tmp41); _k(3, 0) = - _tmp45 * (P(3, 0) * _tmp24 - P(3, 1) * _tmp34 + P(3, 2) * _tmp35 + P(3, 21) * _tmp43 + - P(3, 22) * _tmp44 + P(3, 3) * _tmp38 + P(3, 4) * _tmp41 + P(3, 5) * _tmp42); + _tmp44 * (P(3, 0) * _tmp31 + P(3, 1) * _tmp33 + P(3, 2) * _tmp34 + P(3, 21) * _tmp42 + + P(3, 22) * _tmp43 + P(3, 3) * _tmp37 + P(3, 4) * _tmp40 + P(3, 5) * _tmp41); _k(4, 0) = - _tmp45 * (P(4, 0) * _tmp24 - P(4, 1) * _tmp34 + P(4, 2) * _tmp35 + P(4, 21) * _tmp43 + - P(4, 22) * _tmp44 + P(4, 3) * _tmp38 + P(4, 4) * _tmp41 + P(4, 5) * _tmp42); + _tmp44 * (P(4, 0) * _tmp31 + P(4, 1) * _tmp33 + P(4, 2) * _tmp34 + P(4, 21) * _tmp42 + + P(4, 22) * _tmp43 + P(4, 3) * _tmp37 + P(4, 4) * _tmp40 + P(4, 5) * _tmp41); _k(5, 0) = - _tmp45 * (P(5, 0) * _tmp24 - P(5, 1) * _tmp34 + P(5, 2) * _tmp35 + P(5, 21) * _tmp43 + - P(5, 22) * _tmp44 + P(5, 3) * _tmp38 + P(5, 4) * _tmp41 + P(5, 5) * _tmp42); + _tmp44 * (P(5, 0) * _tmp31 + P(5, 1) * _tmp33 + P(5, 2) * _tmp34 + P(5, 21) * _tmp42 + + P(5, 22) * _tmp43 + P(5, 3) * _tmp37 + P(5, 4) * _tmp40 + P(5, 5) * _tmp41); _k(6, 0) = - _tmp45 * (P(6, 0) * _tmp24 - P(6, 1) * _tmp34 + P(6, 2) * _tmp35 + P(6, 21) * _tmp43 + - P(6, 22) * _tmp44 + P(6, 3) * _tmp38 + P(6, 4) * _tmp41 + P(6, 5) * _tmp42); + _tmp44 * (P(6, 0) * _tmp31 + P(6, 1) * _tmp33 + P(6, 2) * _tmp34 + P(6, 21) * _tmp42 + + P(6, 22) * _tmp43 + P(6, 3) * _tmp37 + P(6, 4) * _tmp40 + P(6, 5) * _tmp41); _k(7, 0) = - _tmp45 * (P(7, 0) * _tmp24 - P(7, 1) * _tmp34 + P(7, 2) * _tmp35 + P(7, 21) * _tmp43 + - P(7, 22) * _tmp44 + P(7, 3) * _tmp38 + P(7, 4) * _tmp41 + P(7, 5) * _tmp42); + _tmp44 * (P(7, 0) * _tmp31 + P(7, 1) * _tmp33 + P(7, 2) * _tmp34 + P(7, 21) * _tmp42 + + P(7, 22) * _tmp43 + P(7, 3) * _tmp37 + P(7, 4) * _tmp40 + P(7, 5) * _tmp41); _k(8, 0) = - _tmp45 * (P(8, 0) * _tmp24 - P(8, 1) * _tmp34 + P(8, 2) * _tmp35 + P(8, 21) * _tmp43 + - P(8, 22) * _tmp44 + P(8, 3) * _tmp38 + P(8, 4) * _tmp41 + P(8, 5) * _tmp42); + _tmp44 * (P(8, 0) * _tmp31 + P(8, 1) * _tmp33 + P(8, 2) * _tmp34 + P(8, 21) * _tmp42 + + P(8, 22) * _tmp43 + P(8, 3) * _tmp37 + P(8, 4) * _tmp40 + P(8, 5) * _tmp41); _k(9, 0) = - _tmp45 * (P(9, 0) * _tmp24 - P(9, 1) * _tmp34 + P(9, 2) * _tmp35 + P(9, 21) * _tmp43 + - P(9, 22) * _tmp44 + P(9, 3) * _tmp38 + P(9, 4) * _tmp41 + P(9, 5) * _tmp42); + _tmp44 * (P(9, 0) * _tmp31 + P(9, 1) * _tmp33 + P(9, 2) * _tmp34 + P(9, 21) * _tmp42 + + P(9, 22) * _tmp43 + P(9, 3) * _tmp37 + P(9, 4) * _tmp40 + P(9, 5) * _tmp41); _k(10, 0) = - _tmp45 * (P(10, 0) * _tmp24 - P(10, 1) * _tmp34 + P(10, 2) * _tmp35 + P(10, 21) * _tmp43 + - P(10, 22) * _tmp44 + P(10, 3) * _tmp38 + P(10, 4) * _tmp41 + P(10, 5) * _tmp42); + _tmp44 * (P(10, 0) * _tmp31 + P(10, 1) * _tmp33 + P(10, 2) * _tmp34 + P(10, 21) * _tmp42 + + P(10, 22) * _tmp43 + P(10, 3) * _tmp37 + P(10, 4) * _tmp40 + P(10, 5) * _tmp41); _k(11, 0) = - _tmp45 * (P(11, 0) * _tmp24 - P(11, 1) * _tmp34 + P(11, 2) * _tmp35 + P(11, 21) * _tmp43 + - P(11, 22) * _tmp44 + P(11, 3) * _tmp38 + P(11, 4) * _tmp41 + P(11, 5) * _tmp42); + _tmp44 * (P(11, 0) * _tmp31 + P(11, 1) * _tmp33 + P(11, 2) * _tmp34 + P(11, 21) * _tmp42 + + P(11, 22) * _tmp43 + P(11, 3) * _tmp37 + P(11, 4) * _tmp40 + P(11, 5) * _tmp41); _k(12, 0) = - _tmp45 * (P(12, 0) * _tmp24 - P(12, 1) * _tmp34 + P(12, 2) * _tmp35 + P(12, 21) * _tmp43 + - P(12, 22) * _tmp44 + P(12, 3) * _tmp38 + P(12, 4) * _tmp41 + P(12, 5) * _tmp42); + _tmp44 * (P(12, 0) * _tmp31 + P(12, 1) * _tmp33 + P(12, 2) * _tmp34 + P(12, 21) * _tmp42 + + P(12, 22) * _tmp43 + P(12, 3) * _tmp37 + P(12, 4) * _tmp40 + P(12, 5) * _tmp41); _k(13, 0) = - _tmp45 * (P(13, 0) * _tmp24 - P(13, 1) * _tmp34 + P(13, 2) * _tmp35 + P(13, 21) * _tmp43 + - P(13, 22) * _tmp44 + P(13, 3) * _tmp38 + P(13, 4) * _tmp41 + P(13, 5) * _tmp42); + _tmp44 * (P(13, 0) * _tmp31 + P(13, 1) * _tmp33 + P(13, 2) * _tmp34 + P(13, 21) * _tmp42 + + P(13, 22) * _tmp43 + P(13, 3) * _tmp37 + P(13, 4) * _tmp40 + P(13, 5) * _tmp41); _k(14, 0) = - _tmp45 * (P(14, 0) * _tmp24 - P(14, 1) * _tmp34 + P(14, 2) * _tmp35 + P(14, 21) * _tmp43 + - P(14, 22) * _tmp44 + P(14, 3) * _tmp38 + P(14, 4) * _tmp41 + P(14, 5) * _tmp42); + _tmp44 * (P(14, 0) * _tmp31 + P(14, 1) * _tmp33 + P(14, 2) * _tmp34 + P(14, 21) * _tmp42 + + P(14, 22) * _tmp43 + P(14, 3) * _tmp37 + P(14, 4) * _tmp40 + P(14, 5) * _tmp41); _k(15, 0) = - _tmp45 * (P(15, 0) * _tmp24 - P(15, 1) * _tmp34 + P(15, 2) * _tmp35 + P(15, 21) * _tmp43 + - P(15, 22) * _tmp44 + P(15, 3) * _tmp38 + P(15, 4) * _tmp41 + P(15, 5) * _tmp42); + _tmp44 * (P(15, 0) * _tmp31 + P(15, 1) * _tmp33 + P(15, 2) * _tmp34 + P(15, 21) * _tmp42 + + P(15, 22) * _tmp43 + P(15, 3) * _tmp37 + P(15, 4) * _tmp40 + P(15, 5) * _tmp41); _k(16, 0) = - _tmp45 * (P(16, 0) * _tmp24 - P(16, 1) * _tmp34 + P(16, 2) * _tmp35 + P(16, 21) * _tmp43 + - P(16, 22) * _tmp44 + P(16, 3) * _tmp38 + P(16, 4) * _tmp41 + P(16, 5) * _tmp42); + _tmp44 * (P(16, 0) * _tmp31 + P(16, 1) * _tmp33 + P(16, 2) * _tmp34 + P(16, 21) * _tmp42 + + P(16, 22) * _tmp43 + P(16, 3) * _tmp37 + P(16, 4) * _tmp40 + P(16, 5) * _tmp41); _k(17, 0) = - _tmp45 * (P(17, 0) * _tmp24 - P(17, 1) * _tmp34 + P(17, 2) * _tmp35 + P(17, 21) * _tmp43 + - P(17, 22) * _tmp44 + P(17, 3) * _tmp38 + P(17, 4) * _tmp41 + P(17, 5) * _tmp42); + _tmp44 * (P(17, 0) * _tmp31 + P(17, 1) * _tmp33 + P(17, 2) * _tmp34 + P(17, 21) * _tmp42 + + P(17, 22) * _tmp43 + P(17, 3) * _tmp37 + P(17, 4) * _tmp40 + P(17, 5) * _tmp41); _k(18, 0) = - _tmp45 * (P(18, 0) * _tmp24 - P(18, 1) * _tmp34 + P(18, 2) * _tmp35 + P(18, 21) * _tmp43 + - P(18, 22) * _tmp44 + P(18, 3) * _tmp38 + P(18, 4) * _tmp41 + P(18, 5) * _tmp42); + _tmp44 * (P(18, 0) * _tmp31 + P(18, 1) * _tmp33 + P(18, 2) * _tmp34 + P(18, 21) * _tmp42 + + P(18, 22) * _tmp43 + P(18, 3) * _tmp37 + P(18, 4) * _tmp40 + P(18, 5) * _tmp41); _k(19, 0) = - _tmp45 * (P(19, 0) * _tmp24 - P(19, 1) * _tmp34 + P(19, 2) * _tmp35 + P(19, 21) * _tmp43 + - P(19, 22) * _tmp44 + P(19, 3) * _tmp38 + P(19, 4) * _tmp41 + P(19, 5) * _tmp42); + _tmp44 * (P(19, 0) * _tmp31 + P(19, 1) * _tmp33 + P(19, 2) * _tmp34 + P(19, 21) * _tmp42 + + P(19, 22) * _tmp43 + P(19, 3) * _tmp37 + P(19, 4) * _tmp40 + P(19, 5) * _tmp41); _k(20, 0) = - _tmp45 * (P(20, 0) * _tmp24 - P(20, 1) * _tmp34 + P(20, 2) * _tmp35 + P(20, 21) * _tmp43 + - P(20, 22) * _tmp44 + P(20, 3) * _tmp38 + P(20, 4) * _tmp41 + P(20, 5) * _tmp42); + _tmp44 * (P(20, 0) * _tmp31 + P(20, 1) * _tmp33 + P(20, 2) * _tmp34 + P(20, 21) * _tmp42 + + P(20, 22) * _tmp43 + P(20, 3) * _tmp37 + P(20, 4) * _tmp40 + P(20, 5) * _tmp41); _k(21, 0) = - _tmp45 * (P(21, 0) * _tmp24 - P(21, 1) * _tmp34 + P(21, 2) * _tmp35 + P(21, 21) * _tmp43 + - P(21, 22) * _tmp44 + P(21, 3) * _tmp38 + P(21, 4) * _tmp41 + P(21, 5) * _tmp42); + _tmp44 * (P(21, 0) * _tmp31 + P(21, 1) * _tmp33 + P(21, 2) * _tmp34 + P(21, 21) * _tmp42 + + P(21, 22) * _tmp43 + P(21, 3) * _tmp37 + P(21, 4) * _tmp40 + P(21, 5) * _tmp41); _k(22, 0) = - _tmp45 * (P(22, 0) * _tmp24 - P(22, 1) * _tmp34 + P(22, 2) * _tmp35 + P(22, 21) * _tmp43 + - P(22, 22) * _tmp44 + P(22, 3) * _tmp38 + P(22, 4) * _tmp41 + P(22, 5) * _tmp42); + _tmp44 * (P(22, 0) * _tmp31 + P(22, 1) * _tmp33 + P(22, 2) * _tmp34 + P(22, 21) * _tmp42 + + P(22, 22) * _tmp43 + P(22, 3) * _tmp37 + P(22, 4) * _tmp40 + P(22, 5) * _tmp41); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h index 48dd3e284f34..b93febcede7f 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h @@ -30,69 +30,70 @@ void ComputeSideslipInnovAndInnovVar(const matrix::Matrix& state, const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov = nullptr, Scalar* const innov_var = nullptr) { - // Total ops: 235 + // Total ops: 265 // Input arrays - // Intermediate terms (46) - const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp2 = 1 - 2 * _tmp1; - const Scalar _tmp3 = -2 * _tmp0 + _tmp2; - const Scalar _tmp4 = -state(22, 0) + state(4, 0); - const Scalar _tmp5 = 2 * state(0, 0); - const Scalar _tmp6 = _tmp5 * state(3, 0); - const Scalar _tmp7 = 2 * state(1, 0); - const Scalar _tmp8 = _tmp7 * state(2, 0); - const Scalar _tmp9 = _tmp6 + _tmp8; - const Scalar _tmp10 = -state(23, 0) + state(5, 0); - const Scalar _tmp11 = _tmp5 * state(2, 0); - const Scalar _tmp12 = -_tmp11; - const Scalar _tmp13 = _tmp7 * state(3, 0); - const Scalar _tmp14 = _tmp12 + _tmp13; - const Scalar _tmp15 = _tmp10 * _tmp9 + _tmp14 * state(6, 0) + _tmp3 * _tmp4; - const Scalar _tmp16 = - _tmp15 + epsilon * (2 * math::min(0, (((_tmp15) > 0) - ((_tmp15) < 0))) + 1); - const Scalar _tmp17 = Scalar(1.0) / (_tmp16); - const Scalar _tmp18 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp19 = -2 * _tmp18 + _tmp2; - const Scalar _tmp20 = -_tmp6; - const Scalar _tmp21 = _tmp20 + _tmp8; - const Scalar _tmp22 = 2 * state(2, 0) * state(3, 0); - const Scalar _tmp23 = _tmp5 * state(1, 0); - const Scalar _tmp24 = _tmp22 + _tmp23; - const Scalar _tmp25 = _tmp21 * _tmp4 + _tmp24 * state(6, 0); - const Scalar _tmp26 = _tmp10 * _tmp19 + _tmp25; - const Scalar _tmp27 = _tmp26 / std::pow(_tmp16, Scalar(2)); - const Scalar _tmp28 = -_tmp14 * _tmp27 + _tmp17 * _tmp24; - const Scalar _tmp29 = _tmp27 * _tmp3; - const Scalar _tmp30 = _tmp17 * _tmp21; - const Scalar _tmp31 = -_tmp29 + _tmp30; - const Scalar _tmp32 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp33 = -_tmp32; - const Scalar _tmp34 = -_tmp18; - const Scalar _tmp35 = -_tmp13; - const Scalar _tmp36 = _tmp0 - _tmp1; - const Scalar _tmp37 = _tmp32 + _tmp34; + // Intermediate terms (42) + const Scalar _tmp0 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp1 = _tmp0 - 2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp2 = -state(22, 0) + state(4, 0); + const Scalar _tmp3 = 2 * state(0, 0); + const Scalar _tmp4 = _tmp3 * state(3, 0); + const Scalar _tmp5 = 2 * state(1, 0); + const Scalar _tmp6 = _tmp5 * state(2, 0); + const Scalar _tmp7 = _tmp4 + _tmp6; + const Scalar _tmp8 = -state(23, 0) + state(5, 0); + const Scalar _tmp9 = 2 * state(2, 0); + const Scalar _tmp10 = _tmp5 * state(3, 0) - _tmp9 * state(0, 0); + const Scalar _tmp11 = _tmp1 * _tmp2 + _tmp10 * state(6, 0) + _tmp7 * _tmp8; + const Scalar _tmp12 = + _tmp11 + epsilon * (2 * math::min(0, (((_tmp11) > 0) - ((_tmp11) < 0))) + 1); + const Scalar _tmp13 = Scalar(1.0) / (_tmp12); + const Scalar _tmp14 = _tmp0 - 2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp15 = -_tmp4 + _tmp6; + const Scalar _tmp16 = _tmp5 * state(0, 0) + _tmp9 * state(3, 0); + const Scalar _tmp17 = _tmp14 * _tmp8 + _tmp15 * _tmp2 + _tmp16 * state(6, 0); + const Scalar _tmp18 = _tmp17 / std::pow(_tmp12, Scalar(2)); + const Scalar _tmp19 = _tmp18 * _tmp7; + const Scalar _tmp20 = _tmp13 * _tmp14; + const Scalar _tmp21 = _tmp19 - _tmp20; + const Scalar _tmp22 = -_tmp10 * _tmp18 + _tmp13 * _tmp16; + const Scalar _tmp23 = _tmp1 * _tmp18; + const Scalar _tmp24 = _tmp13 * _tmp15; + const Scalar _tmp25 = -_tmp23 + _tmp24; + const Scalar _tmp26 = 2 * state(6, 0); + const Scalar _tmp27 = _tmp26 * state(0, 0); + const Scalar _tmp28 = _tmp26 * state(3, 0); + const Scalar _tmp29 = + (Scalar(1) / Scalar(2)) * _tmp13 * (_tmp2 * _tmp5 + _tmp28) - + Scalar(1) / Scalar(2) * _tmp18 * (-4 * _tmp2 * state(2, 0) - _tmp27 + _tmp5 * _tmp8); + const Scalar _tmp30 = + (Scalar(1) / Scalar(2)) * _tmp13 * (_tmp2 * _tmp9 + _tmp27 - 4 * _tmp8 * state(1, 0)) - + Scalar(1) / Scalar(2) * _tmp18 * (_tmp28 + _tmp8 * _tmp9); + const Scalar _tmp31 = 2 * state(3, 0); + const Scalar _tmp32 = _tmp26 * state(2, 0); + const Scalar _tmp33 = _tmp26 * state(1, 0); + const Scalar _tmp34 = (Scalar(1) / Scalar(2)) * _tmp13 * (-_tmp2 * _tmp31 + _tmp33) - + Scalar(1) / Scalar(2) * _tmp18 * (_tmp31 * _tmp8 - _tmp32); + const Scalar _tmp35 = 4 * state(3, 0); + const Scalar _tmp36 = + (Scalar(1) / Scalar(2)) * _tmp13 * (-_tmp2 * _tmp3 + _tmp32 - _tmp35 * _tmp8) - + Scalar(1) / Scalar(2) * _tmp18 * (-_tmp2 * _tmp35 + _tmp3 * _tmp8 + _tmp33); + const Scalar _tmp37 = + _tmp29 * state(1, 0) - _tmp30 * state(2, 0) - _tmp34 * state(3, 0) + _tmp36 * state(0, 0); const Scalar _tmp38 = - _tmp17 * (_tmp10 * (_tmp20 - _tmp8) + _tmp4 * (_tmp0 + _tmp1 + _tmp33 + _tmp34) + - state(6, 0) * (_tmp11 + _tmp35)) - - _tmp27 * (_tmp10 * (_tmp36 + _tmp37) + _tmp25); - const Scalar _tmp39 = _tmp29 - _tmp30; - const Scalar _tmp40 = _tmp27 * _tmp9; - const Scalar _tmp41 = _tmp17 * _tmp19; - const Scalar _tmp42 = -_tmp40 + _tmp41; - const Scalar _tmp43 = _tmp27 * (_tmp10 * (-_tmp22 + _tmp23) + _tmp4 * (_tmp12 + _tmp35) + - state(6, 0) * (_tmp18 + _tmp33 + _tmp36)); - const Scalar _tmp44 = _tmp40 - _tmp41; - const Scalar _tmp45 = _tmp17 * (_tmp10 * (_tmp22 - _tmp23) + _tmp4 * (_tmp11 + _tmp13) + - state(6, 0) * (-_tmp0 + _tmp1 + _tmp37)); + -_tmp29 * state(3, 0) + _tmp30 * state(0, 0) - _tmp34 * state(1, 0) + _tmp36 * state(2, 0); + const Scalar _tmp39 = + _tmp29 * state(0, 0) + _tmp30 * state(3, 0) - _tmp34 * state(2, 0) - _tmp36 * state(1, 0); + const Scalar _tmp40 = _tmp23 - _tmp24; + const Scalar _tmp41 = -_tmp19 + _tmp20; // Output terms (2) if (innov != nullptr) { Scalar& _innov = (*innov); - _innov = _tmp17 * _tmp26; + _innov = _tmp13 * _tmp17; } if (innov_var != nullptr) { @@ -100,22 +101,22 @@ void ComputeSideslipInnovAndInnovVar(const matrix::Matrix& state, _innov_var = R + - _tmp28 * (P(0, 5) * _tmp45 - P(1, 5) * _tmp43 + P(2, 5) * _tmp38 + P(21, 5) * _tmp39 + - P(22, 5) * _tmp44 + P(3, 5) * _tmp31 + P(4, 5) * _tmp42 + P(5, 5) * _tmp28) + - _tmp31 * (P(0, 3) * _tmp45 - P(1, 3) * _tmp43 + P(2, 3) * _tmp38 + P(21, 3) * _tmp39 + - P(22, 3) * _tmp44 + P(3, 3) * _tmp31 + P(4, 3) * _tmp42 + P(5, 3) * _tmp28) + - _tmp38 * (P(0, 2) * _tmp45 - P(1, 2) * _tmp43 + P(2, 2) * _tmp38 + P(21, 2) * _tmp39 + - P(22, 2) * _tmp44 + P(3, 2) * _tmp31 + P(4, 2) * _tmp42 + P(5, 2) * _tmp28) + - _tmp39 * (P(0, 21) * _tmp45 - P(1, 21) * _tmp43 + P(2, 21) * _tmp38 + P(21, 21) * _tmp39 + - P(22, 21) * _tmp44 + P(3, 21) * _tmp31 + P(4, 21) * _tmp42 + P(5, 21) * _tmp28) + - _tmp42 * (P(0, 4) * _tmp45 - P(1, 4) * _tmp43 + P(2, 4) * _tmp38 + P(21, 4) * _tmp39 + - P(22, 4) * _tmp44 + P(3, 4) * _tmp31 + P(4, 4) * _tmp42 + P(5, 4) * _tmp28) - - _tmp43 * (P(0, 1) * _tmp45 - P(1, 1) * _tmp43 + P(2, 1) * _tmp38 + P(21, 1) * _tmp39 + - P(22, 1) * _tmp44 + P(3, 1) * _tmp31 + P(4, 1) * _tmp42 + P(5, 1) * _tmp28) + - _tmp44 * (P(0, 22) * _tmp45 - P(1, 22) * _tmp43 + P(2, 22) * _tmp38 + P(21, 22) * _tmp39 + - P(22, 22) * _tmp44 + P(3, 22) * _tmp31 + P(4, 22) * _tmp42 + P(5, 22) * _tmp28) + - _tmp45 * (P(0, 0) * _tmp45 - P(1, 0) * _tmp43 + P(2, 0) * _tmp38 + P(21, 0) * _tmp39 + - P(22, 0) * _tmp44 + P(3, 0) * _tmp31 + P(4, 0) * _tmp42 + P(5, 0) * _tmp28); + _tmp21 * (P(0, 22) * _tmp38 + P(1, 22) * _tmp39 + P(2, 22) * _tmp37 + P(21, 22) * _tmp40 + + P(22, 22) * _tmp21 + P(3, 22) * _tmp25 + P(4, 22) * _tmp41 + P(5, 22) * _tmp22) + + _tmp22 * (P(0, 5) * _tmp38 + P(1, 5) * _tmp39 + P(2, 5) * _tmp37 + P(21, 5) * _tmp40 + + P(22, 5) * _tmp21 + P(3, 5) * _tmp25 + P(4, 5) * _tmp41 + P(5, 5) * _tmp22) + + _tmp25 * (P(0, 3) * _tmp38 + P(1, 3) * _tmp39 + P(2, 3) * _tmp37 + P(21, 3) * _tmp40 + + P(22, 3) * _tmp21 + P(3, 3) * _tmp25 + P(4, 3) * _tmp41 + P(5, 3) * _tmp22) + + _tmp37 * (P(0, 2) * _tmp38 + P(1, 2) * _tmp39 + P(2, 2) * _tmp37 + P(21, 2) * _tmp40 + + P(22, 2) * _tmp21 + P(3, 2) * _tmp25 + P(4, 2) * _tmp41 + P(5, 2) * _tmp22) + + _tmp38 * (P(0, 0) * _tmp38 + P(1, 0) * _tmp39 + P(2, 0) * _tmp37 + P(21, 0) * _tmp40 + + P(22, 0) * _tmp21 + P(3, 0) * _tmp25 + P(4, 0) * _tmp41 + P(5, 0) * _tmp22) + + _tmp39 * (P(0, 1) * _tmp38 + P(1, 1) * _tmp39 + P(2, 1) * _tmp37 + P(21, 1) * _tmp40 + + P(22, 1) * _tmp21 + P(3, 1) * _tmp25 + P(4, 1) * _tmp41 + P(5, 1) * _tmp22) + + _tmp40 * (P(0, 21) * _tmp38 + P(1, 21) * _tmp39 + P(2, 21) * _tmp37 + P(21, 21) * _tmp40 + + P(22, 21) * _tmp21 + P(3, 21) * _tmp25 + P(4, 21) * _tmp41 + P(5, 21) * _tmp22) + + _tmp41 * (P(0, 4) * _tmp38 + P(1, 4) * _tmp39 + P(2, 4) * _tmp37 + P(21, 4) * _tmp40 + + P(22, 4) * _tmp21 + P(3, 4) * _tmp25 + P(4, 4) * _tmp41 + P(5, 4) * _tmp22); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h index 443fb0b03c5e..e082438f09c1 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h @@ -29,25 +29,20 @@ void ComputeYawInnovVarAndH(const matrix::Matrix& state, const matrix::Matrix& P, const Scalar R, Scalar* const innov_var = nullptr, matrix::Matrix* const H = nullptr) { - // Total ops: 36 + // Total ops: 1 + + // Unused inputs + (void)state; // Input arrays - // Intermediate terms (5) - const Scalar _tmp0 = 2 * state(2, 0); - const Scalar _tmp1 = 2 * state(1, 0); - const Scalar _tmp2 = -_tmp0 * state(0, 0) + _tmp1 * state(3, 0); - const Scalar _tmp3 = _tmp0 * state(3, 0) + _tmp1 * state(0, 0); - const Scalar _tmp4 = std::pow(state(0, 0), Scalar(2)) - std::pow(state(1, 0), Scalar(2)) - - std::pow(state(2, 0), Scalar(2)) + std::pow(state(3, 0), Scalar(2)); + // Intermediate terms (0) // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = R + _tmp2 * (P(0, 0) * _tmp2 + P(1, 0) * _tmp3 + P(2, 0) * _tmp4) + - _tmp3 * (P(0, 1) * _tmp2 + P(1, 1) * _tmp3 + P(2, 1) * _tmp4) + - _tmp4 * (P(0, 2) * _tmp2 + P(1, 2) * _tmp3 + P(2, 2) * _tmp4); + _innov_var = P(2, 2) + R; } if (H != nullptr) { @@ -55,9 +50,7 @@ void ComputeYawInnovVarAndH(const matrix::Matrix& state, _h.setZero(); - _h(0, 0) = _tmp2; - _h(1, 0) = _tmp3; - _h(2, 0) = _tmp4; + _h(2, 0) = 1; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h index 338ee277c039..5fa0ad1772d1 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h @@ -34,172 +34,211 @@ matrix::Matrix PredictCovariance(const matrix::Matrix& accel_var, const matrix::Matrix& gyro, const Scalar gyro_var, const Scalar dt) { - // Total ops: 1793 + // Total ops: 1754 + + // Unused inputs + (void)gyro; // Input arrays - // Intermediate terms (134) - const Scalar _tmp0 = dt * gyro(1, 0); - const Scalar _tmp1 = dt * state(11, 0); - const Scalar _tmp2 = -_tmp0 + _tmp1; - const Scalar _tmp3 = dt * gyro(2, 0); - const Scalar _tmp4 = dt * state(12, 0); - const Scalar _tmp5 = _tmp3 - _tmp4; - const Scalar _tmp6 = P(0, 2) + P(1, 2) * _tmp5 + P(2, 2) * _tmp2 - P(9, 2) * dt; - const Scalar _tmp7 = P(0, 1) + P(1, 1) * _tmp5 + P(2, 1) * _tmp2 - P(9, 1) * dt; - const Scalar _tmp8 = P(0, 9) + P(1, 9) * _tmp5 + P(2, 9) * _tmp2 - P(9, 9) * dt; - const Scalar _tmp9 = std::pow(dt, Scalar(2)); - const Scalar _tmp10 = _tmp9 * gyro_var; - const Scalar _tmp11 = P(0, 0) + P(1, 0) * _tmp5 + P(2, 0) * _tmp2 - P(9, 0) * dt; - const Scalar _tmp12 = P(0, 10) + P(1, 10) * _tmp5 + P(2, 10) * _tmp2 - P(9, 10) * dt; - const Scalar _tmp13 = -_tmp3 + _tmp4; - const Scalar _tmp14 = dt * gyro(0, 0); - const Scalar _tmp15 = dt * state(10, 0); - const Scalar _tmp16 = _tmp14 - _tmp15; - const Scalar _tmp17 = P(0, 10) * _tmp13 + P(1, 10) - P(10, 10) * dt + P(2, 10) * _tmp16; - const Scalar _tmp18 = P(0, 0) * _tmp13 + P(1, 0) - P(10, 0) * dt + P(2, 0) * _tmp16; - const Scalar _tmp19 = P(0, 2) * _tmp13 + P(1, 2) - P(10, 2) * dt + P(2, 2) * _tmp16; - const Scalar _tmp20 = P(0, 1) * _tmp13 + P(1, 1) - P(10, 1) * dt + P(2, 1) * _tmp16; - const Scalar _tmp21 = P(0, 11) + P(1, 11) * _tmp5 + P(2, 11) * _tmp2 - P(9, 11) * dt; - const Scalar _tmp22 = _tmp0 - _tmp1; - const Scalar _tmp23 = -_tmp14 + _tmp15; - const Scalar _tmp24 = P(0, 11) * _tmp13 + P(1, 11) - P(10, 11) * dt + P(2, 11) * _tmp16; - const Scalar _tmp25 = P(0, 11) * _tmp22 + P(1, 11) * _tmp23 - P(11, 11) * dt + P(2, 11); - const Scalar _tmp26 = P(0, 1) * _tmp22 + P(1, 1) * _tmp23 - P(11, 1) * dt + P(2, 1); - const Scalar _tmp27 = P(0, 0) * _tmp22 + P(1, 0) * _tmp23 - P(11, 0) * dt + P(2, 0); - const Scalar _tmp28 = P(0, 2) * _tmp22 + P(1, 2) * _tmp23 - P(11, 2) * dt + P(2, 2); - const Scalar _tmp29 = 2 * state(0, 0); - const Scalar _tmp30 = _tmp29 * state(3, 0); - const Scalar _tmp31 = -_tmp30; - const Scalar _tmp32 = 2 * state(1, 0); - const Scalar _tmp33 = _tmp32 * state(2, 0); + // Intermediate terms (147) + const Scalar _tmp0 = 2 * state(1, 0); + const Scalar _tmp1 = _tmp0 * state(3, 0); + const Scalar _tmp2 = -_tmp1 * dt; + const Scalar _tmp3 = 2 * state(0, 0); + const Scalar _tmp4 = _tmp3 * state(2, 0); + const Scalar _tmp5 = _tmp4 * dt; + const Scalar _tmp6 = _tmp2 - _tmp5; + const Scalar _tmp7 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp8 = _tmp7 * dt; + const Scalar _tmp9 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp10 = -_tmp9 * dt; + const Scalar _tmp11 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp12 = _tmp11 * dt; + const Scalar _tmp13 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp14 = _tmp13 * dt; + const Scalar _tmp15 = _tmp10 + _tmp12 - _tmp14 + _tmp8; + const Scalar _tmp16 = _tmp13 + _tmp7; + const Scalar _tmp17 = _tmp11 + _tmp9; + const Scalar _tmp18 = _tmp16 + _tmp17; + const Scalar _tmp19 = _tmp0 * state(2, 0); + const Scalar _tmp20 = -_tmp19 * dt; + const Scalar _tmp21 = _tmp3 * state(3, 0); + const Scalar _tmp22 = _tmp21 * dt; + const Scalar _tmp23 = _tmp20 + _tmp22; + const Scalar _tmp24 = + P(0, 11) * _tmp18 + P(10, 11) * _tmp23 + P(11, 11) * _tmp6 + P(9, 11) * _tmp15; + const Scalar _tmp25 = + P(0, 10) * _tmp18 + P(10, 10) * _tmp23 + P(11, 10) * _tmp6 + P(9, 10) * _tmp15; + const Scalar _tmp26 = P(0, 0) * _tmp18 + P(10, 0) * _tmp23 + P(11, 0) * _tmp6 + P(9, 0) * _tmp15; + const Scalar _tmp27 = P(0, 9) * _tmp18 + P(10, 9) * _tmp23 + P(11, 9) * _tmp6 + P(9, 9) * _tmp15; + const Scalar _tmp28 = _tmp10 + _tmp14; + const Scalar _tmp29 = -_tmp12 + _tmp28 + _tmp8; + const Scalar _tmp30 = _tmp0 * state(0, 0); + const Scalar _tmp31 = _tmp30 * dt; + const Scalar _tmp32 = 2 * state(2, 0) * state(3, 0); + const Scalar _tmp33 = -_tmp32 * dt; const Scalar _tmp34 = _tmp31 + _tmp33; - const Scalar _tmp35 = accel(0, 0) - state(13, 0); - const Scalar _tmp36 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp37 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp38 = -_tmp37; - const Scalar _tmp39 = _tmp36 + _tmp38; - const Scalar _tmp40 = std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp41 = -_tmp40; - const Scalar _tmp42 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp43 = _tmp41 + _tmp42; - const Scalar _tmp44 = accel(1, 0) - state(14, 0); - const Scalar _tmp45 = dt * (_tmp34 * _tmp35 + _tmp44 * (_tmp39 + _tmp43)); - const Scalar _tmp46 = P(0, 12) + P(1, 12) * _tmp5 + P(2, 12) * _tmp2 - P(9, 12) * dt; - const Scalar _tmp47 = -2 * _tmp42; - const Scalar _tmp48 = -2 * _tmp36; - const Scalar _tmp49 = _tmp47 + _tmp48 + 1; - const Scalar _tmp50 = _tmp49 * dt; - const Scalar _tmp51 = _tmp29 * state(2, 0); - const Scalar _tmp52 = -_tmp51; - const Scalar _tmp53 = _tmp32 * state(3, 0); - const Scalar _tmp54 = -_tmp53; - const Scalar _tmp55 = -_tmp42; - const Scalar _tmp56 = _tmp40 + _tmp55; - const Scalar _tmp57 = -_tmp36; - const Scalar _tmp58 = _tmp37 + _tmp57; - const Scalar _tmp59 = accel(2, 0) - state(15, 0); - const Scalar _tmp60 = dt * (_tmp35 * (_tmp52 + _tmp54) + _tmp59 * (_tmp56 + _tmp58)); - const Scalar _tmp61 = _tmp51 + _tmp53; - const Scalar _tmp62 = -_tmp33; - const Scalar _tmp63 = dt * (_tmp44 * _tmp61 + _tmp59 * (_tmp30 + _tmp62)); - const Scalar _tmp64 = P(0, 13) + P(1, 13) * _tmp5 + P(2, 13) * _tmp2 - P(9, 13) * dt; - const Scalar _tmp65 = _tmp34 * dt; - const Scalar _tmp66 = P(0, 14) + P(1, 14) * _tmp5 + P(2, 14) * _tmp2 - P(9, 14) * dt; - const Scalar _tmp67 = _tmp61 * dt; - const Scalar _tmp68 = P(0, 3) + P(1, 3) * _tmp5 + P(2, 3) * _tmp2 - P(9, 3) * dt; - const Scalar _tmp69 = P(0, 13) * _tmp13 + P(1, 13) - P(10, 13) * dt + P(2, 13) * _tmp16; - const Scalar _tmp70 = P(0, 14) * _tmp13 + P(1, 14) - P(10, 14) * dt + P(2, 14) * _tmp16; - const Scalar _tmp71 = P(0, 12) * _tmp13 + P(1, 12) - P(10, 12) * dt + P(2, 12) * _tmp16; - const Scalar _tmp72 = P(0, 3) * _tmp13 + P(1, 3) - P(10, 3) * dt + P(2, 3) * _tmp16; - const Scalar _tmp73 = P(0, 14) * _tmp22 + P(1, 14) * _tmp23 - P(11, 14) * dt + P(2, 14); - const Scalar _tmp74 = P(0, 13) * _tmp22 + P(1, 13) * _tmp23 - P(11, 13) * dt + P(2, 13); - const Scalar _tmp75 = P(0, 12) * _tmp22 + P(1, 12) * _tmp23 - P(11, 12) * dt + P(2, 12); - const Scalar _tmp76 = P(0, 3) * _tmp22 + P(1, 3) * _tmp23 - P(11, 3) * dt + P(2, 3); - const Scalar _tmp77 = P(0, 1) * _tmp63 + P(1, 1) * _tmp60 - P(12, 1) * _tmp50 - - P(13, 1) * _tmp65 - P(14, 1) * _tmp67 + P(2, 1) * _tmp45 + P(3, 1); - const Scalar _tmp78 = P(0, 14) * _tmp63 + P(1, 14) * _tmp60 - P(12, 14) * _tmp50 - - P(13, 14) * _tmp65 - P(14, 14) * _tmp67 + P(2, 14) * _tmp45 + P(3, 14); - const Scalar _tmp79 = P(0, 13) * _tmp63 + P(1, 13) * _tmp60 - P(12, 13) * _tmp50 - - P(13, 13) * _tmp65 - P(14, 13) * _tmp67 + P(2, 13) * _tmp45 + P(3, 13); - const Scalar _tmp80 = P(0, 0) * _tmp63 + P(1, 0) * _tmp60 - P(12, 0) * _tmp50 - - P(13, 0) * _tmp65 - P(14, 0) * _tmp67 + P(2, 0) * _tmp45 + P(3, 0); - const Scalar _tmp81 = _tmp9 * accel_var(0, 0); - const Scalar _tmp82 = P(0, 2) * _tmp63 + P(1, 2) * _tmp60 - P(12, 2) * _tmp50 - - P(13, 2) * _tmp65 - P(14, 2) * _tmp67 + P(2, 2) * _tmp45 + P(3, 2); - const Scalar _tmp83 = _tmp9 * accel_var(1, 0); - const Scalar _tmp84 = _tmp9 * accel_var(2, 0); - const Scalar _tmp85 = P(0, 12) * _tmp63 + P(1, 12) * _tmp60 - P(12, 12) * _tmp50 - - P(13, 12) * _tmp65 - P(14, 12) * _tmp67 + P(2, 12) * _tmp45 + P(3, 12); - const Scalar _tmp86 = P(0, 3) * _tmp63 + P(1, 3) * _tmp60 - P(12, 3) * _tmp50 - - P(13, 3) * _tmp65 - P(14, 3) * _tmp67 + P(2, 3) * _tmp45 + P(3, 3); - const Scalar _tmp87 = 2 * state(2, 0) * state(3, 0); - const Scalar _tmp88 = _tmp29 * state(1, 0); - const Scalar _tmp89 = -_tmp88; - const Scalar _tmp90 = _tmp87 + _tmp89; - const Scalar _tmp91 = dt * (_tmp44 * _tmp90 + _tmp59 * (_tmp43 + _tmp58)); - const Scalar _tmp92 = dt * (_tmp35 * (_tmp39 + _tmp56) + _tmp44 * (_tmp31 + _tmp62)); - const Scalar _tmp93 = 1 - 2 * _tmp37; - const Scalar _tmp94 = _tmp47 + _tmp93; - const Scalar _tmp95 = _tmp94 * dt; - const Scalar _tmp96 = _tmp90 * dt; - const Scalar _tmp97 = _tmp30 + _tmp33; - const Scalar _tmp98 = -_tmp87; - const Scalar _tmp99 = dt * (_tmp35 * (_tmp88 + _tmp98) + _tmp59 * _tmp97); - const Scalar _tmp100 = _tmp97 * dt; - const Scalar _tmp101 = P(0, 4) + P(1, 4) * _tmp5 + P(2, 4) * _tmp2 - P(9, 4) * dt; - const Scalar _tmp102 = P(0, 4) * _tmp13 + P(1, 4) - P(10, 4) * dt + P(2, 4) * _tmp16; - const Scalar _tmp103 = _tmp74 * dt; - const Scalar _tmp104 = P(0, 4) * _tmp22 + P(1, 4) * _tmp23 - P(11, 4) * dt + P(2, 4); - const Scalar _tmp105 = _tmp81 * _tmp97; - const Scalar _tmp106 = _tmp84 * _tmp90; - const Scalar _tmp107 = P(0, 4) * _tmp63 + P(1, 4) * _tmp60 - P(12, 4) * _tmp50 - - P(13, 4) * _tmp65 - P(14, 4) * _tmp67 + P(2, 4) * _tmp45 + P(3, 4); - const Scalar _tmp108 = P(0, 14) * _tmp91 + P(1, 14) * _tmp99 - P(12, 14) * _tmp100 - - P(13, 14) * _tmp95 - P(14, 14) * _tmp96 + P(2, 14) * _tmp92 + P(4, 14); - const Scalar _tmp109 = P(0, 0) * _tmp91 + P(1, 0) * _tmp99 - P(12, 0) * _tmp100 - - P(13, 0) * _tmp95 - P(14, 0) * _tmp96 + P(2, 0) * _tmp92 + P(4, 0); - const Scalar _tmp110 = P(0, 13) * _tmp91 + P(1, 13) * _tmp99 - P(12, 13) * _tmp100 - - P(13, 13) * _tmp95 - P(14, 13) * _tmp96 + P(2, 13) * _tmp92 + P(4, 13); - const Scalar _tmp111 = P(0, 12) * _tmp91 + P(1, 12) * _tmp99 - P(12, 12) * _tmp100 - - P(13, 12) * _tmp95 - P(14, 12) * _tmp96 + P(2, 12) * _tmp92 + P(4, 12); - const Scalar _tmp112 = P(0, 1) * _tmp91 + P(1, 1) * _tmp99 - P(12, 1) * _tmp100 - - P(13, 1) * _tmp95 - P(14, 1) * _tmp96 + P(2, 1) * _tmp92 + P(4, 1); - const Scalar _tmp113 = P(0, 2) * _tmp91 + P(1, 2) * _tmp99 - P(12, 2) * _tmp100 - - P(13, 2) * _tmp95 - P(14, 2) * _tmp96 + P(2, 2) * _tmp92 + P(4, 2); - const Scalar _tmp114 = P(0, 4) * _tmp91 + P(1, 4) * _tmp99 - P(12, 4) * _tmp100 - - P(13, 4) * _tmp95 - P(14, 4) * _tmp96 + P(2, 4) * _tmp92 + P(4, 4); - const Scalar _tmp115 = - dt * (_tmp44 * (_tmp38 + _tmp40 + _tmp42 + _tmp57) + _tmp59 * (_tmp89 + _tmp98)); - const Scalar _tmp116 = _tmp48 + _tmp93; - const Scalar _tmp117 = _tmp116 * dt; - const Scalar _tmp118 = _tmp87 + _tmp88; - const Scalar _tmp119 = _tmp118 * dt; - const Scalar _tmp120 = dt * (_tmp118 * _tmp35 + _tmp44 * (_tmp51 + _tmp54)); - const Scalar _tmp121 = _tmp52 + _tmp53; - const Scalar _tmp122 = dt * (_tmp121 * _tmp59 + _tmp35 * (_tmp36 + _tmp37 + _tmp41 + _tmp55)); - const Scalar _tmp123 = _tmp121 * dt; - const Scalar _tmp124 = P(0, 5) + P(1, 5) * _tmp5 + P(2, 5) * _tmp2 - P(9, 5) * dt; - const Scalar _tmp125 = P(0, 5) * _tmp13 + P(1, 5) - P(10, 5) * dt + P(2, 5) * _tmp16; - const Scalar _tmp126 = P(0, 5) * _tmp22 + P(1, 5) * _tmp23 - P(11, 5) * dt + P(2, 5); - const Scalar _tmp127 = _tmp118 * _tmp83; - const Scalar _tmp128 = P(0, 5) * _tmp63 + P(1, 5) * _tmp60 - P(12, 5) * _tmp50 - - P(13, 5) * _tmp65 - P(14, 5) * _tmp67 + P(2, 5) * _tmp45 + P(3, 5); - const Scalar _tmp129 = P(0, 5) * _tmp91 + P(1, 5) * _tmp99 - P(12, 5) * _tmp100 - - P(13, 5) * _tmp95 - P(14, 5) * _tmp96 + P(2, 5) * _tmp92 + P(4, 5); - const Scalar _tmp130 = P(0, 13) * _tmp115 + P(1, 13) * _tmp122 - P(12, 13) * _tmp123 - - P(13, 13) * _tmp119 - P(14, 13) * _tmp117 + P(2, 13) * _tmp120 + P(5, 13); - const Scalar _tmp131 = P(0, 14) * _tmp115 + P(1, 14) * _tmp122 - P(12, 14) * _tmp123 - - P(13, 14) * _tmp119 - P(14, 14) * _tmp117 + P(2, 14) * _tmp120 + P(5, 14); - const Scalar _tmp132 = P(0, 12) * _tmp115 + P(1, 12) * _tmp122 - P(12, 12) * _tmp123 - - P(13, 12) * _tmp119 - P(14, 12) * _tmp117 + P(2, 12) * _tmp120 + P(5, 12); - const Scalar _tmp133 = P(0, 5) * _tmp115 + P(1, 5) * _tmp122 - P(12, 5) * _tmp123 - - P(13, 5) * _tmp119 - P(14, 5) * _tmp117 + P(2, 5) * _tmp120 + P(5, 5); + const Scalar _tmp35 = P(0, 1) * _tmp18 + P(10, 1) * _tmp23 + P(11, 1) * _tmp6 + P(9, 1) * _tmp15; + const Scalar _tmp36 = _tmp20 - _tmp22; + const Scalar _tmp37 = _tmp23 * gyro_var; + const Scalar _tmp38 = _tmp36 * gyro_var; + const Scalar _tmp39 = _tmp6 * gyro_var; + const Scalar _tmp40 = + P(1, 10) * _tmp18 + P(10, 10) * _tmp29 + P(11, 10) * _tmp34 + P(9, 10) * _tmp36; + const Scalar _tmp41 = + P(1, 11) * _tmp18 + P(10, 11) * _tmp29 + P(11, 11) * _tmp34 + P(9, 11) * _tmp36; + const Scalar _tmp42 = P(1, 9) * _tmp18 + P(10, 9) * _tmp29 + P(11, 9) * _tmp34 + P(9, 9) * _tmp36; + const Scalar _tmp43 = P(1, 1) * _tmp18 + P(10, 1) * _tmp29 + P(11, 1) * _tmp34 + P(9, 1) * _tmp36; + const Scalar _tmp44 = _tmp12 + _tmp28 - _tmp8; + const Scalar _tmp45 = -_tmp31 + _tmp33; + const Scalar _tmp46 = P(0, 2) * _tmp18 + P(10, 2) * _tmp23 + P(11, 2) * _tmp6 + P(9, 2) * _tmp15; + const Scalar _tmp47 = _tmp2 + _tmp5; + const Scalar _tmp48 = P(1, 2) * _tmp18 + P(10, 2) * _tmp29 + P(11, 2) * _tmp34 + P(9, 2) * _tmp36; + const Scalar _tmp49 = + P(10, 10) * _tmp45 + P(11, 10) * _tmp44 + P(2, 10) * _tmp18 + P(9, 10) * _tmp47; + const Scalar _tmp50 = + P(10, 11) * _tmp45 + P(11, 11) * _tmp44 + P(2, 11) * _tmp18 + P(9, 11) * _tmp47; + const Scalar _tmp51 = P(10, 2) * _tmp45 + P(11, 2) * _tmp44 + P(2, 2) * _tmp18 + P(9, 2) * _tmp47; + const Scalar _tmp52 = P(10, 9) * _tmp45 + P(11, 9) * _tmp44 + P(2, 9) * _tmp18 + P(9, 9) * _tmp47; + const Scalar _tmp53 = + P(0, 12) * _tmp18 + P(10, 12) * _tmp23 + P(11, 12) * _tmp6 + P(9, 12) * _tmp15; + const Scalar _tmp54 = -2 * _tmp7; + const Scalar _tmp55 = -2 * _tmp11; + const Scalar _tmp56 = _tmp54 + _tmp55 + 1; + const Scalar _tmp57 = _tmp56 * dt; + const Scalar _tmp58 = + P(0, 13) * _tmp18 + P(10, 13) * _tmp23 + P(11, 13) * _tmp6 + P(9, 13) * _tmp15; + const Scalar _tmp59 = -_tmp21; + const Scalar _tmp60 = _tmp19 + _tmp59; + const Scalar _tmp61 = _tmp60 * dt; + const Scalar _tmp62 = + P(0, 14) * _tmp18 + P(10, 14) * _tmp23 + P(11, 14) * _tmp6 + P(9, 14) * _tmp15; + const Scalar _tmp63 = _tmp1 + _tmp4; + const Scalar _tmp64 = _tmp63 * dt; + const Scalar _tmp65 = -_tmp4; + const Scalar _tmp66 = _tmp1 + _tmp65; + const Scalar _tmp67 = accel(0, 0) - state(13, 0); + const Scalar _tmp68 = -_tmp13; + const Scalar _tmp69 = _tmp68 + _tmp7; + const Scalar _tmp70 = -_tmp11; + const Scalar _tmp71 = _tmp70 + _tmp9; + const Scalar _tmp72 = accel(2, 0) - state(15, 0); + const Scalar _tmp73 = _tmp30 + _tmp32; + const Scalar _tmp74 = accel(1, 0) - state(14, 0); + const Scalar _tmp75 = dt * (_tmp66 * _tmp67 + _tmp72 * (_tmp69 + _tmp71) + _tmp73 * _tmp74); + const Scalar _tmp76 = -_tmp19; + const Scalar _tmp77 = -_tmp9; + const Scalar _tmp78 = -_tmp32; + const Scalar _tmp79 = dt * (_tmp67 * (_tmp59 + _tmp76) + _tmp72 * (_tmp30 + _tmp78) + + _tmp74 * (_tmp16 + _tmp70 + _tmp77)); + const Scalar _tmp80 = P(0, 3) * _tmp18 + P(10, 3) * _tmp23 + P(11, 3) * _tmp6 + P(9, 3) * _tmp15; + const Scalar _tmp81 = + P(1, 12) * _tmp18 + P(10, 12) * _tmp29 + P(11, 12) * _tmp34 + P(9, 12) * _tmp36; + const Scalar _tmp82 = + P(1, 13) * _tmp18 + P(10, 13) * _tmp29 + P(11, 13) * _tmp34 + P(9, 13) * _tmp36; + const Scalar _tmp83 = + P(1, 14) * _tmp18 + P(10, 14) * _tmp29 + P(11, 14) * _tmp34 + P(9, 14) * _tmp36; + const Scalar _tmp84 = P(1, 3) * _tmp18 + P(10, 3) * _tmp29 + P(11, 3) * _tmp34 + P(9, 3) * _tmp36; + const Scalar _tmp85 = + P(10, 12) * _tmp45 + P(11, 12) * _tmp44 + P(2, 12) * _tmp18 + P(9, 12) * _tmp47; + const Scalar _tmp86 = P(10, 1) * _tmp45 + P(11, 1) * _tmp44 + P(2, 1) * _tmp18 + P(9, 1) * _tmp47; + const Scalar _tmp87 = + P(10, 13) * _tmp45 + P(11, 13) * _tmp44 + P(2, 13) * _tmp18 + P(9, 13) * _tmp47; + const Scalar _tmp88 = + P(10, 14) * _tmp45 + P(11, 14) * _tmp44 + P(2, 14) * _tmp18 + P(9, 14) * _tmp47; + const Scalar _tmp89 = P(10, 3) * _tmp45 + P(11, 3) * _tmp44 + P(2, 3) * _tmp18 + P(9, 3) * _tmp47; + const Scalar _tmp90 = P(1, 12) * _tmp75 - P(12, 12) * _tmp57 - P(13, 12) * _tmp61 - + P(14, 12) * _tmp64 + P(2, 12) * _tmp79 + P(3, 12); + const Scalar _tmp91 = P(1, 1) * _tmp75 - P(12, 1) * _tmp57 - P(13, 1) * _tmp61 - + P(14, 1) * _tmp64 + P(2, 1) * _tmp79 + P(3, 1); + const Scalar _tmp92 = P(1, 2) * _tmp75 - P(12, 2) * _tmp57 - P(13, 2) * _tmp61 - + P(14, 2) * _tmp64 + P(2, 2) * _tmp79 + P(3, 2); + const Scalar _tmp93 = P(1, 13) * _tmp75 - P(12, 13) * _tmp57 - P(13, 13) * _tmp61 - + P(14, 13) * _tmp64 + P(2, 13) * _tmp79 + P(3, 13); + const Scalar _tmp94 = P(1, 14) * _tmp75 - P(12, 14) * _tmp57 - P(13, 14) * _tmp61 - + P(14, 14) * _tmp64 + P(2, 14) * _tmp79 + P(3, 14); + const Scalar _tmp95 = std::pow(dt, Scalar(2)); + const Scalar _tmp96 = _tmp95 * accel_var(0, 0); + const Scalar _tmp97 = _tmp95 * accel_var(1, 0); + const Scalar _tmp98 = _tmp95 * accel_var(2, 0); + const Scalar _tmp99 = P(1, 3) * _tmp75 - P(12, 3) * _tmp57 - P(13, 3) * _tmp61 - + P(14, 3) * _tmp64 + P(2, 3) * _tmp79 + P(3, 3); + const Scalar _tmp100 = 1 - 2 * _tmp13; + const Scalar _tmp101 = _tmp100 + _tmp54; + const Scalar _tmp102 = _tmp101 * dt; + const Scalar _tmp103 = -_tmp7; + const Scalar _tmp104 = _tmp103 + _tmp13; + const Scalar _tmp105 = dt * (_tmp60 * _tmp74 + _tmp63 * _tmp72 + _tmp67 * (_tmp104 + _tmp71)); + const Scalar _tmp106 = -_tmp30; + const Scalar _tmp107 = _tmp106 + _tmp32; + const Scalar _tmp108 = _tmp107 * dt; + const Scalar _tmp109 = _tmp19 + _tmp21; + const Scalar _tmp110 = _tmp109 * dt; + const Scalar _tmp111 = -_tmp1; + const Scalar _tmp112 = _tmp11 + _tmp77; + const Scalar _tmp113 = + _tmp67 * (_tmp111 + _tmp4) + _tmp72 * (_tmp104 + _tmp112) + _tmp74 * (_tmp106 + _tmp78); + const Scalar _tmp114 = _tmp26 * dt; + const Scalar _tmp115 = P(0, 4) * _tmp18 + P(10, 4) * _tmp23 + P(11, 4) * _tmp6 + P(9, 4) * _tmp15; + const Scalar _tmp116 = + P(1, 0) * _tmp18 + P(10, 0) * _tmp29 + P(11, 0) * _tmp34 + P(9, 0) * _tmp36; + const Scalar _tmp117 = _tmp113 * dt; + const Scalar _tmp118 = + P(1, 4) * _tmp18 + P(10, 4) * _tmp29 + P(11, 4) * _tmp34 + P(9, 4) * _tmp36; + const Scalar _tmp119 = + P(10, 0) * _tmp45 + P(11, 0) * _tmp44 + P(2, 0) * _tmp18 + P(9, 0) * _tmp47; + const Scalar _tmp120 = + P(10, 4) * _tmp45 + P(11, 4) * _tmp44 + P(2, 4) * _tmp18 + P(9, 4) * _tmp47; + const Scalar _tmp121 = _tmp56 * _tmp96; + const Scalar _tmp122 = _tmp60 * _tmp97; + const Scalar _tmp123 = P(1, 0) * _tmp75 - P(12, 0) * _tmp57 - P(13, 0) * _tmp61 - + P(14, 0) * _tmp64 + P(2, 0) * _tmp79 + P(3, 0); + const Scalar _tmp124 = _tmp63 * _tmp98; + const Scalar _tmp125 = P(1, 4) * _tmp75 - P(12, 4) * _tmp57 - P(13, 4) * _tmp61 - + P(14, 4) * _tmp64 + P(2, 4) * _tmp79 + P(3, 4); + const Scalar _tmp126 = P(0, 0) * _tmp117 - P(12, 0) * _tmp110 - P(13, 0) * _tmp102 - + P(14, 0) * _tmp108 + P(2, 0) * _tmp105 + P(4, 0); + const Scalar _tmp127 = P(0, 13) * _tmp117 - P(12, 13) * _tmp110 - P(13, 13) * _tmp102 - + P(14, 13) * _tmp108 + P(2, 13) * _tmp105 + P(4, 13); + const Scalar _tmp128 = P(0, 14) * _tmp117 - P(12, 14) * _tmp110 - P(13, 14) * _tmp102 - + P(14, 14) * _tmp108 + P(2, 14) * _tmp105 + P(4, 14); + const Scalar _tmp129 = P(0, 12) * _tmp117 - P(12, 12) * _tmp110 - P(13, 12) * _tmp102 - + P(14, 12) * _tmp108 + P(2, 12) * _tmp105 + P(4, 12); + const Scalar _tmp130 = P(0, 4) * _tmp117 - P(12, 4) * _tmp110 - P(13, 4) * _tmp102 - + P(14, 4) * _tmp108 + P(2, 4) * _tmp105 + P(4, 4); + const Scalar _tmp131 = _tmp100 + _tmp55; + const Scalar _tmp132 = _tmp131 * dt; + const Scalar _tmp133 = + dt * (_tmp67 * (_tmp112 + _tmp69) + _tmp72 * (_tmp111 + _tmp65) + _tmp74 * (_tmp21 + _tmp76)); + const Scalar _tmp134 = _tmp73 * dt; + const Scalar _tmp135 = _tmp66 * dt; + const Scalar _tmp136 = _tmp107 * _tmp72 + _tmp109 * _tmp67 + _tmp74 * (_tmp103 + _tmp17 + _tmp68); + const Scalar _tmp137 = P(0, 5) * _tmp18 + P(10, 5) * _tmp23 + P(11, 5) * _tmp6 + P(9, 5) * _tmp15; + const Scalar _tmp138 = _tmp136 * dt; + const Scalar _tmp139 = + P(1, 5) * _tmp18 + P(10, 5) * _tmp29 + P(11, 5) * _tmp34 + P(9, 5) * _tmp36; + const Scalar _tmp140 = + P(10, 5) * _tmp45 + P(11, 5) * _tmp44 + P(2, 5) * _tmp18 + P(9, 5) * _tmp47; + const Scalar _tmp141 = P(1, 5) * _tmp75 - P(12, 5) * _tmp57 - P(13, 5) * _tmp61 - + P(14, 5) * _tmp64 + P(2, 5) * _tmp79 + P(3, 5); + const Scalar _tmp142 = P(0, 5) * _tmp117 - P(12, 5) * _tmp110 - P(13, 5) * _tmp102 - + P(14, 5) * _tmp108 + P(2, 5) * _tmp105 + P(4, 5); + const Scalar _tmp143 = P(0, 14) * _tmp138 + P(1, 14) * _tmp133 - P(12, 14) * _tmp135 - + P(13, 14) * _tmp134 - P(14, 14) * _tmp132 + P(5, 14); + const Scalar _tmp144 = P(0, 13) * _tmp138 + P(1, 13) * _tmp133 - P(12, 13) * _tmp135 - + P(13, 13) * _tmp134 - P(14, 13) * _tmp132 + P(5, 13); + const Scalar _tmp145 = P(0, 12) * _tmp138 + P(1, 12) * _tmp133 - P(12, 12) * _tmp135 - + P(13, 12) * _tmp134 - P(14, 12) * _tmp132 + P(5, 12); + const Scalar _tmp146 = P(0, 5) * _tmp138 + P(1, 5) * _tmp133 - P(12, 5) * _tmp135 - + P(13, 5) * _tmp134 - P(14, 5) * _tmp132 + P(5, 5); // Output terms (1) matrix::Matrix _res; - _res(0, 0) = _tmp10 + _tmp11 + _tmp2 * _tmp6 + _tmp5 * _tmp7 - _tmp8 * dt; + _res(0, 0) = std::pow(_tmp15, Scalar(2)) * gyro_var + _tmp15 * _tmp27 + _tmp18 * _tmp26 + + std::pow(_tmp23, Scalar(2)) * gyro_var + _tmp23 * _tmp25 + _tmp24 * _tmp6 + + std::pow(_tmp6, Scalar(2)) * gyro_var; _res(1, 0) = 0; _res(2, 0) = 0; _res(3, 0) = 0; @@ -222,8 +261,11 @@ matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::MatrixgetVelocity()); - EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.01f) + EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.02f) << "estimated vel = " << estimated_horz_velocity(0); - EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f) + EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.02f) << "estimated vel = " << estimated_horz_velocity(1); } diff --git a/src/modules/ekf2/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp index 142a4ea3ef73..fb1990f90b1f 100644 --- a/src/modules/ekf2/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -78,7 +78,7 @@ class EkfInitializationTest : public ::testing::Test void quaternionVarianceBigEnoughAfterOrientationInitialization(float quat_variance_limit = 0.00001f) { - const matrix::Vector3f quat_variance = _ekf->getQuaternionVariance(); + const matrix::Vector3f quat_variance = _ekf->getRotVarBody(); EXPECT_TRUE(quat_variance(0) > quat_variance_limit) << "quat_variance(3): " << quat_variance(0); EXPECT_TRUE(quat_variance(1) > quat_variance_limit) << "quat_variance(1): " << quat_variance(1); EXPECT_TRUE(quat_variance(2) > quat_variance_limit) << "quat_variance(2): " << quat_variance(2); diff --git a/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp b/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp index 7e536e62bb79..77d1f10687d4 100644 --- a/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp +++ b/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp @@ -42,9 +42,8 @@ using namespace matrix; Vector3f getRotVarNed(const Quatf &q, const SquareMatrixState &P) { constexpr auto S = State::quat_nominal; - matrix::SquareMatrix3f rot_cov_body = P.slice(S.idx, S.idx); - auto R_to_earth = Dcmf(q); - return matrix::SquareMatrix(R_to_earth * rot_cov_body * R_to_earth.T()).diag(); + matrix::SquareMatrix3f rot_cov_ned = P.slice(S.idx, S.idx); + return rot_cov_ned.diag(); } TEST(YawFusionGenerated, positiveVarianceAllOrientations) From 0c9e4013d26f6b22ea702f06f7c10da24a8c08f1 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 25 Mar 2024 11:53:25 +0100 Subject: [PATCH 080/652] ekf2: improve tilt leveling speed Starting with no yaw uncertainty makes the tilt more observable when using fake position fusion during the quasi-stationary alignment phase. --- src/modules/ekf2/EKF/covariance.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 482596070b96..055feef795e9 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -53,7 +53,7 @@ void Ekf::initialiseCovariance() { P.zero(); - resetQuatCov(); + resetQuatCov(0.f); // Start with no initial uncertainty to improve fine leveling through zero vel/pos fusion // velocity #if defined(CONFIG_EKF2_GNSS) @@ -271,7 +271,7 @@ void Ekf::resetQuatCov(const float yaw_noise) // update the yaw angle variance using the variance of the measurement if (PX4_ISFINITE(yaw_noise)) { // using magnetic heading tuning parameter - yaw_var = math::max(sq(yaw_noise), yaw_var); + yaw_var = sq(yaw_noise); } resetQuatCov(Vector3f(tilt_var, tilt_var, yaw_var)); From 51883fe5d4738ff057bbb54ed3fa2373b41d8152 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 25 Mar 2024 11:57:27 +0100 Subject: [PATCH 081/652] ekf2: integrate mag heading into mag 3D --- msg/EstimatorAidSource1d.msg | 2 +- src/modules/ekf2/CMakeLists.txt | 1 - src/modules/ekf2/EKF/CMakeLists.txt | 1 - src/modules/ekf2/EKF/ekf.cpp | 1 - src/modules/ekf2/EKF/ekf.h | 31 +-- src/modules/ekf2/EKF/ekf_helper.cpp | 13 +- src/modules/ekf2/EKF/mag_3d_control.cpp | 23 ++- src/modules/ekf2/EKF/mag_control.cpp | 34 +++- src/modules/ekf2/EKF/mag_fusion.cpp | 7 +- src/modules/ekf2/EKF/mag_heading_control.cpp | 204 ------------------- src/modules/ekf2/EKF2.cpp | 4 - src/modules/ekf2/EKF2.hpp | 2 - src/modules/ekf2/test/test_EKF_flow.cpp | 6 +- src/modules/logger/logged_topics.cpp | 2 - 14 files changed, 66 insertions(+), 265 deletions(-) delete mode 100644 src/modules/ekf2/EKF/mag_heading_control.cpp diff --git a/msg/EstimatorAidSource1d.msg b/msg/EstimatorAidSource1d.msg index 78273d6b0671..1b416835d670 100644 --- a/msg/EstimatorAidSource1d.msg +++ b/msg/EstimatorAidSource1d.msg @@ -20,5 +20,5 @@ bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt # TOPICS estimator_aid_src_airspeed estimator_aid_src_sideslip # TOPICS estimator_aid_src_fake_hgt -# TOPICS estimator_aid_src_mag_heading estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw +# TOPICS estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw # TOPICS estimator_aid_src_terrain_range_finder diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 3f1f9a4c991d..8ddca66d92cd 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -189,7 +189,6 @@ if(CONFIG_EKF2_MAGNETOMETER) EKF/mag_3d_control.cpp EKF/mag_control.cpp EKF/mag_fusion.cpp - EKF/mag_heading_control.cpp ) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index adf922907a1f..4851bdfc755f 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -107,7 +107,6 @@ if(CONFIG_EKF2_MAGNETOMETER) mag_3d_control.cpp mag_control.cpp mag_fusion.cpp - mag_heading_control.cpp ) endif() diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index b6de89f544bb..7b75211edd7e 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -155,7 +155,6 @@ void Ekf::reset() #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_MAGNETOMETER) - resetEstimatorAidStatus(_aid_src_mag_heading); resetEstimatorAidStatus(_aid_src_mag); #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index b8b02a06345a..139214866aac 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -149,11 +149,7 @@ class Ekf final : public EstimatorInterface float getHeadingInnov() const { #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag_hdg) { - return _aid_src_mag_heading.innovation; - } - - if (_control_status.flags.mag_3D) { + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { return Vector3f(_aid_src_mag.innovation).max(); } #endif // CONFIG_EKF2_MAGNETOMETER @@ -176,11 +172,7 @@ class Ekf final : public EstimatorInterface float getHeadingInnovVar() const { #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag_hdg) { - return _aid_src_mag_heading.innovation_variance; - } - - if (_control_status.flags.mag_3D) { + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { return Vector3f(_aid_src_mag.innovation_variance).max(); } #endif // CONFIG_EKF2_MAGNETOMETER @@ -203,11 +195,7 @@ class Ekf final : public EstimatorInterface float getHeadingInnovRatio() const { #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag_hdg) { - return _aid_src_mag_heading.test_ratio; - } - - if (_control_status.flags.mag_3D) { + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { return Vector3f(_aid_src_mag.test_ratio).max(); } #endif // CONFIG_EKF2_MAGNETOMETER @@ -460,7 +448,6 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_MAGNETOMETER) - const auto &aid_src_mag_heading() const { return _aid_src_mag_heading; } const auto &aid_src_mag() const { return _aid_src_mag; } #endif // CONFIG_EKF2_MAGNETOMETER @@ -715,19 +702,13 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_MAGNETOMETER) - float _mag_heading_prev{}; ///< previous value of mag heading (rad) - float _mag_heading_pred_prev{}; ///< previous value of yaw state used by mag heading fusion (rad) - // used by magnetometer fusion mode selection bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable AlphaFilter _mag_heading_innov_lpf{0.1f}; - float _mag_heading_last_declination{}; ///< last magnetic field declination used for heading fusion (rad) bool _mag_decl_cov_reset{false}; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event. - uint8_t _nb_mag_heading_reset_available{0}; uint8_t _nb_mag_3d_reset_available{0}; uint32_t _min_mag_health_time_us{1'000'000}; ///< magnetometer is marked as healthy only after this amount of time - estimator_aid_source1d_s _aid_src_mag_heading{}; estimator_aid_source3d_s _aid_src_mag{}; AlphaFilter _mag_lpf{0.1f}; ///< filtered magnetometer measurement for instant reset (Gauss) @@ -777,7 +758,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // ekf sequential fusion of magnetometer measurements - bool fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = true); + bool fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = true, bool update_tilt = true); // fuse magnetometer declination measurement // argument passed in is the declination uncertainty in radians @@ -1048,7 +1029,6 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // control fusion of magnetometer observations void controlMagFusion(); - void controlMagHeadingFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source1d_s &aid_src); void controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source3d_s &aid_src); bool checkHaglYawResetReq() const; @@ -1058,12 +1038,11 @@ class Ekf final : public EstimatorInterface bool haglYawResetReq(); void checkYawAngleObservability(); - void checkMagHeadingConsistency(); + void checkMagHeadingConsistency(const magSample &mag_sample); bool checkMagField(const Vector3f &mag); static bool isMeasuredMatchingExpected(float measured, float expected, float gate); - void stopMagHdgFusion(); void stopMagFusion(); // calculate a synthetic value for the magnetometer Z component, given the 3D magnetomter diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 48aa6cf41563..afff6dc0ca48 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -381,11 +381,7 @@ void Ekf::get_innovation_test_status(uint16_t &status, float &mag, float &vel, f mag = 0.f; #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag_hdg) { - mag = math::max(mag, sqrtf(_aid_src_mag_heading.test_ratio)); - } - - if (_control_status.flags.mag_3D) { + if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) { mag = math::max(mag, sqrtf(Vector3f(_aid_src_mag.test_ratio).max())); } #endif // CONFIG_EKF2_MAGNETOMETER @@ -523,12 +519,7 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const bool mag_innov_good = true; #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag_hdg) { - if (_aid_src_mag_heading.test_ratio < 1.f) { - mag_innov_good = false; - } - - } else if (_control_status.flags.mag_3D) { + if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) { if (Vector3f(_aid_src_mag.test_ratio).max() < 1.f) { mag_innov_good = false; } diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/mag_3d_control.cpp index 89f502ac93f8..ff0902039d79 100644 --- a/src/modules/ekf2/EKF/mag_3d_control.cpp +++ b/src/modules/ekf2/EKF/mag_3d_control.cpp @@ -67,6 +67,18 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star && !_control_status.flags.ev_yaw && !_control_status.flags.gps_yaw; + const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; + + _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) + || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) + && _control_status.flags.tilt_align + && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && !_control_status.flags.mag_fault + && !_control_status.flags.mag_field_disturbed + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + // TODO: allow clearing mag_fault if mag_3d is good? if (_control_status.flags.mag_3D && !_control_status_prev.flags.mag_3D) { @@ -108,8 +120,9 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star // The normal sequence is to fuse the magnetometer data first before fusing // declination angle at a higher uncertainty to allow some learning of // declination angle over time. - const bool update_all_states = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, aid_src, update_all_states); + const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; + const bool update_tilt = _control_status.flags.mag_3D; + fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); if (_control_status.flags.mag_dec) { fuseDeclination(0.5f); @@ -199,6 +212,12 @@ void Ekf::stopMagFusion() _control_status.flags.mag_3D = false; } + if (_control_status.flags.mag_hdg) { + ECL_INFO("stopping mag heading fusion"); + _control_status.flags.mag_hdg = false; + _fault_status.flags.bad_hdg = false; + } + _fault_status.flags.bad_mag_x = false; _fault_status.flags.bad_mag_y = false; _fault_status.flags.bad_mag_z = false; diff --git a/src/modules/ekf2/EKF/mag_control.cpp b/src/modules/ekf2/EKF/mag_control.cpp index b491228c3999..5497d427f49f 100644 --- a/src/modules/ekf2/EKF/mag_control.cpp +++ b/src/modules/ekf2/EKF/mag_control.cpp @@ -48,11 +48,9 @@ void Ekf::controlMagFusion() } checkYawAngleObservability(); - checkMagHeadingConsistency(); if (_params.mag_fusion_type == MagFuseType::NONE) { stopMagFusion(); - stopMagHdgFusion(); return; } @@ -105,12 +103,11 @@ void Ekf::controlMagFusion() _control_status.flags.synthetic_mag_z = false; } + checkMagHeadingConsistency(mag_sample); controlMag3DFusion(mag_sample, starting_conditions_passing, _aid_src_mag); - controlMagHeadingFusion(mag_sample, starting_conditions_passing, _aid_src_mag_heading); } else if (!isNewestSampleRecent(_time_last_mag_buffer_push, 2 * MAG_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. - stopMagHdgFusion(); stopMagFusion(); } } @@ -239,8 +236,34 @@ void Ekf::checkYawAngleObservability() } } -void Ekf::checkMagHeadingConsistency() +void Ekf::checkMagHeadingConsistency(const magSample &mag_sample) { + // use mag bias if variance good + Vector3f mag_bias{0.f, 0.f, 0.f}; + const Vector3f mag_bias_var = getMagBiasVariance(); + + if ((mag_bias_var.min() > 0.f) && (mag_bias_var.max() <= sq(_params.mag_noise))) { + mag_bias = _state.mag_B; + } + + // calculate mag heading + // Rotate the measurements into earth frame using the zero yaw angle + const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth); + + // the angle of the projection onto the horizontal gives the yaw angle + // calculate the yaw innovation and wrap to the interval between +-pi + const Vector3f mag_earth_pred = R_to_earth * (mag_sample.mag - mag_bias); + const float declination = getMagDeclination(); + const float measured_hdg = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + declination; + + if (_control_status.flags.yaw_align) { + const float innovation = wrap_pi(getEulerYaw(_R_to_earth) - measured_hdg); + _mag_heading_innov_lpf.update(innovation); + + } else { + _mag_heading_innov_lpf.reset(0.f); + } + if (fabsf(_mag_heading_innov_lpf.getState()) < _params.mag_heading_noise) { if (_yaw_angle_observable) { // yaw angle must be observable to consider consistency @@ -349,7 +372,6 @@ void Ekf::resetMagHeading(const Vector3f &mag) // update quaternion states and corresponding covarainces resetQuatStateYaw(yaw_new, yaw_new_variance); - _mag_heading_last_declination = declination; _time_last_heading_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/mag_fusion.cpp b/src/modules/ekf2/EKF/mag_fusion.cpp index b1a8cc68fe29..1dbff8874c0f 100644 --- a/src/modules/ekf2/EKF/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/mag_fusion.cpp @@ -51,7 +51,7 @@ #include -bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states) +bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states, bool update_tilt) { // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); @@ -191,6 +191,11 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo Kfusion.slice(State::mag_B.idx, 0) = K_mag_B; } + if (!update_tilt) { + Kfusion(State::quat_nominal.idx) = 0.f; + Kfusion(State::quat_nominal.idx + 1) = 0.f; + } + if (measurementUpdate(Kfusion, H, aid_src_mag.observation_variance[index], aid_src_mag.innovation[index])) { fused[index] = true; limitDeclination(); diff --git a/src/modules/ekf2/EKF/mag_heading_control.cpp b/src/modules/ekf2/EKF/mag_heading_control.cpp deleted file mode 100644 index 612474937e10..000000000000 --- a/src/modules/ekf2/EKF/mag_heading_control.cpp +++ /dev/null @@ -1,204 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mag_heading_control.cpp - * Control functions for ekf mag heading fusion - */ - -#include "ekf.h" - -void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, - estimator_aid_source1d_s &aid_src) -{ - static constexpr const char *AID_SRC_NAME = "mag heading"; - - // use mag bias if variance good - Vector3f mag_bias{0.f, 0.f, 0.f}; - const Vector3f mag_bias_var = getMagBiasVariance(); - - if ((mag_bias_var.min() > 0.f) && (mag_bias_var.max() <= sq(_params.mag_noise))) { - mag_bias = _state.mag_B; - } - - // calculate mag heading - // Rotate the measurements into earth frame using the zero yaw angle - const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth); - - // the angle of the projection onto the horizontal gives the yaw angle - // calculate the yaw innovation and wrap to the interval between +-pi - const Vector3f mag_earth_pred = R_to_earth * (mag_sample.mag - mag_bias); - const float declination = getMagDeclination(); - const float measured_hdg = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + declination; - - resetEstimatorAidStatus(aid_src); - aid_src.observation = measured_hdg; - aid_src.observation_variance = math::max(sq(_params.mag_heading_noise), sq(0.01f)); - - if (_control_status.flags.yaw_align) { - // mag heading - aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation); - _mag_heading_innov_lpf.update(aid_src.innovation); - - } else { - // mag heading delta (logging only) - aid_src.innovation = wrap_pi(wrap_pi(getEulerYaw(_R_to_earth) - _mag_heading_pred_prev) - - wrap_pi(measured_hdg - _mag_heading_prev)); - _mag_heading_innov_lpf.reset(0.f); - } - - // determine if we should use mag heading aiding - const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; - - bool continuing_conditions_passing = ((_params.mag_fusion_type == MagFuseType::HEADING) - || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) - && _control_status.flags.tilt_align - && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) - || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && !_control_status.flags.mag_fault - && !_control_status.flags.mag_field_disturbed - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw - && PX4_ISFINITE(aid_src.observation) - && PX4_ISFINITE(aid_src.observation_variance); - - const bool starting_conditions_passing = common_starting_conditions_passing - && continuing_conditions_passing - && isTimedOut(aid_src.time_last_fuse, 3e6); - - if (_control_status.flags.mag_hdg) { - aid_src.timestamp_sample = mag_sample.time_us; - - if (continuing_conditions_passing && _control_status.flags.yaw_align) { - - const bool declination_changed = _control_status_prev.flags.mag_hdg - && (fabsf(declination - _mag_heading_last_declination) > math::radians(3.f)); - bool skip_timeout_check = false; - - if (mag_sample.reset || declination_changed) { - if (declination_changed) { - ECL_INFO("reset to %s, declination changed %.5f->%.5f", - AID_SRC_NAME, (double)_mag_heading_last_declination, (double)declination); - - } else { - ECL_INFO("reset to %s", AID_SRC_NAME); - } - - resetMagHeading(_mag_lpf.getState()); - aid_src.time_last_fuse = _time_delayed_us; - - } else { - VectorState H_YAW; - computeYawInnovVarAndH(aid_src.observation_variance, aid_src.innovation_variance, H_YAW); - - if ((aid_src.innovation_variance - aid_src.observation_variance) > sq(_params.mag_heading_noise / 2.f)) { - // Only fuse mag to constrain the yaw variance to a safe value - fuseYaw(aid_src, H_YAW); - - } else { - // Yaw variance is low enough, stay in mag heading mode but don't fuse the data and skip the fusion timeout check - skip_timeout_check = true; - aid_src.test_ratio = 0.f; // required for preflight checks to pass - } - } - - const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max) && !skip_timeout_check; - - if (is_fusion_failing) { - if (_nb_mag_heading_reset_available > 0) { - // Data seems good, attempt a reset - ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); - resetMagHeading(_mag_lpf.getState()); - aid_src.time_last_fuse = _time_delayed_us; - - if (_control_status.flags.in_air) { - _nb_mag_heading_reset_available--; - } - - } else if (starting_conditions_passing) { - // Data seems good, but previous reset did not fix the issue - // something else must be wrong, declare the sensor faulty and stop the fusion - _control_status.flags.mag_fault = true; - ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); - stopMagHdgFusion(); - - } else { - // A reset did not fix the issue but all the starting checks are not passing - // This could be a temporary issue, stop the fusion without declaring the sensor faulty - ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); - stopMagHdgFusion(); - } - } - - } else { - // Stop fusion but do not declare it faulty - ECL_WARN("stopping %s fusion, continuing conditions failing", AID_SRC_NAME); - stopMagHdgFusion(); - } - - } else { - if (starting_conditions_passing) { - // activate fusion - ECL_INFO("starting %s fusion", AID_SRC_NAME); - - if (!_control_status.flags.yaw_align) { - // reset heading - resetMagHeading(_mag_lpf.getState()); - _control_status.flags.yaw_align = true; - } - - _control_status.flags.mag_hdg = true; - aid_src.time_last_fuse = _time_delayed_us; - - _nb_mag_heading_reset_available = 1; - } - } - - // record corresponding mag heading and yaw state for future mag heading delta heading innovation (logging only) - _mag_heading_prev = measured_hdg; - _mag_heading_pred_prev = getEulerYaw(_state.quat_nominal); - - _mag_heading_last_declination = getMagDeclination(); -} - -void Ekf::stopMagHdgFusion() -{ - if (_control_status.flags.mag_hdg) { - ECL_INFO("stopping mag heading fusion"); - resetEstimatorAidStatus(_aid_src_mag_heading); - - _control_status.flags.mag_hdg = false; - - _fault_status.flags.bad_hdg = false; - } -} diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 81530df7046f..9aec7b213c6a 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -335,7 +335,6 @@ bool EKF2::multi_init(int imu, int mag) // mag advertise if (_param_ekf2_mag_type.get() != MagFuseType::NONE) { - _estimator_aid_src_mag_heading_pub.advertise(); _estimator_aid_src_mag_pub.advertise(); } @@ -874,9 +873,6 @@ void EKF2::PublishAidSourceStatus(const hrt_abstime ×tamp) #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_MAGNETOMETER) - // mag heading - PublishAidSourceStatus(_ekf.aid_src_mag_heading(), _status_mag_heading_pub_last, _estimator_aid_src_mag_heading_pub); - // mag 3d PublishAidSourceStatus(_ekf.aid_src_mag(), _status_mag_pub_last, _estimator_aid_src_mag_pub); #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 1d54315b8cc8..ff425e891d03 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -307,11 +307,9 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem Vector3f _last_mag_bias_published{}; hrt_abstime _status_mag_pub_last{0}; - hrt_abstime _status_mag_heading_pub_last{0}; uORB::Subscription _magnetometer_sub{ORB_ID(vehicle_magnetometer)}; - uORB::PublicationMulti _estimator_aid_src_mag_heading_pub{ORB_ID(estimator_aid_src_mag_heading)}; uORB::PublicationMulti _estimator_aid_src_mag_pub{ORB_ID(estimator_aid_src_mag)}; #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/test/test_EKF_flow.cpp b/src/modules/ekf2/test/test_EKF_flow.cpp index 68e25fdf59bd..f39249190ada 100644 --- a/src/modules/ekf2/test/test_EKF_flow.cpp +++ b/src/modules/ekf2/test/test_EKF_flow.cpp @@ -259,7 +259,6 @@ TEST_F(EkfFlowTest, yawMotionCorrectionWithAutopilotGyroData) // THEN: the flow due to the yaw rotation and the offsets is canceled // and the velocity estimate stays 0 // FIXME: the estimate isn't perfect 0 mainly because the mag simulated measurement isn't rotating - // and this creates an incorrect Z gyro bias which is used to compensate for the apparent flow const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.02f) << "estimated vel = " << estimated_horz_velocity(0); @@ -298,10 +297,11 @@ TEST_F(EkfFlowTest, yawMotionCorrectionWithFlowGyroData) // THEN: the flow due to the yaw rotation and the offsets is canceled // and the velocity estimate stays 0 + // FIXME: the estimate isn't perfect 0 mainly because the mag simulated measurement isn't rotating const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); - EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.01f) + EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.02f) << "estimated vel = " << estimated_horz_velocity(0); - EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f) + EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.02f) << "estimated vel = " << estimated_horz_velocity(1); _ekf->state().vector().print(); _ekf->covariances().print(); diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 3465d857bc05..1b0326234bcd 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -204,7 +204,6 @@ void LoggedTopics::add_default_topics() // add_optional_topic_multi("estimator_aid_src_gnss_yaw", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_gnss_vel", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_gnss_pos", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_mag_heading", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_mag", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_optical_flow", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_terrain_optical_flow", 100, MAX_ESTIMATOR_INSTANCES); @@ -297,7 +296,6 @@ void LoggedTopics::add_default_topics() add_optional_topic_multi("estimator_aid_src_gnss_vel", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_gnss_yaw", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_gravity", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_mag_heading", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_mag", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_optical_flow", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_terrain_optical_flow", 0, MAX_ESTIMATOR_INSTANCES); From 2f51db7284dea66fbb92d5d58848eb8ddac1e1ea Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 26 Mar 2024 14:43:20 +0100 Subject: [PATCH 082/652] ekf2: limit mag heading fusion to prevent heading overconfidence --- src/modules/ekf2/EKF/mag_3d_control.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/mag_3d_control.cpp index ff0902039d79..8d182da7d9ae 100644 --- a/src/modules/ekf2/EKF/mag_3d_control.cpp +++ b/src/modules/ekf2/EKF/mag_3d_control.cpp @@ -120,7 +120,7 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star // The normal sequence is to fuse the magnetometer data first before fusing // declination angle at a higher uncertainty to allow some learning of // declination angle over time. - const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; + const bool update_all_states = _control_status.flags.mag_3D || (_control_status.flags.mag_hdg && (getYawVar() > sq(_params.mag_heading_noise / 2.f))); const bool update_tilt = _control_status.flags.mag_3D; fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); From dae246d7e2bd9664914a84bef9f29f3e51c7c2b6 Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 28 Mar 2024 18:18:52 +0100 Subject: [PATCH 083/652] ekf2: do not continuously use mag decl fusion when GNSS fusion is active This prevents over-constraining the heading from mag fusion. An incorrect mag yaw rotation can be absorbed as a declination error. --- src/modules/ekf2/EKF/mag_3d_control.cpp | 9 ++++----- src/modules/ekf2/ekf2_params.c | 2 +- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/mag_3d_control.cpp index 8d182da7d9ae..79ed2b6c9db1 100644 --- a/src/modules/ekf2/EKF/mag_3d_control.cpp +++ b/src/modules/ekf2/EKF/mag_3d_control.cpp @@ -90,11 +90,10 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star // if we are using 3-axis magnetometer fusion, but without external NE aiding, // then the declination must be fused as an observation to prevent long term heading drift - // fusing declination when gps aiding is available is optional, but recommended to prevent - // problem if the vehicle is static for extended periods of time + // fusing declination when gps aiding is available is optional. const bool mag_decl_user_selected = (_params.mag_declination_source & GeoDeclinationMask::FUSE_DECL); - const bool not_using_ne_aiding = !_control_status.flags.gps; - _control_status.flags.mag_dec = (_control_status.flags.mag && (not_using_ne_aiding || mag_decl_user_selected)); + const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; + _control_status.flags.mag_dec = (_control_status.flags.mag && ((not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight) || mag_decl_user_selected)); if (_control_status.flags.mag) { aid_src.timestamp_sample = mag_sample.time_us; @@ -120,7 +119,7 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star // The normal sequence is to fuse the magnetometer data first before fusing // declination angle at a higher uncertainty to allow some learning of // declination angle over time. - const bool update_all_states = _control_status.flags.mag_3D || (_control_status.flags.mag_hdg && (getYawVar() > sq(_params.mag_heading_noise / 2.f))); + const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; const bool update_tilt = _control_status.flags.mag_3D; fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index 396ba9651559..ebeae0e8e1a3 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -484,7 +484,7 @@ PARAM_DEFINE_FLOAT(EKF2_MAG_GATE, 3.0f); * @bit 2 use declination as an observation * @reboot_required true */ -PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7); +PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 3); /** * Type of magnetometer fusion From b79d3854e41a61e4e8de17b6c9c3e3417d394b3a Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 2 Apr 2024 11:01:16 +0200 Subject: [PATCH 084/652] ekf2: remove option to continuously fuse mag declination Declination fusion is only used when not observable (no global aiding). --- src/modules/ekf2/EKF/common.h | 5 ++--- src/modules/ekf2/EKF/mag_3d_control.cpp | 3 +-- src/modules/ekf2/ekf2_params.c | 4 +--- 3 files changed, 4 insertions(+), 8 deletions(-) diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 880df1d4fec7..aaabe89eaa6e 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -95,8 +95,7 @@ enum class VelocityFrame : uint8_t { enum GeoDeclinationMask : uint8_t { // Bit locations for mag_declination_source USE_GEO_DECL = (1<<0), ///< set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value - SAVE_GEO_DECL = (1<<1), ///< set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library - FUSE_DECL = (1<<2) ///< set to true if the declination is always fused as an observation to constrain drift when 3-axis fusion is performed + SAVE_GEO_DECL = (1<<1) ///< set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library }; enum MagFuseType : uint8_t { @@ -361,7 +360,7 @@ struct parameters { float mag_noise{5.0e-2f}; ///< measurement noise used for 3-axis magnetometer fusion (Gauss) float mag_declination_deg{0.0f}; ///< magnetic declination (degrees) float mag_innov_gate{3.0f}; ///< magnetometer fusion innovation consistency gate size (STD) - int32_t mag_declination_source{7}; ///< bitmask used to control the handling of declination data + int32_t mag_declination_source{3}; ///< bitmask used to control the handling of declination data int32_t mag_fusion_type{0}; ///< integer used to specify the type of magnetometer fusion used float mag_acc_gate{0.5f}; ///< when in auto select mode, heading fusion will be used when manoeuvre accel is lower than this (m/sec**2) diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/mag_3d_control.cpp index 79ed2b6c9db1..41192f2cbf64 100644 --- a/src/modules/ekf2/EKF/mag_3d_control.cpp +++ b/src/modules/ekf2/EKF/mag_3d_control.cpp @@ -91,9 +91,8 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star // if we are using 3-axis magnetometer fusion, but without external NE aiding, // then the declination must be fused as an observation to prevent long term heading drift // fusing declination when gps aiding is available is optional. - const bool mag_decl_user_selected = (_params.mag_declination_source & GeoDeclinationMask::FUSE_DECL); const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; - _control_status.flags.mag_dec = (_control_status.flags.mag && ((not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight) || mag_decl_user_selected)); + _control_status.flags.mag_dec = (_control_status.flags.mag && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight)); if (_control_status.flags.mag) { aid_src.timestamp_sample = mag_sample.time_us; diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index ebeae0e8e1a3..b43f30440dfb 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -474,14 +474,12 @@ PARAM_DEFINE_FLOAT(EKF2_MAG_GATE, 3.0f); * Set bits in the following positions to enable functions. * 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. * 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. - * 2 : Set to true to always use the declination as an observation when 3-axis magnetometer fusion is being used. * * @group EKF2 * @min 0 - * @max 7 + * @max 3 * @bit 0 use geo_lookup declination * @bit 1 save EKF2_MAG_DECL on disarm - * @bit 2 use declination as an observation * @reboot_required true */ PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 3); From 5f61e3b7856902efbbf3682c7632f5998b1c9ade Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 25 Mar 2024 14:50:59 +0100 Subject: [PATCH 085/652] ekf2: update change indicator --- .../test/change_indication/ekf_gsf_reset.csv | 780 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 700 ++++++++-------- 2 files changed, 740 insertions(+), 740 deletions(-) diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv index 17437ae7216c..7faff984e16f 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -1,391 +1,391 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00055,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00048,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00038,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00034,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2190000,1,-0.011,-0.014,5.8e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2590000,1,-0.011,-0.013,5.8e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2790000,1,-0.011,-0.013,4.8e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2890000,1,-0.011,-0.013,-1.8e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3090000,1,-0.011,-0.013,4.8e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3190000,1,-0.011,-0.013,-8.9e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00021,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3290000,1,-0.011,-0.013,3.1e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3390000,1,-0.011,-0.012,2.5e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3490000,1,-0.011,-0.013,-5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3590000,1,-0.011,-0.012,1.8e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4290000,1,-0.01,-0.012,8.2e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00016,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00017,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4690000,1,-0.01,-0.012,0.0002,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4790000,1,-0.01,-0.012,0.00019,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5690000,1,-0.0096,-0.011,0.00034,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6090000,1,-0.0094,-0.011,0.00032,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6290000,1,-0.0094,-0.011,0.00022,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6390000,1,-0.0093,-0.011,0.00024,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6590000,1,-0.0094,-0.011,0.00017,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6690000,1,-0.0093,-0.011,9.6e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6790000,0.78,-0.024,0.0049,-0.63,-0.0056,0.0015,-0.11,0.0015,0.00055,-3.7e+02,-0.0014,-0.0057,-8.2e-05,0,0,-5.8e-05,-0.092,-0.02,0.51,-0.00081,-0.075,-0.061,0,0,0.0013,0.0013,0.072,0.18,0.18,0.6,0.11,0.11,0.2,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 -6890000,0.78,-0.025,0.0057,-0.63,-0.03,-0.0077,-0.12,-9e-05,-0.0018,-3.7e+02,-0.0013,-0.0057,-8.3e-05,0,0,-0.00011,-0.1,-0.022,0.51,-0.0011,-0.083,-0.067,0,0,0.0013,0.0013,0.057,0.18,0.18,0.46,0.14,0.14,0.18,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00094,0.0014,0.0013,1,1 -6990000,0.78,-0.025,0.0058,-0.63,-0.059,-0.018,-0.12,-0.0053,-0.0061,-3.7e+02,-0.0012,-0.0057,-8.7e-05,-2.7e-05,-6.9e-05,-0.00041,-0.1,-0.022,0.5,-0.0015,-0.084,-0.067,0,0,0.0013,0.0013,0.053,0.19,0.18,0.36,0.17,0.17,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.0009,0.0014,0.0013,1,1 -7090000,0.78,-0.025,0.0059,-0.63,-0.087,-0.028,-0.12,-0.014,-0.012,-3.7e+02,-0.0011,-0.0057,-9.1e-05,-8.3e-05,-0.00024,-0.00077,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.052,0.19,0.19,0.29,0.2,0.2,0.16,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00089,0.0013,0.0013,1,1 -7190000,0.78,-0.025,0.006,-0.63,-0.11,-0.037,-0.15,-0.024,-0.018,-3.7e+02,-0.001,-0.0057,-9.3e-05,-7.7e-05,-0.00036,-0.00056,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.051,0.21,0.21,0.24,0.23,0.23,0.15,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00088,0.0013,0.0013,1,1 -7290000,0.78,-0.025,0.0059,-0.63,-0.14,-0.04,-0.14,-0.035,-0.019,-3.7e+02,-0.0011,-0.0057,-9e-05,-4.6e-05,-0.00024,-0.0012,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.22,0.22,0.2,0.28,0.28,0.14,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00087,0.0013,0.0013,1,1 -7390000,0.78,-0.025,0.0059,-0.63,-0.16,-0.048,-0.16,-0.049,-0.025,-3.7e+02,-0.0011,-0.0057,-9e-05,8.1e-07,-0.00028,-0.0014,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.18,0.32,0.32,0.13,7.8e-05,7.9e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00087,0.0013,0.0013,1,1 -7490000,0.78,-0.025,0.0059,-0.63,-0.19,-0.061,-0.16,-0.066,-0.038,-3.7e+02,-0.00093,-0.0057,-9.3e-05,1.6e-05,-0.0005,-0.0022,-0.1,-0.023,0.5,-0.0017,-0.085,-0.069,0,0,0.0013,0.0013,0.049,0.27,0.26,0.15,0.37,0.37,0.12,7.8e-05,7.8e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 -7590000,0.78,-0.025,0.0059,-0.63,-0.21,-0.067,-0.16,-0.082,-0.044,-3.7e+02,-0.00093,-0.0056,-9e-05,0.00011,-0.00047,-0.003,-0.1,-0.023,0.5,-0.0016,-0.085,-0.068,0,0,0.0013,0.0013,0.049,0.29,0.29,0.14,0.43,0.43,0.12,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 -7690000,0.78,-0.025,0.0059,-0.63,-0.24,-0.079,-0.16,-0.1,-0.058,-3.7e+02,-0.00082,-0.0056,-9.3e-05,8.3e-05,-0.00057,-0.005,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.32,0.32,0.13,0.49,0.49,0.11,7.6e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 -7790000,0.78,-0.025,0.006,-0.63,-0.27,-0.088,-0.16,-0.14,-0.072,-3.7e+02,-0.00074,-0.0057,-9.9e-05,-0.00013,-0.00063,-0.007,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.35,0.35,0.12,0.56,0.55,0.11,7.5e-05,7.5e-05,4.9e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00086,0.0013,0.0013,1,1 -7890000,0.78,-0.025,0.006,-0.63,-0.29,-0.099,-0.15,-0.16,-0.086,-3.7e+02,-0.00067,-0.0056,-9.8e-05,-8.1e-05,-0.00064,-0.0095,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.39,0.38,0.11,0.63,0.63,0.1,7.4e-05,7.4e-05,4.9e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00086,0.0013,0.0013,1,1 -7990000,0.78,-0.025,0.006,-0.63,-0.32,-0.11,-0.16,-0.19,-0.098,-3.7e+02,-0.00064,-0.0056,-9.7e-05,2.6e-06,-0.00064,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.43,0.42,0.1,0.71,0.71,0.099,7.2e-05,7.3e-05,4.9e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00086,0.0013,0.0013,1,1 -8090000,0.78,-0.025,0.006,-0.63,-0.34,-0.12,-0.17,-0.21,-0.11,-3.7e+02,-0.00058,-0.0054,-9.5e-05,0.00017,-0.00074,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.47,0.46,0.1,0.8,0.8,0.097,7e-05,7.1e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 -8190000,0.78,-0.025,0.0061,-0.63,-0.37,-0.13,-0.17,-0.25,-0.13,-3.7e+02,-0.00056,-0.0055,-9.8e-05,-2.7e-05,-0.00068,-0.013,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.52,0.51,0.099,0.9,0.89,0.094,6.8e-05,6.9e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8290000,0.78,-0.025,0.0061,-0.63,-0.019,-0.0046,-0.17,-0.27,-0.13,-3.7e+02,-0.00042,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.017,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.6e-05,6.7e-05,4.9e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8390000,0.78,-0.025,0.0061,-0.63,-0.046,-0.012,-0.17,-0.27,-0.13,-3.7e+02,-0.00038,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.021,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,6.5e-05,4.9e-06,0.04,0.04,0.035,0.0013,8.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8490000,0.78,-0.026,0.0062,-0.63,-0.073,-0.02,-0.17,-0.27,-0.13,-3.7e+02,-0.00033,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.025,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,6.2e-05,6.3e-05,4.9e-06,0.04,0.04,0.034,0.0013,8.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8590000,0.78,-0.025,0.0062,-0.63,-0.099,-0.028,-0.16,-0.28,-0.14,-3.7e+02,-0.00051,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.029,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.9e-05,6.1e-05,4.9e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8690000,0.78,-0.025,0.0061,-0.63,-0.12,-0.036,-0.16,-0.28,-0.14,-3.7e+02,-0.00047,-0.0055,-9.9e-05,-6.1e-05,-0.00064,-0.034,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,35,35,0.088,5.7e-05,5.9e-05,4.9e-06,0.04,0.04,0.033,0.0013,7.9e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8790000,0.78,-0.026,0.0062,-0.63,-0.15,-0.044,-0.15,-0.3,-0.14,-3.7e+02,-0.0004,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.04,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,5.5e-05,5.6e-05,4.9e-06,0.04,0.04,0.032,0.0013,7.8e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8890000,0.78,-0.026,0.0063,-0.63,-0.18,-0.05,-0.15,-0.3,-0.14,-3.7e+02,-0.00037,-0.0056,-0.00011,-6.1e-05,-0.00064,-0.044,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.095,28,28,0.086,5.2e-05,5.4e-05,4.9e-06,0.04,0.04,0.03,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 -8990000,0.78,-0.026,0.0064,-0.63,-0.21,-0.056,-0.14,-0.32,-0.15,-3.7e+02,-0.00029,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.05,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.096,30,30,0.087,5e-05,5.1e-05,4.9e-06,0.04,0.04,0.029,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9090000,0.78,-0.026,0.0065,-0.63,-0.23,-0.06,-0.14,-0.33,-0.15,-3.7e+02,-0.00033,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.052,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.7e-05,4.9e-05,4.9e-06,0.04,0.04,0.028,0.0013,7.6e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9190000,0.78,-0.026,0.0063,-0.63,-0.25,-0.071,-0.14,-0.35,-0.16,-3.7e+02,-0.00029,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.056,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,4.5e-05,4.6e-05,4.9e-06,0.04,0.04,0.027,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9290000,0.78,-0.026,0.0063,-0.63,-0.27,-0.077,-0.13,-0.35,-0.16,-3.7e+02,-0.00023,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.06,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,4.2e-05,4.4e-05,4.9e-06,0.04,0.04,0.025,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9390000,0.78,-0.026,0.0065,-0.63,-0.3,-0.086,-0.13,-0.38,-0.17,-3.7e+02,-0.00018,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.063,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,21,21,0.093,25,25,0.086,4e-05,4.2e-05,4.9e-06,0.04,0.04,0.024,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9490000,0.78,-0.026,0.0064,-0.63,-0.31,-0.092,-0.13,-0.38,-0.17,-3.7e+02,-0.00011,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.067,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.091,22,22,0.085,3.8e-05,4e-05,4.9e-06,0.04,0.04,0.023,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9590000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.18,-3.7e+02,-0.00024,-0.0053,-0.0001,-6.1e-05,-0.00064,-0.07,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.09,25,25,0.085,3.6e-05,3.7e-05,4.9e-06,0.04,0.04,0.022,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9690000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.17,-3.7e+02,-0.0003,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.075,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.089,22,22,0.086,3.4e-05,3.6e-05,4.9e-06,0.04,0.04,0.02,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9790000,0.78,-0.026,0.0063,-0.63,-0.38,-0.11,-0.1,-0.45,-0.19,-3.7e+02,-0.00026,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.08,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.087,24,24,0.085,3.2e-05,3.4e-05,4.9e-06,0.04,0.04,0.019,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9890000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.1,-0.48,-0.2,-3.7e+02,-0.00033,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.083,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.084,28,28,0.085,3e-05,3.2e-05,4.9e-06,0.04,0.04,0.018,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 -9990000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.096,-0.47,-0.19,-3.7e+02,-0.00035,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.086,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.083,24,24,0.086,2.8e-05,3e-05,4.9e-06,0.04,0.04,0.017,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10090000,0.78,-0.026,0.0062,-0.63,-0.43,-0.12,-0.092,-0.51,-0.2,-3.7e+02,-0.00043,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.089,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.081,27,27,0.085,2.7e-05,2.8e-05,4.9e-06,0.04,0.04,0.016,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10190000,0.78,-0.026,0.0065,-0.63,-0.43,-0.12,-0.092,-0.5,-0.2,-3.7e+02,-0.00044,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.09,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,13,0.078,24,24,0.084,2.5e-05,2.7e-05,4.9e-06,0.04,0.04,0.015,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10290000,0.78,-0.026,0.0067,-0.63,-0.46,-0.12,-0.08,-0.55,-0.21,-3.7e+02,-0.00045,-0.0058,-0.00011,-6.1e-05,-0.00064,-0.096,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,14,0.076,27,27,0.085,2.4e-05,2.5e-05,4.9e-06,0.04,0.04,0.014,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10390000,0.78,-0.026,0.0068,-0.63,-0.017,-0.027,0.0097,-0.00031,-0.0021,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00013,-0.00061,-0.099,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,4.9e-06,0.04,0.04,0.013,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10490000,0.78,-0.026,0.0069,-0.63,-0.047,-0.034,0.023,-0.0035,-0.0051,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00035,-0.00043,-0.1,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.26,0.26,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,4.9e-06,0.04,0.04,0.012,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10590000,0.78,-0.026,0.0066,-0.63,-0.045,-0.023,0.026,0.0012,-0.0011,-3.7e+02,-0.00059,-0.0058,-0.00011,-3.5e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.1e-05,4.9e-06,0.04,0.04,0.012,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10690000,0.78,-0.026,0.0066,-0.63,-0.073,-0.029,0.03,-0.0048,-0.0037,-3.7e+02,-0.00059,-0.0059,-0.00011,-9.8e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.9e-05,2e-05,4.9e-06,0.04,0.04,0.011,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 -10790000,0.78,-0.025,0.0064,-0.63,-0.069,-0.024,0.024,-0.0001,-0.0015,-3.7e+02,-0.00063,-0.0058,-0.00011,0.00028,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.8e-05,1.9e-05,4.8e-06,0.04,0.039,0.011,0.0013,7e-05,0.0013,0.00084,0.0013,0.0013,1,1 -10890000,0.78,-0.025,0.0064,-0.63,-0.097,-0.03,0.02,-0.0084,-0.0042,-3.7e+02,-0.00063,-0.0058,-0.00011,0.0003,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00084,0.0013,0.0013,1,1 -10990000,0.78,-0.025,0.0059,-0.63,-0.085,-0.024,0.014,-0.0037,-0.0024,-3.7e+02,-0.00066,-0.0058,-0.0001,0.0011,-0.009,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.6e-05,1.7e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 -11090000,0.78,-0.025,0.0057,-0.63,-0.11,-0.032,0.019,-0.013,-0.0054,-3.7e+02,-0.00069,-0.0057,-9.6e-05,0.0013,-0.0089,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.1,0.1,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 -11190000,0.78,-0.024,0.0051,-0.63,-0.095,-0.025,0.0078,-0.0051,-0.0021,-3.7e+02,-0.00079,-0.0057,-9.3e-05,0.0019,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.084,0.084,0.084,0.11,0.11,0.069,1.4e-05,1.5e-05,4.8e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 -11290000,0.78,-0.024,0.0052,-0.63,-0.12,-0.029,0.0076,-0.016,-0.0046,-3.7e+02,-0.00074,-0.0058,-9.7e-05,0.0016,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.099,0.099,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,4.8e-06,0.038,0.038,0.01,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 -11390000,0.78,-0.022,0.0045,-0.63,-0.1,-0.024,0.002,-0.0027,-0.00099,-3.7e+02,-0.00084,-0.0059,-9.5e-05,0.0015,-0.022,-0.11,-0.11,-0.023,0.5,-0.0013,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.08,0.08,0.063,0.082,0.082,0.068,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 -11490000,0.78,-0.022,0.0047,-0.63,-0.12,-0.026,0.0029,-0.014,-0.0031,-3.7e+02,-0.0008,-0.006,-0.0001,0.0009,-0.022,-0.11,-0.11,-0.023,0.5,-0.0014,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.095,0.095,0.058,0.089,0.089,0.069,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 -11590000,0.78,-0.022,0.0041,-0.63,-0.1,-0.022,-0.003,-0.0044,-0.00098,-3.7e+02,-0.00085,-0.006,-9.8e-05,0.00079,-0.029,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.078,0.078,0.049,0.068,0.068,0.066,1.1e-05,1.2e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 -11690000,0.78,-0.022,0.0042,-0.63,-0.12,-0.026,-0.0074,-0.016,-0.0033,-3.7e+02,-0.00079,-0.006,-0.0001,0.00062,-0.03,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.093,0.093,0.046,0.075,0.075,0.066,1.1e-05,1.1e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 -11790000,0.78,-0.021,0.0037,-0.63,-0.1,-0.017,-0.0092,-0.0082,0.00018,-3.7e+02,-0.00082,-0.006,-9.7e-05,0.0012,-0.036,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.077,0.076,0.039,0.06,0.06,0.063,1e-05,1.1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 -11890000,0.78,-0.021,0.0038,-0.63,-0.12,-0.019,-0.01,-0.019,-0.0015,-3.7e+02,-0.0008,-0.0061,-9.9e-05,0.00091,-0.036,-0.11,-0.11,-0.023,0.5,-0.0015,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.09,0.09,0.037,0.067,0.067,0.063,9.5e-06,1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 -11990000,0.78,-0.02,0.003,-0.63,-0.095,-0.012,-0.015,-0.011,0.0012,-3.7e+02,-0.00095,-0.0061,-9.3e-05,0.0013,-0.04,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.074,0.074,0.033,0.055,0.055,0.061,9e-06,9.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 -12090000,0.78,-0.02,0.0029,-0.63,-0.11,-0.016,-0.021,-0.021,-0.00045,-3.7e+02,-0.00099,-0.006,-9e-05,0.0018,-0.04,-0.11,-0.11,-0.023,0.5,-0.0013,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.087,0.086,0.031,0.063,0.063,0.061,8.6e-06,9.2e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 -12190000,0.78,-0.019,0.0023,-0.63,-0.084,-0.015,-0.016,-0.01,0.00028,-3.7e+02,-0.00098,-0.006,-8.9e-05,0.0016,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.071,0.071,0.028,0.052,0.052,0.059,8.1e-06,8.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 -12290000,0.78,-0.019,0.0024,-0.63,-0.092,-0.017,-0.015,-0.019,-0.0014,-3.7e+02,-0.00094,-0.006,-8.9e-05,0.0017,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.082,0.082,0.028,0.06,0.06,0.059,7.8e-06,8.4e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 -12390000,0.78,-0.019,0.0019,-0.63,-0.073,-0.014,-0.013,-0.0094,-0.00012,-3.7e+02,-0.00099,-0.006,-8.8e-05,0.0011,-0.05,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.067,0.067,0.026,0.05,0.05,0.057,7.4e-06,8e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 -12490000,0.78,-0.019,0.0021,-0.63,-0.08,-0.016,-0.016,-0.017,-0.0014,-3.7e+02,-0.00096,-0.0061,-9.1e-05,0.00059,-0.05,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.077,0.076,0.026,0.058,0.058,0.057,7.1e-06,7.6e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 -12590000,0.78,-0.018,0.0018,-0.63,-0.073,-0.014,-0.022,-0.014,-0.00033,-3.7e+02,-0.001,-0.0061,-8.8e-05,0.00072,-0.052,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.063,0.063,0.025,0.049,0.049,0.055,6.8e-06,7.3e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.5e-05,0.0012,0.00072,0.0013,0.0012,1,1 -12690000,0.78,-0.018,0.0018,-0.63,-0.079,-0.015,-0.025,-0.021,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.8e-05,0.00038,-0.051,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.071,0.071,0.025,0.057,0.057,0.055,6.5e-06,7e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1 -12790000,0.78,-0.018,0.0016,-0.63,-0.072,-0.012,-0.028,-0.018,-0.0006,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00058,-0.053,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00054,0.00056,0.046,0.059,0.058,0.024,0.048,0.048,0.053,6.2e-06,6.7e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 -12890000,0.78,-0.018,0.0017,-0.63,-0.079,-0.013,-0.027,-0.026,-0.0019,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00062,-0.054,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00055,0.00056,0.046,0.066,0.066,0.025,0.056,0.056,0.054,6e-06,6.5e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 -12990000,0.78,-0.018,0.0013,-0.63,-0.064,-0.012,-0.028,-0.019,-0.0015,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.0009,-0.056,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.059,0.058,0.025,0.058,0.058,0.052,5.7e-06,6.2e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 -13090000,0.78,-0.018,0.0014,-0.63,-0.069,-0.011,-0.028,-0.026,-0.0023,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00025,-0.057,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.065,0.065,0.025,0.066,0.066,0.052,5.5e-06,6e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 -13190000,0.78,-0.018,0.0011,-0.63,-0.055,-0.011,-0.025,-0.017,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.7e-05,-1.3e-05,-0.058,-0.11,-0.11,-0.024,0.5,-0.0016,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.058,0.058,0.025,0.067,0.067,0.051,5.2e-06,5.7e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 -13290000,0.78,-0.018,0.0011,-0.63,-0.06,-0.013,-0.021,-0.024,-0.003,-3.7e+02,-0.001,-0.006,-8.8e-05,0.00039,-0.059,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.064,0.064,0.027,0.077,0.077,0.051,5.1e-06,5.5e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1 -13390000,0.78,-0.017,0.00099,-0.63,-0.049,-0.012,-0.017,-0.016,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00065,-0.06,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.9e-06,5.3e-06,4.8e-06,0.032,0.032,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13490000,0.78,-0.017,0.00096,-0.63,-0.053,-0.013,-0.016,-0.022,-0.0034,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00089,-0.061,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.062,0.062,0.028,0.088,0.088,0.05,4.7e-06,5.1e-06,4.8e-06,0.031,0.032,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13590000,0.78,-0.017,0.00083,-0.63,-0.043,-0.012,-0.018,-0.014,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00051,-0.062,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.054,0.054,0.028,0.087,0.087,0.05,4.5e-06,5e-06,4.8e-06,0.031,0.032,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13690000,0.78,-0.017,0.00081,-0.63,-0.046,-0.015,-0.022,-0.019,-0.0035,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00095,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.06,0.06,0.029,0.098,0.098,0.05,4.3e-06,4.8e-06,4.8e-06,0.031,0.032,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 -13790000,0.78,-0.017,0.00063,-0.63,-0.033,-0.013,-0.024,-0.0063,-0.003,-3.7e+02,-0.0011,-0.006,-8.3e-05,0.00068,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.045,0.045,0.029,0.072,0.072,0.049,4.2e-06,4.6e-06,4.8e-06,0.031,0.031,0.0079,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 -13890000,0.78,-0.017,0.00069,-0.63,-0.037,-0.015,-0.028,-0.01,-0.0045,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00091,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.049,0.049,0.03,0.081,0.081,0.05,4e-06,4.5e-06,4.8e-06,0.031,0.031,0.0078,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 -13990000,0.78,-0.017,0.00054,-0.63,-0.029,-0.014,-0.027,-0.0032,-0.004,-3.7e+02,-0.0011,-0.006,-8.4e-05,0.00078,-0.064,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.9e-06,4.3e-06,4.8e-06,0.031,0.031,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 -14090000,0.78,-0.017,0.00048,-0.63,-0.03,-0.015,-0.028,-0.006,-0.0056,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0012,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.044,0.044,0.031,0.07,0.07,0.05,3.8e-06,4.2e-06,4.8e-06,0.031,0.031,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 -14190000,0.78,-0.017,0.00041,-0.63,-0.024,-0.013,-0.03,-8.4e-05,-0.0036,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0015,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.6e-06,4.1e-06,4.8e-06,0.031,0.031,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 -14290000,0.78,-0.017,0.00037,-0.63,-0.025,-0.015,-0.029,-0.0025,-0.0051,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3.5e-06,3.9e-06,4.8e-06,0.031,0.031,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 -14390000,0.78,-0.017,0.00033,-0.63,-0.02,-0.015,-0.031,0.0017,-0.0037,-3.7e+02,-0.0011,-0.0059,-7.8e-05,0.0021,-0.065,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.034,0.034,0.031,0.053,0.053,0.05,3.4e-06,3.8e-06,4.8e-06,0.031,0.031,0.0063,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 -14490000,0.78,-0.017,0.0004,-0.63,-0.022,-0.018,-0.034,-0.00071,-0.0054,-3.7e+02,-0.001,-0.0059,-7.9e-05,0.0022,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.037,0.037,0.032,0.06,0.06,0.051,3.3e-06,3.7e-06,4.8e-06,0.031,0.031,0.0062,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 -14590000,0.78,-0.017,0.00048,-0.63,-0.023,-0.018,-0.034,-0.0013,-0.0052,-3.7e+02,-0.001,-0.0059,-8e-05,0.0021,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.032,0.032,0.031,0.051,0.051,0.051,3.2e-06,3.6e-06,4.8e-06,0.031,0.031,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14690000,0.78,-0.017,0.0005,-0.63,-0.026,-0.017,-0.031,-0.0038,-0.0071,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0024,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.035,0.035,0.032,0.056,0.056,0.051,3.1e-06,3.5e-06,4.8e-06,0.031,0.031,0.0057,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14790000,0.78,-0.017,0.00051,-0.63,-0.025,-0.016,-0.027,-0.0038,-0.0066,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0023,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.03,0.03,0.031,0.049,0.049,0.051,3e-06,3.3e-06,4.8e-06,0.031,0.031,0.0053,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14890000,0.78,-0.017,0.00052,-0.63,-0.028,-0.019,-0.03,-0.0065,-0.0085,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0025,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.9e-06,3.3e-06,4.8e-06,0.031,0.031,0.0051,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 -14990000,0.78,-0.017,0.00057,-0.63,-0.026,-0.016,-0.026,-0.0049,-0.0065,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.8e-06,3.2e-06,4.8e-06,0.031,0.031,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15090000,0.78,-0.017,0.00066,-0.63,-0.028,-0.017,-0.029,-0.0076,-0.0081,-3.7e+02,-0.00097,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.7e-06,3.1e-06,4.8e-06,0.031,0.031,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15190000,0.78,-0.017,0.00069,-0.63,-0.026,-0.016,-0.026,-0.006,-0.0064,-3.7e+02,-0.00096,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.00041,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.6e-06,3e-06,4.8e-06,0.031,0.031,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15290000,0.78,-0.017,0.00069,-0.63,-0.028,-0.018,-0.024,-0.0086,-0.0082,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0023,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.5e-06,2.9e-06,4.8e-06,0.031,0.031,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15390000,0.78,-0.017,0.00064,-0.63,-0.027,-0.018,-0.022,-0.0082,-0.0083,-3.7e+02,-0.00099,-0.0059,-7.4e-05,0.0028,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.029,0.029,0.029,0.054,0.054,0.051,2.4e-06,2.8e-06,4.8e-06,0.031,0.031,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15490000,0.78,-0.017,0.00066,-0.63,-0.03,-0.018,-0.022,-0.011,-0.0098,-3.7e+02,-0.00099,-0.0059,-7.6e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.4e-06,2.7e-06,4.8e-06,0.031,0.031,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15590000,0.78,-0.017,0.0007,-0.63,-0.028,-0.017,-0.021,-0.01,-0.0091,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0022,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2.3e-06,2.7e-06,4.8e-06,0.031,0.031,0.0035,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15690000,0.78,-0.017,0.00067,-0.63,-0.029,-0.017,-0.021,-0.013,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0021,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.028,0.069,0.069,0.052,2.2e-06,2.6e-06,4.8e-06,0.03,0.031,0.0033,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 -15790000,0.78,-0.017,0.00067,-0.63,-0.026,-0.016,-0.024,-0.009,-0.009,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.026,0.027,0.027,0.056,0.057,0.051,2.2e-06,2.5e-06,4.8e-06,0.03,0.031,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -15890000,0.78,-0.017,0.00068,-0.63,-0.028,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.028,0.029,0.027,0.063,0.063,0.052,2.1e-06,2.5e-06,4.8e-06,0.03,0.031,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -15990000,0.78,-0.017,0.00066,-0.63,-0.025,-0.017,-0.017,-0.0084,-0.0095,-3.7e+02,-0.001,-0.0059,-7.3e-05,0.0023,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.026,0.053,0.053,0.051,2e-06,2.4e-06,4.8e-06,0.03,0.031,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16090000,0.78,-0.017,0.00058,-0.63,-0.027,-0.019,-0.014,-0.011,-0.012,-3.7e+02,-0.0011,-0.0059,-7.1e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.026,0.026,0.025,0.058,0.058,0.052,2e-06,2.3e-06,4.8e-06,0.03,0.031,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16190000,0.78,-0.017,0.00056,-0.63,-0.025,-0.017,-0.013,-0.008,-0.009,-3.7e+02,-0.0011,-0.0059,-6.9e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.9e-06,2.3e-06,4.8e-06,0.03,0.031,0.0025,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16290000,0.78,-0.017,0.00049,-0.63,-0.028,-0.019,-0.014,-0.011,-0.011,-3.7e+02,-0.0011,-0.0059,-6.7e-05,0.0031,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.9e-06,2.2e-06,4.8e-06,0.03,0.031,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16390000,0.78,-0.017,0.00051,-0.63,-0.024,-0.015,-0.013,-0.0081,-0.0086,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.022,0.022,0.023,0.047,0.047,0.051,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16490000,0.78,-0.016,0.00047,-0.63,-0.024,-0.017,-0.016,-0.01,-0.01,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.024,0.023,0.052,0.052,0.052,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.013,-0.017,-0.01,-0.0062,-3.7e+02,-0.0011,-0.0059,-5.9e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.021,0.022,0.046,0.046,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16690000,0.78,-0.016,0.00048,-0.63,-0.025,-0.014,-0.013,-0.013,-0.0073,-3.7e+02,-0.0011,-0.0059,-6.1e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.00096,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.022,0.023,0.022,0.05,0.051,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16790000,0.78,-0.016,0.00052,-0.63,-0.024,-0.01,-0.012,-0.013,-0.004,-3.7e+02,-0.0011,-0.006,-5.6e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.0009,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.6e-06,2e-06,4.8e-06,0.03,0.031,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16890000,0.78,-0.016,0.00051,-0.63,-0.025,-0.011,-0.0096,-0.015,-0.0049,-3.7e+02,-0.0011,-0.006,-5.7e-05,0.0027,-0.066,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.6e-06,1.9e-06,4.8e-06,0.03,0.031,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -16990000,0.78,-0.016,0.00055,-0.63,-0.024,-0.011,-0.0091,-0.014,-0.0048,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.019,0.02,0.02,0.043,0.043,0.05,1.5e-06,1.9e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17090000,0.78,-0.016,0.00054,-0.63,-0.025,-0.013,-0.009,-0.016,-0.0059,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17190000,0.78,-0.016,0.00048,-0.63,-0.024,-0.015,-0.0099,-0.014,-0.0062,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17290000,0.78,-0.016,0.00051,-0.63,-0.027,-0.017,-0.0054,-0.017,-0.0074,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0024,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.019,0.047,0.047,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17390000,0.78,-0.016,0.00044,-0.63,-0.024,-0.018,-0.0035,-0.014,-0.0076,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17490000,0.78,-0.016,0.00046,-0.63,-0.026,-0.019,-0.0018,-0.017,-0.0095,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17590000,0.78,-0.016,0.00047,-0.63,-0.024,-0.019,0.0036,-0.014,-0.0091,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17690000,0.78,-0.016,0.00049,-0.63,-0.026,-0.021,0.003,-0.017,-0.011,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.0027,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.019,0.017,0.045,0.045,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17790000,0.78,-0.016,0.00043,-0.63,-0.024,-0.022,0.0016,-0.015,-0.012,-3.7e+02,-0.0012,-0.0059,-4.8e-05,0.0031,-0.065,-0.13,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.023,0.0017,-0.018,-0.015,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0033,-0.065,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.016,0.053,0.053,0.048,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 -17990000,0.78,-0.016,0.00045,-0.63,-0.026,-0.021,0.0029,-0.016,-0.015,-3.7e+02,-0.0012,-0.0059,-4.5e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.001,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 -18090000,0.78,-0.016,0.00049,-0.63,-0.027,-0.021,0.0053,-0.019,-0.016,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.021,0.021,0.016,0.06,0.061,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.00098,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 -18190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.02,0.0066,-0.014,-0.013,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00093,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18290000,0.78,-0.016,0.00059,-0.63,-0.025,-0.02,0.0078,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18390000,0.78,-0.016,0.00055,-0.63,-0.024,-0.021,0.009,-0.013,-0.012,-3.7e+02,-0.0012,-0.006,-3.8e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.014,0.048,0.048,0.046,1.1e-06,1.4e-06,4.7e-06,0.03,0.03,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18490000,0.78,-0.016,0.00051,-0.63,-0.024,-0.023,0.0086,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3.7e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.014,0.053,0.053,0.046,1.1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18590000,0.78,-0.016,0.00049,-0.63,-0.022,-0.022,0.0067,-0.012,-0.013,-3.7e+02,-0.0013,-0.0059,-2.8e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.016,0.017,0.014,0.046,0.046,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18690000,0.78,-0.016,0.00055,-0.63,-0.024,-0.023,0.0048,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3e-05,0.0033,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.013,0.05,0.05,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18790000,0.78,-0.016,0.00057,-0.63,-0.022,-0.021,0.0045,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.013,0.044,0.044,0.045,1e-06,1.2e-06,4.7e-06,0.03,0.03,0.00073,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18890000,0.78,-0.016,0.00048,-0.63,-0.022,-0.024,0.0051,-0.014,-0.015,-3.7e+02,-0.0013,-0.0059,-2.2e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.8e-07,1.2e-06,4.7e-06,0.03,0.03,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -18990000,0.78,-0.016,0.00042,-0.63,-0.019,-0.024,0.0037,-0.0098,-0.013,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.012,0.043,0.043,0.044,9.5e-07,1.2e-06,4.7e-06,0.03,0.03,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19090000,0.78,-0.016,0.00041,-0.63,-0.019,-0.025,0.0067,-0.011,-0.015,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.012,0.046,0.047,0.044,9.4e-07,1.2e-06,4.7e-06,0.03,0.03,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19190000,0.78,-0.016,0.00036,-0.63,-0.015,-0.024,0.0067,-0.0077,-0.013,-3.7e+02,-0.0013,-0.0059,-8.2e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.015,0.012,0.041,0.042,0.044,9.1e-07,1.2e-06,4.7e-06,0.03,0.03,0.00063,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19290000,0.78,-0.016,0.00037,-0.63,-0.016,-0.024,0.0094,-0.0095,-0.016,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0034,-0.065,-0.13,-0.11,-0.024,0.5,-0.00069,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.012,0.045,0.046,0.044,9e-07,1.1e-06,4.7e-06,0.03,0.03,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19390000,0.78,-0.016,0.0004,-0.63,-0.015,-0.022,0.013,-0.0084,-0.014,-3.7e+02,-0.0013,-0.006,-2.4e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.8e-07,1.1e-06,4.6e-06,0.03,0.03,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19490000,0.78,-0.016,0.00035,-0.63,-0.015,-0.024,0.0096,-0.01,-0.017,-3.7e+02,-0.0013,-0.0059,1.4e-06,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00064,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.6e-07,1.1e-06,4.6e-06,0.03,0.03,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.022,0.0088,-0.0085,-0.015,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.0039,-0.065,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.04,0.04,0.042,8.4e-07,1.1e-06,4.6e-06,0.03,0.03,0.00055,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19690000,0.78,-0.015,0.00028,-0.63,-0.014,-0.021,0.01,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00061,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.044,0.042,8.3e-07,1.1e-06,4.6e-06,0.03,0.03,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.018,0.011,-0.0079,-0.015,-3.7e+02,-0.0013,-0.006,1.8e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00058,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.039,0.039,0.042,8.1e-07,1e-06,4.6e-06,0.03,0.03,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.02,0.012,-0.0096,-0.017,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.004,-0.065,-0.13,-0.11,-0.024,0.5,-0.00056,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.043,0.042,8e-07,1e-06,4.6e-06,0.03,0.03,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -19990000,0.78,-0.016,0.00028,-0.63,-0.0096,-0.02,0.015,-0.0084,-0.016,-3.7e+02,-0.0013,-0.0059,3.9e-05,0.0043,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.039,0.039,0.041,7.7e-07,9.9e-07,4.6e-06,0.03,0.03,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20090000,0.78,-0.016,0.00023,-0.63,-0.0096,-0.02,0.015,-0.0091,-0.019,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.01,0.042,0.043,0.042,7.7e-07,9.8e-07,4.6e-06,0.03,0.03,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20190000,0.78,-0.016,0.00019,-0.63,-0.01,-0.019,0.017,-0.0092,-0.017,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00046,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.038,0.039,0.041,7.4e-07,9.5e-07,4.6e-06,0.03,0.03,0.00045,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20290000,0.78,-0.016,0.00019,-0.63,-0.0089,-0.019,0.015,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,7.4e-07,9.4e-07,4.6e-06,0.03,0.03,0.00044,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20390000,0.78,-0.016,0.00024,-0.63,-0.0085,-0.016,0.017,-0.0095,-0.017,-3.7e+02,-0.0013,-0.0059,6.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,7.2e-07,9.2e-07,4.5e-06,0.03,0.03,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20490000,0.78,-0.016,0.0002,-0.63,-0.0087,-0.016,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,6.5e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,7.1e-07,9.1e-07,4.5e-06,0.03,0.03,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20590000,0.78,-0.016,0.0002,-0.63,-0.0081,-0.014,0.014,-0.0089,-0.016,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0093,0.038,0.038,0.04,6.9e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20690000,0.78,-0.016,0.00015,-0.63,-0.0089,-0.014,0.015,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,7.2e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.8e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20790000,0.78,-0.016,0.00013,-0.63,-0.0065,-0.013,0.016,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.6e-07,8.5e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20890000,0.78,-0.016,0.00011,-0.63,-0.0067,-0.013,0.015,-0.0088,-0.017,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.6e-07,8.4e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -20990000,0.78,-0.016,9.5e-05,-0.63,-0.0051,-0.011,0.015,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,9e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00038,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.4e-07,8.3e-07,4.4e-06,0.03,0.03,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21090000,0.78,-0.016,8.8e-05,-0.63,-0.0062,-0.011,0.016,-0.0094,-0.019,-3.7e+02,-0.0013,-0.0059,9.3e-05,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6.4e-07,8.2e-07,4.4e-06,0.03,0.03,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21190000,0.78,-0.016,8.4e-05,-0.63,-0.0063,-0.011,0.015,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,9.4e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00036,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21290000,0.78,-0.016,-6.5e-06,-0.63,-0.0059,-0.011,0.017,-0.0099,-0.021,-3.7e+02,-0.0013,-0.0059,0.0001,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0085,0.054,0.055,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21390000,0.78,-0.016,4.3e-05,-0.63,-0.0052,-0.0064,0.016,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,0.00011,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0084,0.046,0.047,0.039,6e-07,7.7e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21490000,0.78,-0.016,3.3e-05,-0.63,-0.0059,-0.0073,0.016,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,0.00011,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0083,0.05,0.052,0.038,5.9e-07,7.6e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21590000,0.78,-0.016,7.2e-05,-0.63,-0.0045,-0.0056,0.016,-0.0082,-0.013,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00029,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0081,0.044,0.045,0.038,5.8e-07,7.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21690000,0.78,-0.016,6.5e-05,-0.63,-0.0061,-0.0065,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.7e-07,7.4e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21790000,0.78,-0.016,0.00016,-0.63,-0.0051,-0.0043,0.016,-0.0083,-0.0092,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.6e-07,7.1e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21890000,0.78,-0.015,0.00016,-0.63,-0.0058,-0.005,0.016,-0.009,-0.0097,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.5e-07,7.1e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -21990000,0.78,-0.015,0.00019,-0.63,-0.0057,-0.0022,0.017,-0.0084,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.4e-07,6.9e-07,4.3e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -22090000,0.78,-0.015,0.00018,-0.63,-0.0054,-0.0037,0.015,-0.0088,-0.006,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0078,0.045,0.046,0.037,5.4e-07,6.9e-07,4.2e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -22190000,0.78,-0.015,0.00019,-0.63,-0.004,-0.0043,0.016,-0.0073,-0.0054,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0076,0.04,0.041,0.037,5.2e-07,6.7e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -22290000,0.78,-0.015,0.00016,-0.63,-0.0036,-0.0039,0.016,-0.008,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0076,0.043,0.045,0.037,5.2e-07,6.6e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 -22390000,0.78,-0.015,0.00015,-0.63,-0.0011,-0.0039,0.017,-0.0062,-0.0051,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.012,0.014,0.0075,0.039,0.04,0.037,5.1e-07,6.5e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22490000,0.78,-0.015,0.00013,-0.63,7e-05,-0.0045,0.018,-0.0056,-0.0054,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0074,0.042,0.044,0.037,5e-07,6.4e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22590000,0.78,-0.015,0.00013,-0.63,0.0019,-0.0034,0.018,-0.0039,-0.0047,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0073,0.045,0.046,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22690000,0.78,-0.015,6.1e-05,-0.63,0.0035,-0.0046,0.019,-0.0032,-0.0056,-3.7e+02,-0.0014,-0.0059,0.00016,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0073,0.048,0.05,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22790000,0.78,-0.015,0.0001,-0.63,0.0045,-0.004,0.02,-0.0026,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0072,0.051,0.052,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22890000,0.78,-0.015,0.00011,-0.63,0.0052,-0.0049,0.021,-0.0028,-0.0048,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0072,0.055,0.057,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -22990000,0.78,-0.015,0.00012,-0.63,0.0049,-0.0049,0.022,-0.0029,-0.0055,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0071,0.058,0.06,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23090000,0.78,-0.015,0.00018,-0.63,0.0051,-0.0046,0.023,-0.0027,-0.0052,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.007,0.062,0.065,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23190000,0.78,-0.015,0.00017,-0.63,0.0027,-0.0034,0.024,-0.0055,-0.005,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0069,0.065,0.067,0.035,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23290000,0.78,-0.015,0.00023,-0.63,0.0023,-0.0031,0.025,-0.0058,-0.0057,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.017,0.019,0.0069,0.07,0.073,0.036,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23390000,0.78,-0.015,0.00021,-0.63,-0.0011,-0.0028,0.022,-0.01,-0.0058,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.0068,0.072,0.075,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23490000,0.78,-0.013,-0.0019,-0.63,0.0044,-0.0021,-0.011,-0.011,-0.007,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00014,-0.091,-0.068,0,0,0.00036,0.00036,0.046,0.017,0.019,0.0068,0.078,0.081,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23590000,0.78,-0.0042,-0.0062,-0.63,0.015,0.0017,-0.043,-0.0099,-0.0038,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.066,-0.13,-0.11,-0.024,0.5,-0.00012,-0.091,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0067,0.062,0.064,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23690000,0.78,0.0014,-0.0052,-0.63,0.042,0.016,-0.093,-0.0075,-0.0033,-3.7e+02,-0.0013,-0.0059,0.00018,0.0046,-0.066,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0067,0.067,0.069,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23790000,0.78,-0.0022,-0.0027,-0.63,0.063,0.033,-0.15,-0.0074,-0.0017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.014,0.015,0.0066,0.055,0.056,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23890000,0.78,-0.0085,-0.0007,-0.63,0.077,0.045,-0.2,2.8e-05,0.0023,-3.7e+02,-0.0013,-0.0059,0.00019,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00034,0.00035,0.046,0.014,0.016,0.0066,0.059,0.061,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -23990000,0.78,-0.013,0.00021,-0.63,0.072,0.045,-0.25,-0.0055,0.00083,-3.7e+02,-0.0013,-0.0059,0.00018,0.0052,-0.067,-0.13,-0.11,-0.024,0.5,-0.00029,-0.09,-0.067,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0066,0.062,0.063,0.035,4.1e-07,5.2e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -24090000,0.78,-0.012,-0.00093,-0.63,0.072,0.044,-0.3,0.00081,0.0045,-3.7e+02,-0.0013,-0.0059,0.00019,0.0053,-0.067,-0.13,-0.11,-0.024,0.5,-0.00034,-0.09,-0.067,0,0,0.00035,0.00036,0.046,0.015,0.017,0.0065,0.066,0.069,0.035,4.1e-07,5.2e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -24190000,0.78,-0.0097,-0.0017,-0.63,0.069,0.043,-0.35,-0.0065,0.0022,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00031,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.015,0.017,0.0065,0.069,0.071,0.034,4.1e-07,5.1e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24290000,0.78,-0.0089,-0.0021,-0.63,0.077,0.048,-0.4,-0.00011,0.0069,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0065,0.074,0.077,0.034,4e-07,5.1e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24390000,0.78,-0.0093,-0.0022,-0.63,0.074,0.047,-0.46,-0.013,0.00027,-3.7e+02,-0.0012,-0.0059,0.00015,0.0062,-0.069,-0.13,-0.11,-0.024,0.5,-0.0003,-0.089,-0.068,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24490000,0.78,-0.0051,-0.0026,-0.63,0.085,0.054,-0.51,-0.0046,0.0052,-3.7e+02,-0.0012,-0.0059,0.00015,0.0063,-0.069,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.02,0.0064,0.082,0.085,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24590000,0.78,-0.0016,-0.0027,-0.63,0.089,0.057,-0.56,-0.018,-0.0039,-3.7e+02,-0.0012,-0.0059,0.00014,0.0069,-0.071,-0.13,-0.11,-0.024,0.5,-0.00037,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24690000,0.78,-0.00074,-0.0027,-0.63,0.11,0.073,-0.64,-0.0089,0.0014,-3.7e+02,-0.0012,-0.0059,0.00015,0.0072,-0.071,-0.13,-0.11,-0.024,0.5,-0.00055,-0.089,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0063,0.09,0.094,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -24790000,0.78,-0.0023,-0.0024,-0.63,0.11,0.082,-0.73,-0.028,-0.0034,-3.7e+02,-0.0012,-0.0059,0.00013,0.0079,-0.073,-0.13,-0.11,-0.025,0.5,-0.00036,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0062,0.093,0.096,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -24890000,0.78,-0.00046,-0.004,-0.63,0.13,0.097,-0.75,-0.017,0.0055,-3.7e+02,-0.0012,-0.0059,0.00012,0.0081,-0.074,-0.13,-0.11,-0.025,0.5,-0.00045,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.099,0.1,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00062,0.0012,0.0012,1,1 -24990000,0.78,0.0012,-0.0055,-0.63,0.13,0.1,-0.81,-0.039,-0.001,-3.7e+02,-0.0011,-0.0059,9e-05,0.0092,-0.076,-0.13,-0.11,-0.025,0.5,-0.00024,-0.087,-0.069,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -25090000,0.78,0.00063,-0.0059,-0.63,0.16,0.12,-0.86,-0.025,0.011,-3.7e+02,-0.0011,-0.0059,8.4e-05,0.0094,-0.076,-0.13,-0.11,-0.025,0.5,-0.00025,-0.087,-0.068,0,0,0.00034,0.00034,0.044,0.02,0.023,0.0062,0.11,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0011,0.0012,1,1 -25190000,0.78,-0.0015,-0.0054,-0.62,0.15,0.11,-0.91,-0.069,-0.012,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00022,-0.086,-0.069,0,0,0.00034,0.00033,0.044,0.02,0.023,0.0061,0.11,0.11,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1 -25290000,0.78,0.0055,-0.0066,-0.62,0.17,0.13,-0.96,-0.053,-0.00075,-3.7e+02,-0.0011,-0.0059,4.8e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00034,-0.086,-0.069,0,0,0.00033,0.00034,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.0006,0.0011,0.0012,1,1 -25390000,0.78,0.011,-0.0071,-0.62,0.18,0.13,-1,-0.1,-0.025,-3.7e+02,-0.001,-0.0058,8.1e-06,0.014,-0.086,-0.13,-0.11,-0.025,0.5,-0.00037,-0.085,-0.069,0,0,0.00033,0.00036,0.043,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1 -25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.082,-0.012,-3.7e+02,-0.001,-0.0058,2.3e-05,0.014,-0.087,-0.13,-0.11,-0.025,0.5,-0.00072,-0.084,-0.069,0,0,0.00033,0.00036,0.042,0.022,0.026,0.0061,0.13,0.13,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25590000,0.78,0.011,-0.007,-0.63,0.25,0.19,-1.1,-0.059,0.0041,-3.7e+02,-0.001,-0.0058,3.2e-05,0.014,-0.087,-0.13,-0.12,-0.025,0.5,-0.00098,-0.084,-0.068,0,0,0.00033,0.00035,0.042,0.024,0.028,0.0061,0.14,0.14,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1 -25690000,0.78,0.018,-0.0099,-0.63,0.29,0.21,-1.2,-0.032,0.022,-3.7e+02,-0.001,-0.0058,4.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0013,-0.082,-0.068,0,0,0.00034,0.00039,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00017,0.001,5.2e-05,0.0011,0.00057,0.0011,0.0011,1,1 -25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,-0.00023,0.043,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00034,0.00043,0.041,0.027,0.033,0.0061,0.15,0.16,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1 -25890000,0.77,0.025,-0.012,-0.63,0.41,0.28,-1.3,0.039,0.066,-3.7e+02,-0.00099,-0.0058,8.6e-05,0.015,-0.089,-0.13,-0.12,-0.026,0.5,-0.0025,-0.079,-0.066,0,0,0.00034,0.00043,0.04,0.029,0.037,0.0061,0.17,0.17,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5e-05,0.0011,0.00056,0.0011,0.0011,1,1 -25990000,0.77,0.021,-0.012,-0.63,0.47,0.31,-1.3,0.083,0.093,-3.7e+02,-0.00099,-0.0058,9.9e-05,0.015,-0.089,-0.13,-0.12,-0.027,0.5,-0.0029,-0.078,-0.065,0,0,0.00034,0.00041,0.04,0.032,0.04,0.0061,0.18,0.19,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1 -26090000,0.78,0.032,-0.016,-0.63,0.52,0.35,-1.3,0.13,0.13,-3.7e+02,-0.00098,-0.0058,8.8e-05,0.016,-0.089,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00035,0.00049,0.039,0.034,0.043,0.0061,0.19,0.2,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00097,4.8e-05,0.0011,0.00054,0.001,0.0011,1,1 -26190000,0.78,0.041,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,9.6e-05,0.018,-0.09,-0.13,-0.13,-0.028,0.5,-0.0035,-0.074,-0.063,0,0,0.00036,0.00058,0.037,0.036,0.047,0.0061,0.2,0.22,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00093,4.7e-05,0.001,0.00053,0.00098,0.001,1,1 -26290000,0.78,0.044,-0.018,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,9.2e-05,0.019,-0.091,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00036,0.0006,0.036,0.039,0.052,0.0061,0.21,0.23,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00091,4.6e-05,0.001,0.00052,0.00094,0.001,1,1 -26390000,0.77,0.04,-0.018,-0.63,0.76,0.5,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,0.0001,0.02,-0.091,-0.13,-0.13,-0.028,0.49,-0.0042,-0.069,-0.06,0,0,0.00036,0.00055,0.034,0.042,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00097,1,1 -26490000,0.77,0.056,-0.024,-0.63,0.84,0.55,-1.3,0.4,0.3,-3.7e+02,-0.00096,-0.0058,0.0001,0.02,-0.092,-0.13,-0.13,-0.029,0.49,-0.0043,-0.067,-0.058,0,0,0.00038,0.00075,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1 -26590000,0.77,0.073,-0.029,-0.63,0.95,0.63,-1.3,0.48,0.36,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.023,-0.092,-0.13,-0.13,-0.03,0.49,-0.0039,-0.064,-0.057,0,0,0.00041,0.00098,0.031,0.048,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1 -26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.024,-0.093,-0.13,-0.14,-0.031,0.49,-0.0049,-0.059,-0.052,0,0,0.00041,0.00097,0.028,0.052,0.073,0.0061,0.28,0.31,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1 -26790000,0.77,0.07,-0.029,-0.64,1.2,0.79,-1.3,0.7,0.5,-3.7e+02,-0.00095,-0.0058,6.9e-05,0.025,-0.093,-0.13,-0.14,-0.032,0.48,-0.0047,-0.055,-0.049,0,0,0.00039,0.00084,0.026,0.055,0.079,0.0061,0.3,0.33,0.033,3.7e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1 -26890000,0.76,0.093,-0.036,-0.64,1.3,0.86,-1.3,0.83,0.58,-3.7e+02,-0.00095,-0.0058,7.2e-05,0.026,-0.093,-0.13,-0.15,-0.032,0.48,-0.0052,-0.052,-0.047,0,0,0.00044,0.0011,0.024,0.058,0.085,0.0061,0.32,0.35,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1 -26990000,0.76,0.12,-0.041,-0.64,1.5,0.97,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,6.1e-05,0.029,-0.094,-0.13,-0.15,-0.034,0.48,-0.0055,-0.046,-0.043,0,0,0.00049,0.0014,0.021,0.061,0.091,0.0061,0.34,0.37,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1 -27090000,0.76,0.12,-0.041,-0.64,1.7,1.1,-1.2,1.1,0.78,-3.7e+02,-0.00095,-0.0058,4.5e-05,0.03,-0.093,-0.13,-0.16,-0.035,0.47,-0.0055,-0.041,-0.038,0,0,0.00049,0.0013,0.018,0.065,0.098,0.0061,0.36,0.4,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1 -27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.9,-3.7e+02,-0.00096,-0.0058,2.8e-05,0.032,-0.092,-0.13,-0.16,-0.035,0.47,-0.0053,-0.038,-0.035,0,0,0.00045,0.0011,0.017,0.068,0.1,0.0062,0.38,0.43,0.034,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1 -27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,2.2e-05,0.032,-0.091,-0.13,-0.16,-0.036,0.47,-0.0054,-0.035,-0.033,0,0,0.00041,0.00083,0.015,0.07,0.11,0.0062,0.4,0.46,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1 -27390000,0.76,0.077,-0.03,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00095,-0.0058,1.7e-05,0.033,-0.089,-0.13,-0.17,-0.036,0.47,-0.0054,-0.033,-0.032,0,0,0.00038,0.00064,0.014,0.071,0.11,0.0062,0.43,0.49,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1 -27490000,0.76,0.061,-0.025,-0.64,2.2,1.4,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,9e-06,0.033,-0.087,-0.13,-0.17,-0.037,0.47,-0.0052,-0.032,-0.032,0,0,0.00036,0.00052,0.012,0.072,0.11,0.0062,0.46,0.52,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1 -27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,-8.8e-07,0.034,-0.084,-0.13,-0.17,-0.037,0.47,-0.0048,-0.031,-0.031,0,0,0.00035,0.00045,0.012,0.073,0.11,0.0062,0.48,0.55,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1 -27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,-9.9e-06,0.034,-0.083,-0.13,-0.17,-0.037,0.47,-0.0044,-0.031,-0.031,0,0,0.00035,0.00044,0.011,0.073,0.11,0.0063,0.51,0.59,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1 -27790000,0.77,0.049,-0.021,-0.64,2.3,1.5,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,-2.3e-05,0.035,-0.081,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.031,0,0,0.00035,0.00044,0.0098,0.074,0.1,0.0063,0.54,0.62,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00042,2.2e-05,0.00049,0.00022,0.00044,0.00048,1,1 -27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,-2.4e-05,0.034,-0.079,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00043,0.0093,0.075,0.1,0.0063,0.58,0.66,0.034,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00041,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1 -27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,-2.7e-05,0.034,-0.078,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00041,0.0087,0.076,0.1,0.0064,0.61,0.7,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1 -28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,-3.8e-05,0.035,-0.076,-0.13,-0.17,-0.038,0.47,-0.0035,-0.029,-0.03,0,0,0.00035,0.00045,0.0081,0.077,0.1,0.0064,0.65,0.74,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.0004,2.1e-05,0.00048,0.00021,0.00042,0.00048,1,1 -28190000,0.77,0.071,-0.028,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,-4e-05,0.035,-0.074,-0.13,-0.17,-0.038,0.46,-0.0035,-0.029,-0.03,0,0,0.00036,0.00049,0.0077,0.078,0.1,0.0065,0.68,0.79,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1 -28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00095,-0.0058,-4.9e-05,0.035,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.028,-0.029,0,0,0.00035,0.00043,0.0074,0.077,0.1,0.0066,0.72,0.83,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1 -28390000,0.77,0.02,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,-5.7e-05,0.035,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00035,0.00037,0.0071,0.076,0.1,0.0066,0.76,0.88,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 -28490000,0.77,0.0014,-0.0026,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,-6.3e-05,0.035,-0.065,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0068,0.077,0.099,0.0067,0.8,0.93,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 -28590000,0.77,-0.0022,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00096,-0.0058,-6.4e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0065,0.077,0.098,0.0067,0.84,0.98,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 -28690000,0.77,-0.0032,-0.00057,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00097,-0.0058,-7.1e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00034,0.00036,0.0063,0.078,0.098,0.0067,0.88,1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1 -28790000,0.77,-0.0034,-0.00035,-0.63,2.2,1.6,1,5,3.4,-3.7e+02,-0.00098,-0.0058,-7.9e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00034,0.00037,0.0061,0.079,0.098,0.0068,0.92,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 -28890000,0.77,-0.0032,-0.00036,-0.63,2.2,1.5,0.99,5.2,3.6,-3.7e+02,-0.00099,-0.0058,-8.6e-05,0.033,-0.06,-0.12,-0.17,-0.038,0.46,-0.0028,-0.027,-0.029,0,0,0.00034,0.00037,0.0059,0.08,0.1,0.0068,0.97,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 -28990000,0.77,-0.0027,-0.00054,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-9.8e-05,0.033,-0.058,-0.12,-0.17,-0.038,0.46,-0.0026,-0.027,-0.028,0,0,0.00034,0.00037,0.0057,0.081,0.1,0.0069,1,1.2,0.034,3.6e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 -29090000,0.78,-0.0022,-0.0007,-0.63,2.1,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.056,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00034,0.00037,0.0055,0.083,0.1,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 -29190000,0.77,-0.0019,-0.00078,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.028,0,0,0.00034,0.00037,0.0054,0.084,0.1,0.007,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1 -29290000,0.78,-0.00093,-0.0011,-0.63,1.9,1.4,1,6.1,4.2,-3.7e+02,-0.001,-0.0058,-0.00011,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.028,0,0,0.00033,0.00037,0.0053,0.086,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00044,1,1 -29390000,0.78,0.00051,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-0.00012,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.0051,0.087,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29490000,0.78,0.0017,-0.0018,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,-0.00013,0.03,-0.05,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.005,0.089,0.11,0.0071,1.3,1.5,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29590000,0.78,0.0028,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-0.00013,0.028,-0.048,-0.12,-0.17,-0.038,0.46,-0.002,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.091,0.12,0.0071,1.3,1.6,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29690000,0.78,0.0036,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-0.00014,0.028,-0.045,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.093,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29790000,0.78,0.0041,-0.0025,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0058,-0.00014,0.027,-0.042,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0048,0.095,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29890000,0.78,0.0045,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.001,-0.0058,-0.00015,0.026,-0.038,-0.12,-0.17,-0.038,0.46,-0.0017,-0.028,-0.028,0,0,0.00033,0.00038,0.0047,0.097,0.13,0.0072,1.5,1.8,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 -29990000,0.78,0.0046,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.001,-0.0058,-0.00015,0.025,-0.035,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00033,0.00038,0.0046,0.099,0.13,0.0072,1.6,1.9,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 -30090000,0.78,0.0046,-0.0027,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0058,-0.00016,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0046,0.1,0.14,0.0072,1.6,2,0.034,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 -30190000,0.78,0.0043,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.001,-0.0058,-0.00016,0.023,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0045,0.1,0.14,0.0072,1.7,2.1,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 -30290000,0.78,0.0042,-0.0026,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00016,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.2,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 -30390000,0.78,0.0041,-0.0026,-0.63,1.5,1.2,0.9,8,5.7,-3.7e+02,-0.0011,-0.0058,-0.00017,0.021,-0.028,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.3,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30490000,0.78,0.0039,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.8,-3.7e+02,-0.0011,-0.0058,-0.00017,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.16,0.0072,1.9,2.4,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30590000,0.78,0.0036,-0.0025,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.019,-0.022,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0043,0.11,0.16,0.0072,2,2.5,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30690000,0.78,0.0034,-0.0024,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00017,0.018,-0.019,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00039,0.0043,0.11,0.17,0.0072,2.1,2.6,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30790000,0.78,0.0031,-0.0023,-0.63,1.4,1.2,0.83,8.6,6.2,-3.7e+02,-0.0011,-0.0058,-0.00017,0.017,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.8,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30890000,0.78,0.0027,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.3,-3.7e+02,-0.0011,-0.0058,-0.00018,0.016,-0.016,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.9,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -30990000,0.78,0.0023,-0.0022,-0.63,1.3,1.2,0.81,8.9,6.4,-3.7e+02,-0.0011,-0.0058,-0.00018,0.015,-0.012,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.19,0.0072,2.3,3,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -31090000,0.78,0.0019,-0.0021,-0.63,1.3,1.1,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00018,0.014,-0.0094,-0.12,-0.17,-0.038,0.46,-0.00097,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.12,0.2,0.0072,2.4,3.2,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -31190000,0.78,0.0016,-0.002,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00019,0.012,-0.0056,-0.12,-0.17,-0.038,0.46,-0.00088,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.2,0.0072,2.5,3.3,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -31290000,0.78,0.0012,-0.0018,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00019,0.011,-0.0028,-0.12,-0.17,-0.038,0.46,-0.00081,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.21,0.0071,2.6,3.5,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 -31390000,0.78,0.00059,-0.0016,-0.63,1.2,1.1,0.79,9.4,6.9,-3.7e+02,-0.0011,-0.0058,-0.00019,0.0099,0.0002,-0.12,-0.17,-0.038,0.46,-0.00074,-0.029,-0.027,0,0,0.0003,0.0004,0.0041,0.13,0.22,0.0071,2.7,3.6,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 -31490000,0.78,8.5e-05,-0.0015,-0.63,1.2,1.1,0.79,9.5,7,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0086,0.0029,-0.12,-0.17,-0.038,0.46,-0.00061,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.23,0.0071,2.8,3.8,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 -31590000,0.78,-0.00021,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.1,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0073,0.005,-0.11,-0.17,-0.038,0.46,-0.00056,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.0071,2.9,3.9,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 -31690000,0.78,-0.00082,-0.0013,-0.63,1.1,1.1,0.79,9.8,7.2,-3.7e+02,-0.0011,-0.0058,-0.0002,0.006,0.0077,-0.11,-0.17,-0.038,0.46,-0.00049,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.007,3,4.1,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -31790000,0.78,-0.0014,-0.0011,-0.63,1.1,1,0.79,9.9,7.3,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0047,0.011,-0.11,-0.17,-0.038,0.46,-0.00042,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.25,0.007,3.1,4.3,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -31890000,0.78,-0.002,-0.001,-0.63,1.1,1,0.78,10,7.4,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0033,0.014,-0.11,-0.17,-0.038,0.46,-0.00033,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.15,0.26,0.007,3.2,4.5,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -31990000,0.78,-0.0024,-0.0009,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0011,-0.0058,-0.00021,0.0018,0.017,-0.11,-0.17,-0.038,0.46,-0.00022,-0.029,-0.027,0,0,0.00029,0.00041,0.004,0.15,0.27,0.007,3.3,4.7,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32090000,0.78,-0.003,-0.0007,-0.63,1,0.99,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00021,0.00019,0.02,-0.11,-0.17,-0.038,0.46,-0.00011,-0.029,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.28,0.007,3.5,4.9,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32190000,0.78,-0.0038,-0.00051,-0.63,0.97,0.98,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0015,0.024,-0.11,-0.18,-0.038,0.46,3.2e-05,-0.03,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.29,0.0069,3.6,5.1,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32290000,0.78,-0.0044,-0.00042,-0.63,0.94,0.96,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0032,0.028,-0.11,-0.18,-0.038,0.46,0.00014,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.3,0.0069,3.7,5.4,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32390000,0.78,-0.0049,-0.00032,-0.63,0.91,0.94,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0041,0.03,-0.11,-0.18,-0.038,0.46,0.00019,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.31,0.0069,3.8,5.6,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 -32490000,0.78,-0.0051,-0.00027,-0.63,0.88,0.92,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0056,0.032,-0.11,-0.18,-0.038,0.46,0.00028,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.16,0.32,0.0068,4,5.8,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 -32590000,0.78,-0.0053,-0.00021,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0064,0.033,-0.11,-0.18,-0.038,0.46,0.00034,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,3e-07,5.1e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 -32690000,0.78,-0.0053,-0.00025,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0073,0.035,-0.11,-0.18,-0.038,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.2e-06,0.029,0.023,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -32790000,0.78,-0.0052,-0.00026,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0081,0.036,-0.11,-0.18,-0.038,0.46,0.00047,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.27,0.26,0.26,0.049,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -32890000,0.78,-0.005,-0.00039,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0089,0.038,-0.11,-0.18,-0.038,0.46,0.00057,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -32990000,0.78,-0.0049,-0.0005,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0098,0.04,-0.11,-0.18,-0.038,0.46,0.00059,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -33090000,0.78,-0.005,-0.00048,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00061,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -33190000,0.78,-0.0036,-0.0037,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.01,0.041,-0.11,-0.18,-0.038,0.46,0.0006,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -33290000,0.82,-0.0015,-0.016,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.039,0.46,0.00058,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00035,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 -33390000,0.89,-0.0018,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.015,0.038,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.9e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1 -33490000,0.95,-0.00026,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.018,0.037,-0.11,-0.18,-0.04,0.46,0.0017,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1 -33590000,0.99,-0.003,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.018,0.037,-0.11,-0.19,-0.042,0.46,0.0025,-0.013,-0.026,0,0,0.00035,0.00031,0.003,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00017,1e-05,0.00041,9.5e-05,0.00016,0.0004,1,1 -33690000,1,-0.0064,0.005,0.024,-1.6,-0.86,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.018,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00028,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1 -33790000,0.98,-0.0073,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0068,-0.027,0,0,0.00037,0.00026,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,4.9e-07,3.1e-06,0.028,0.022,9.3e-05,9.7e-05,6.4e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1 -33890000,0.94,-0.0075,0.0082,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,4.9e-07,3e-06,0.028,0.022,9.3e-05,8.1e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1 -33990000,0.87,-0.0095,0.0057,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00027,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.8e-07,3e-06,0.028,0.022,9.3e-05,7.1e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1 -34090000,0.81,-0.011,0.0044,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.01,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.034,0.33,0.33,0.063,2.8e-07,4.9e-07,3e-06,0.027,0.022,9.3e-05,6.6e-05,4.9e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1 -34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.039,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00028,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.7e-07,3e-06,0.026,0.021,9.3e-05,6e-05,4.6e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1 -34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.038,0.051,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00029,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.7e-07,3e-06,0.025,0.021,9.3e-05,5.7e-05,4.5e-06,0.0004,1.4e-05,1.6e-05,0.0004,1,1 -34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.036,0.05,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00025,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.5e-05,4.4e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1 -34490000,0.69,-0.00036,0.0066,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.073,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.4e-05,4.3e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1 -34590000,0.68,0.00092,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.05,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.085,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.2e-05,4.3e-06,0.0004,1e-05,1.1e-05,0.0004,1,1 -34690000,0.67,0.0017,0.0079,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.034,0.049,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00024,0.0003,0.0017,0.098,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,9.6e-06,1e-05,0.0004,1,1 -34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.036,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00024,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,8.9e-06,9.2e-06,0.0004,1,1 -34890000,0.66,0.0025,0.0082,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1 -34990000,0.66,-0.00086,0.016,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00024,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.9e-06,8e-06,0.0004,1,1 -35090000,0.66,-0.00092,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.5e-06,7.5e-06,0.0004,1,1 -35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.28,0.014,0.52,0.55,0.054,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1 -35290000,0.66,-0.0012,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00084,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.23,0.31,0.013,0.56,0.6,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1 -35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.25,0.34,0.013,0.61,0.66,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.6e-06,6.4e-06,0.0004,1,1 -35490000,0.66,-0.0012,0.016,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.28,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.4e-06,6.2e-06,0.0004,1,1 -35590000,0.66,-0.0012,0.016,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00092,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.31,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,4e-06,0.0004,6.2e-06,5.9e-06,0.0004,1,1 -35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.046,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.33,0.44,0.011,0.79,0.9,0.049,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1 -35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.36,0.48,0.01,0.86,1,0.048,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1 -35890000,0.66,-0.0013,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.4,0.52,0.01,0.95,1.1,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,5.7e-06,5.3e-06,0.0004,1,1 -35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00094,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.43,0.56,0.0097,1,1.2,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.6e-06,5.1e-06,0.0004,1,1 -36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00096,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.46,0.6,0.0093,1.2,1.4,0.046,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.5e-06,5e-06,0.0004,1,1 -36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.5,0.65,0.009,1.3,1.5,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.4e-06,4.8e-06,0.0004,1,1 -36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.53,0.69,0.0088,1.4,1.7,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.3e-06,4.7e-06,0.0004,1,1 -36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.57,0.74,0.0086,1.6,1.9,0.044,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.2e-06,4.6e-06,0.0004,1,1 -36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.61,0.79,0.0083,1.7,2.1,0.043,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.0004,5.2e-06,4.5e-06,0.0004,1,1 -36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.65,0.84,0.0082,1.9,2.4,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5.1e-06,4.4e-06,0.0004,1,1 -36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.69,0.89,0.0081,2.1,2.6,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.3e-06,0.0004,1,1 -36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.74,0.94,0.0079,2.3,2.9,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.2e-06,0.0004,1,1 -36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.78,1,0.0078,2.6,3.2,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4.1e-06,0.0004,1,1 -36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.82,1.1,0.0077,2.8,3.6,0.04,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1 -37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.87,1.1,0.0076,3.1,4,0.04,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 -37190000,0.66,-0.0014,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.92,1.2,0.0076,3.4,4.4,0.039,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 -37290000,0.66,-0.0015,0.017,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.97,1.2,0.0075,3.7,4.8,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.8e-06,0.0004,1,1 -37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,1,1.3,0.0075,4.1,5.3,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 -37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.4,5.8,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 -37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.9,6.3,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 -37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.2,1.5,0.0074,5.3,6.9,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.6e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 -37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.2,1.5,0.0074,5.8,7.5,0.037,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.5e-06,0.0004,1,1 -37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.6,0.0074,6.3,8.2,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 -37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.7,0.0074,6.8,8.9,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 -38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.7,0.0074,7.4,9.6,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.5e-06,3.4e-06,0.0004,1,1 -38190000,0.66,-0.0016,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0074,8,10,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 -38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.6,11,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 -38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,9.3,12,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 -38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.07,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,10,13,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 -38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.1,0.0075,11,14,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 -38690000,0.66,-0.0016,0.017,0.75,-4.3,-4.1,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.2,0.0075,12,15,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1 -38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00026,0.0016,1.8,2.3,0.0075,12,16,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 -38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.9,2.3,0.0075,13,17,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 +10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2190000,1,-0.011,-0.014,5.9e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2590000,1,-0.011,-0.013,5.9e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2790000,1,-0.011,-0.013,4.9e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2890000,1,-0.011,-0.013,-1.1e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3090000,1,-0.011,-0.013,4.9e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3190000,1,-0.011,-0.013,-8e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3290000,1,-0.011,-0.013,3.2e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3390000,1,-0.011,-0.012,3.2e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3490000,1,-0.011,-0.013,-4.5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3590000,1,-0.011,-0.012,1.9e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4290000,1,-0.01,-0.012,8.1e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4690000,1,-0.01,-0.012,0.00019,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4790000,1,-0.01,-0.012,0.00018,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5690000,1,-0.0096,-0.011,0.00033,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6090000,1,-0.0094,-0.011,0.00031,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6290000,1,-0.0094,-0.011,0.00021,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6390000,1,-0.0093,-0.011,0.00023,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,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 +6590000,1,-0.0094,-0.011,0.00016,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,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 +6690000,1,-0.0093,-0.011,9e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,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 +6790000,0.78,-0.024,0.005,-0.63,-0.22,-0.047,-0.11,-0.13,-0.028,-3.7e+02,-0.00035,-0.011,-0.0002,0,0,0.0012,-0.092,-0.02,0.51,-0.00079,-0.075,-0.061,0,0,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 +6890000,0.78,-0.025,0.0059,-0.63,-0.27,-0.062,-0.12,-0.16,-0.038,-3.7e+02,-0.00018,-0.011,-0.00022,0,0,0.0013,-0.1,-0.022,0.51,-0.0012,-0.083,-0.067,0,0,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00089,0.0014,0.0013,1,1 +6990000,0.78,-0.025,0.0061,-0.63,-0.3,-0.073,-0.12,-0.2,-0.048,-3.7e+02,-7.9e-05,-0.011,-0.00022,-0.00057,-6.5e-05,0.00098,-0.1,-0.022,0.5,-0.0016,-0.084,-0.067,0,0,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1 +7090000,0.78,-0.025,0.0064,-0.63,-0.33,-0.084,-0.12,-0.23,-0.06,-3.7e+02,3.5e-05,-0.011,-0.00023,-0.0013,-0.00028,0.00063,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00083,0.0014,0.0013,1,1 +7190000,0.78,-0.025,0.0066,-0.63,-0.36,-0.093,-0.15,-0.27,-0.071,-3.7e+02,0.0001,-0.011,-0.00023,-0.0017,-0.00044,0.00086,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00082,0.0013,0.0013,1,1 +7290000,0.78,-0.025,0.0068,-0.63,-0.38,-0.094,-0.14,-0.3,-0.078,-3.7e+02,4.4e-05,-0.011,-0.00022,-0.0016,-0.0004,0.00018,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1 +7390000,0.78,-0.024,0.007,-0.63,-0.41,-0.1,-0.16,-0.34,-0.089,-3.7e+02,6.5e-05,-0.011,-0.00022,-0.0017,-0.00044,2.8e-05,-0.1,-0.023,0.5,-0.0018,-0.085,-0.068,0,0,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00081,0.0013,0.0013,1,1 +7490000,0.78,-0.024,0.007,-0.63,-0.43,-0.11,-0.16,-0.38,-0.11,-3.7e+02,0.0002,-0.011,-0.00023,-0.0019,-0.00051,-0.00073,-0.1,-0.023,0.5,-0.0019,-0.085,-0.069,0,0,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1 +7590000,0.78,-0.024,0.0071,-0.63,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00019,-0.011,-0.00022,-0.0018,-0.00049,-0.0016,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1 +7690000,0.78,-0.024,0.0072,-0.63,0,0,-0.16,-0.46,-0.14,-3.7e+02,0.00028,-0.011,-0.00022,-0.002,-0.00046,-0.0036,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0013,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.0008,0.0013,0.0013,1,1 +7790000,0.78,-0.024,0.0074,-0.63,-0.028,-0.004,-0.16,-0.46,-0.14,-3.7e+02,0.00034,-0.011,-0.00023,-0.002,-0.00046,-0.0056,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00079,0.0013,0.0013,1,1 +7890000,0.78,-0.024,0.0074,-0.63,-0.053,-0.0088,-0.15,-0.46,-0.14,-3.7e+02,0.00038,-0.011,-0.00022,-0.002,-0.00046,-0.0081,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.11,1e+02,1e+02,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00079,0.0013,0.0013,1,1 +7990000,0.78,-0.024,0.0074,-0.63,-0.079,-0.013,-0.16,-0.47,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.002,-0.00046,-0.0093,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00079,0.0013,0.0013,1,1 +8090000,0.78,-0.024,0.0072,-0.63,-0.1,-0.018,-0.17,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.0095,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,52,52,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00079,0.0013,0.0013,1,1 +8190000,0.78,-0.024,0.0074,-0.63,-0.13,-0.021,-0.18,-0.48,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.012,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,25,0.099,35,35,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.4e-05,0.0013,0.00078,0.0013,0.0013,1,1 +8290000,0.78,-0.024,0.0074,-0.63,-0.15,-0.026,-0.17,-0.49,-0.14,-3.7e+02,0.00052,-0.01,-0.00021,-0.002,-0.00046,-0.016,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,25,25,0.097,37,37,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00078,0.0013,0.0013,1,1 +8390000,0.78,-0.024,0.0072,-0.63,-0.17,-0.031,-0.17,-0.5,-0.14,-3.7e+02,0.00054,-0.01,-0.00021,-0.002,-0.00046,-0.019,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.1e-05,0.0013,0.00078,0.0013,0.0013,1,1 +8490000,0.78,-0.023,0.0072,-0.63,-0.2,-0.036,-0.17,-0.51,-0.15,-3.7e+02,0.00055,-0.0099,-0.0002,-0.002,-0.00046,-0.024,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.096,31,31,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00077,0.0013,0.0013,1,1 +8590000,0.78,-0.023,0.0074,-0.63,-0.21,-0.033,-0.17,-0.52,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.002,-0.00046,-0.028,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.095,25,25,0.088,5.7e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.9e-05,0.0013,0.00077,0.0013,0.0013,1,1 +8690000,0.78,-0.023,0.007,-0.63,-0.23,-0.038,-0.16,-0.54,-0.15,-3.7e+02,0.00037,-0.0096,-0.00019,-0.002,-0.00046,-0.033,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,28,28,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.8e-05,0.0013,0.00077,0.0013,0.0013,1,1 +8790000,0.78,-0.023,0.0071,-0.63,-0.24,-0.041,-0.15,-0.54,-0.15,-3.7e+02,0.00039,-0.0095,-0.00019,-0.002,-0.00046,-0.039,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.096,24,24,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,7.7e-05,0.0013,0.00076,0.0013,0.0013,1,1 +8890000,0.78,-0.023,0.007,-0.63,-0.26,-0.045,-0.15,-0.56,-0.16,-3.7e+02,0.00039,-0.0094,-0.00018,-0.002,-0.00046,-0.043,-0.1,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.095,26,26,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0013,7.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 +8990000,0.78,-0.023,0.007,-0.63,-0.28,-0.05,-0.14,-0.59,-0.16,-3.7e+02,0.00044,-0.0093,-0.00018,-0.0021,-0.00036,-0.049,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.096,29,29,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0013,7.6e-05,0.0013,0.00075,0.0013,0.0013,1,1 +9090000,0.78,-0.022,0.007,-0.63,-0.3,-0.05,-0.14,-0.61,-0.17,-3.7e+02,0.00036,-0.0092,-0.00018,-0.0021,-0.00019,-0.052,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.095,33,33,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0013,7.5e-05,0.0013,0.00075,0.0013,0.0013,1,1 +9190000,0.77,-0.022,0.0063,-0.63,-0.3,-0.06,-0.14,-0.63,-0.18,-3.7e+02,0.00037,-0.0088,-0.00017,-0.0019,4e-05,-0.055,-0.11,-0.023,0.5,-0.0027,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.094,37,37,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,7.4e-05,0.0013,0.00074,0.0013,0.0013,1,1 +9290000,0.77,-0.022,0.006,-0.63,-0.32,-0.068,-0.14,-0.66,-0.19,-3.7e+02,0.0004,-0.0086,-0.00016,-0.002,0.00028,-0.059,-0.11,-0.023,0.5,-0.0028,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,41,41,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1 +9390000,0.77,-0.022,0.0059,-0.63,-0.34,-0.077,-0.13,-0.69,-0.2,-3.7e+02,0.00042,-0.0085,-0.00016,-0.0021,0.00046,-0.063,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,46,46,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1 +9490000,0.77,-0.022,0.0054,-0.63,-0.34,-0.09,-0.13,-0.71,-0.21,-3.7e+02,0.00045,-0.0082,-0.00015,-0.002,0.00072,-0.067,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.091,51,51,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1 +9590000,0.77,-0.022,0.0051,-0.63,-0.35,-0.089,-0.13,-0.73,-0.22,-3.7e+02,0.0003,-0.008,-0.00014,-0.002,0.001,-0.07,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0013,0.054,21,21,0.09,57,57,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1 +9690000,0.77,-0.022,0.0053,-0.63,-0.37,-0.086,-0.12,-0.77,-0.22,-3.7e+02,0.00022,-0.0081,-0.00014,-0.0022,0.0012,-0.075,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.089,63,63,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1 +9790000,0.77,-0.022,0.0049,-0.63,-0.37,-0.099,-0.11,-0.79,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0023,0.0016,-0.081,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.087,69,69,0.085,3.1e-05,3.4e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1 +9890000,0.77,-0.021,0.0047,-0.63,-0.38,-0.1,-0.11,-0.82,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0023,0.0018,-0.083,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,22,0.084,76,76,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7e-05,0.0013,0.00072,0.0013,0.0013,1,1 +9990000,0.77,-0.021,0.0047,-0.63,-0.4,-0.1,-0.1,-0.85,-0.25,-3.7e+02,9.4e-05,-0.0077,-0.00013,-0.0025,0.002,-0.087,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,22,22,0.083,83,83,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1 +10090000,0.77,-0.021,0.0044,-0.63,-0.4,-0.099,-0.096,-0.87,-0.26,-3.7e+02,-1.2e-05,-0.0075,-0.00012,-0.0025,0.0022,-0.09,-0.11,-0.023,0.5,-0.003,-0.088,-0.069,0,0,0.0011,0.0012,0.054,22,22,0.08,91,91,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1 +10190000,0.77,-0.021,0.0047,-0.63,-0.42,-0.097,-0.096,-0.92,-0.26,-3.7e+02,-4.4e-05,-0.0076,-0.00012,-0.0025,0.0022,-0.091,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.078,99,99,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,6.9e-05,0.0013,0.00071,0.0013,0.0013,1,1 +10290000,0.77,-0.021,0.0049,-0.63,-0.44,-0.096,-0.083,-0.96,-0.27,-3.7e+02,-7.1e-05,-0.0076,-0.00012,-0.0028,0.0025,-0.097,-0.11,-0.023,0.5,-0.0028,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.076,1.1e+02,1.1e+02,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10390000,0.77,-0.021,0.0047,-0.63,-0.0086,-0.022,0.0097,7.7e-05,-0.0019,-3.7e+02,-6e-05,-0.0075,-0.00012,-0.0028,0.0027,-0.1,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10490000,0.77,-0.021,0.0048,-0.63,-0.028,-0.024,0.023,-0.0017,-0.0042,-3.7e+02,-8.3e-05,-0.0075,-0.00012,-0.0029,0.0028,-0.1,-0.11,-0.024,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10590000,0.77,-0.02,0.0045,-0.63,-0.026,-0.013,0.026,0.0015,-0.0009,-3.7e+02,-0.00027,-0.0074,-0.00011,-0.0021,0.0027,-0.1,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10690000,0.77,-0.02,0.0044,-0.63,-0.043,-0.014,0.03,-0.002,-0.0023,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0021,0.0028,-0.11,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 +10790000,0.77,-0.02,0.004,-0.63,-0.04,-0.0098,0.024,0.001,-0.001,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00033,0.0016,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.001,0.001,0.054,0.091,0.092,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 +10890000,0.77,-0.02,0.0039,-0.63,-0.057,-0.012,0.02,-0.0037,-0.0022,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.00027,0.0017,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.00098,0.00098,0.053,0.099,0.1,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 +10990000,0.77,-0.02,0.0031,-0.63,-0.048,-0.0092,0.015,0.00014,-0.0011,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0035,-0.0006,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00093,0.00093,0.053,0.078,0.079,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 +11090000,0.77,-0.02,0.0028,-0.63,-0.06,-0.013,0.02,-0.0047,-0.0024,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0035,-0.00017,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0013,1,1 +11190000,0.77,-0.019,0.0023,-0.63,-0.054,-0.0091,0.0082,0.0007,-0.00036,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.008,-0.0035,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00085,0.00085,0.053,0.073,0.074,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0013,1,1 +11290000,0.77,-0.019,0.0024,-0.63,-0.069,-0.011,0.008,-0.0057,-0.0014,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0081,-0.0036,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.069,0,0,0.00084,0.00084,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0013,1,1 +11390000,0.78,-0.019,0.002,-0.63,-0.064,-0.0096,0.0024,0.00035,-0.00029,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.068,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0012,1,1 +11490000,0.78,-0.019,0.0022,-0.63,-0.078,-0.011,0.0032,-0.0072,-0.0011,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.024,0.5,-0.0032,-0.089,-0.07,0,0,0.00075,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0012,1,1 +11590000,0.78,-0.019,0.0017,-0.63,-0.069,-0.011,-0.0027,-0.0022,-0.00067,-3.7e+02,-0.0006,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0033,-0.089,-0.07,0,0,0.00067,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11690000,0.78,-0.019,0.0018,-0.63,-0.08,-0.014,-0.0071,-0.0098,-0.0021,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0034,-0.089,-0.07,0,0,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11790000,0.78,-0.019,0.0012,-0.63,-0.072,-0.0097,-0.0089,-0.0061,-4.1e-05,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.00061,0.051,0.065,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11890000,0.78,-0.019,0.0013,-0.63,-0.084,-0.01,-0.0098,-0.014,-0.001,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.0006,0.051,0.075,0.076,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11990000,0.78,-0.019,0.00071,-0.63,-0.072,-0.0052,-0.015,-0.009,0.0011,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00052,0.00053,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8.1e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.8e-05,0.0013,0.00066,0.0013,0.0012,1,1 +12090000,0.78,-0.018,0.00055,-0.63,-0.078,-0.0073,-0.021,-0.016,0.00038,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00051,0.00053,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.5e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.8e-05,0.0013,0.00066,0.0013,0.0012,1,1 +12190000,0.78,-0.018,-0.00013,-0.63,-0.064,-0.0098,-0.016,-0.0085,-0.00012,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.8e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12290000,0.78,-0.018,-0.00015,-0.63,-0.07,-0.012,-0.015,-0.015,-0.0016,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.071,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.6e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.8e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12390000,0.78,-0.018,-0.00055,-0.63,-0.057,-0.01,-0.013,-0.0083,-0.00071,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.5e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.7e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12490000,0.78,-0.018,-0.00042,-0.63,-0.064,-0.012,-0.016,-0.015,-0.0018,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.037,-0.027,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00041,0.05,0.068,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.7e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12590000,0.78,-0.018,-0.00062,-0.63,-0.06,-0.01,-0.022,-0.013,-0.00071,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00036,0.00037,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.9e-06,6.4e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12690000,0.78,-0.018,-0.00055,-0.63,-0.065,-0.0094,-0.025,-0.019,-0.00092,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.024,0.5,-0.0035,-0.091,-0.07,0,0,0.00035,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.7e-06,6.2e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12790000,0.78,-0.018,-0.00083,-0.63,-0.061,-0.0086,-0.029,-0.017,-0.00085,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12890000,0.78,-0.018,-0.00082,-0.63,-0.068,-0.0098,-0.028,-0.024,-0.0022,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.2e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12990000,0.78,-0.018,-0.0013,-0.63,-0.055,-0.0092,-0.028,-0.018,-0.0022,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.054,0.055,0.025,0.057,0.057,0.052,4.9e-06,5.4e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 +13090000,0.78,-0.018,-0.0012,-0.63,-0.061,-0.009,-0.028,-0.024,-0.0029,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.7e-05,0.0012,0.00065,0.0012,0.0012,1,1 +13190000,0.78,-0.018,-0.0015,-0.63,-0.049,-0.0085,-0.025,-0.017,-0.0023,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.035,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00027,0.00028,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13290000,0.78,-0.018,-0.0016,-0.63,-0.053,-0.011,-0.022,-0.022,-0.0043,-3.7e+02,-0.00094,-0.0062,-8.2e-05,0.049,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00026,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.018,0.0091,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13390000,0.78,-0.018,-0.0018,-0.63,-0.044,-0.011,-0.018,-0.016,-0.0036,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13490000,0.78,-0.018,-0.0019,-0.63,-0.047,-0.012,-0.016,-0.021,-0.0051,-3.7e+02,-0.00097,-0.0062,-8e-05,0.051,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.5e-06,2.3e-06,0.017,0.017,0.0087,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13590000,0.78,-0.018,-0.002,-0.63,-0.038,-0.011,-0.019,-0.014,-0.0037,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13690000,0.78,-0.018,-0.0021,-0.63,-0.041,-0.014,-0.023,-0.018,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.8e-06,4.2e-06,2.3e-06,0.016,0.017,0.0083,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13790000,0.78,-0.018,-0.0023,-0.63,-0.03,-0.012,-0.024,-0.0066,-0.0043,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13890000,0.78,-0.018,-0.0023,-0.63,-0.033,-0.014,-0.029,-0.01,-0.0061,-3.7e+02,-0.00099,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00021,0.00022,0.049,0.048,0.048,0.03,0.079,0.08,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13990000,0.78,-0.018,-0.0025,-0.63,-0.025,-0.013,-0.028,-0.0036,-0.0053,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.4e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 +14090000,0.78,-0.018,-0.0025,-0.63,-0.026,-0.014,-0.029,-0.0058,-0.0068,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.055,-0.037,-0.12,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00019,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.3e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,6.7e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14190000,0.78,-0.017,-0.0027,-0.63,-0.021,-0.012,-0.031,-0.00022,-0.0047,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.013,0.014,0.0069,0.0012,6.7e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14290000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.014,-0.03,-0.0022,-0.006,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.036,-0.12,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3.1e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,6.7e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14390000,0.78,-0.017,-0.0029,-0.63,-0.017,-0.014,-0.032,0.0018,-0.0047,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.059,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14490000,0.78,-0.017,-0.0029,-0.63,-0.019,-0.017,-0.035,-0.00046,-0.0066,-3.7e+02,-0.001,-0.006,-7.4e-05,0.061,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.9e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14590000,0.78,-0.017,-0.0028,-0.63,-0.02,-0.017,-0.035,-0.0013,-0.0063,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.062,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00017,0.00018,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14690000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.032,-0.0035,-0.0082,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00018,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14790000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.028,-0.0036,-0.0076,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.019,-0.031,-0.0061,-0.0095,-3.7e+02,-0.00097,-0.006,-7.3e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14990000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.027,-0.0046,-0.0074,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.011,0.012,0.0048,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +15090000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.03,-0.0072,-0.009,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +15190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.015,-0.027,-0.0058,-0.0073,-3.7e+02,-0.00096,-0.006,-7.5e-05,0.066,-0.038,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 +15290000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.017,-0.025,-0.0081,-0.0089,-3.7e+02,-0.00097,-0.006,-7.3e-05,0.066,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15390000,0.78,-0.017,-0.0029,-0.63,-0.025,-0.017,-0.023,-0.0076,-0.0091,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.066,-0.036,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15490000,0.78,-0.017,-0.0028,-0.63,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.5e-06,2.4e-06,0.011,0.011,0.0037,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15590000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.022,-0.0097,-0.0098,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.01,0.011,0.0035,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15690000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15790000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.015,-0.025,-0.0085,-0.0096,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.3e-06,2.4e-06,0.01,0.011,0.0031,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15890000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.0099,0.011,0.003,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.016,-0.018,-0.0079,-0.0099,-3.7e+02,-0.001,-0.006,-7.1e-05,0.065,-0.037,-0.13,-0.11,-0.024,0.5,-0.004,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0028,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16090000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0096,0.01,0.0027,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16190000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.014,-0.0074,-0.0092,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.064,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0094,0.01,0.0025,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16290000,0.78,-0.017,-0.003,-0.63,-0.026,-0.018,-0.015,-0.0099,-0.011,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.065,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0093,0.01,0.0024,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16390000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.014,-0.014,-0.0074,-0.0088,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0022,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16490000,0.78,-0.017,-0.0029,-0.63,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0091,0.01,0.0021,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16590000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.012,-0.018,-0.0097,-0.0063,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.9e-06,2.4e-06,0.0089,0.0098,0.002,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16690000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.012,-0.014,-0.012,-0.0073,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.0088,0.0097,0.0019,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0091,-0.013,-0.012,-0.004,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0087,0.0096,0.0018,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16890000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.01,-0.01,-0.014,-0.0048,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0086,0.0095,0.0017,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0099,-0.0099,-0.013,-0.0047,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.062,-0.037,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0085,0.0094,0.0016,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +17090000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.012,-0.0098,-0.015,-0.0057,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0084,0.0093,0.0015,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +17190000,0.78,-0.017,-0.0028,-0.63,-0.023,-0.014,-0.011,-0.014,-0.006,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.4e-06,1.6e-06,2.4e-06,0.0083,0.0092,0.0015,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +17290000,0.78,-0.017,-0.0027,-0.63,-0.026,-0.015,-0.0061,-0.016,-0.0071,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0083,0.0091,0.0014,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 +17390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.017,-0.0042,-0.013,-0.0073,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.091,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0082,0.009,0.0013,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17490000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.018,-0.0025,-0.016,-0.0092,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0081,0.0089,0.0013,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17590000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.018,0.003,-0.014,-0.0088,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.008,0.0088,0.0012,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17690000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.5e-06,2.4e-06,0.0079,0.0087,0.0011,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.06,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.0011,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.022,0.0012,-0.017,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.001,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17990000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0077,0.0085,0.00099,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18090000,0.78,-0.017,-0.0028,-0.63,-0.027,-0.02,0.0047,-0.018,-0.015,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00096,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0083,0.0009,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18290000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.019,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0075,0.0082,0.00087,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.02,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0082,0.00083,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18490000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0081,-0.014,-0.014,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0081,0.0008,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18590000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.022,0.0062,-0.011,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0073,0.008,0.00076,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18690000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0072,0.008,0.00074,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18790000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.0007,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18890000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.023,0.0046,-0.014,-0.015,-3.7e+02,-0.0013,-0.006,-3.9e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.00068,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18990000,0.78,-0.016,-0.0029,-0.63,-0.019,-0.023,0.0033,-0.0094,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.00065,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19090000,0.78,-0.016,-0.0028,-0.63,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.007,0.0077,0.00063,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19190000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.024,0.0063,-0.0074,-0.013,-3.7e+02,-0.0013,-0.006,-3.1e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0069,0.0076,0.0006,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19290000,0.78,-0.016,-0.0029,-0.63,-0.016,-0.024,0.0091,-0.0091,-0.015,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.0069,0.0076,0.00058,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19390000,0.78,-0.016,-0.0028,-0.63,-0.015,-0.022,0.013,-0.0081,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.0068,0.0075,0.00056,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19490000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.023,0.0093,-0.0097,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0068,0.0075,0.00055,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19590000,0.78,-0.016,-0.003,-0.63,-0.014,-0.022,0.0085,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,-1.9e-05,0.06,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,8e-07,9.7e-07,2.3e-06,0.0067,0.0074,0.00052,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19690000,0.78,-0.016,-0.003,-0.63,-0.014,-0.02,0.01,-0.0091,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.9e-07,9.6e-07,2.3e-06,0.0067,0.0074,0.00051,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +19790000,0.78,-0.016,-0.003,-0.63,-0.012,-0.018,0.01,-0.0077,-0.015,-3.7e+02,-0.0013,-0.006,-1.7e-05,0.058,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0066,0.0073,0.00049,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +19890000,0.78,-0.016,-0.003,-0.63,-0.012,-0.02,0.012,-0.0093,-0.018,-3.7e+02,-0.0013,-0.0059,-1.3e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0031,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0066,0.0073,0.00048,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +19990000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.02,0.014,-0.0081,-0.016,-3.7e+02,-0.0013,-0.0059,-4.6e-06,0.06,-0.031,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0066,0.0072,0.00046,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20090000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.021,0.015,-0.0088,-0.019,-3.7e+02,-0.0013,-0.0059,1.3e-07,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0065,0.0072,0.00045,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20190000,0.78,-0.016,-0.0032,-0.63,-0.01,-0.019,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,6.1e-06,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0065,0.0071,0.00043,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20290000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.019,0.015,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,7.8e-06,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0064,0.0071,0.00042,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20390000,0.78,-0.016,-0.0032,-0.63,-0.0087,-0.016,0.017,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0064,0.007,0.00041,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20490000,0.78,-0.016,-0.0032,-0.63,-0.0089,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,1e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0064,0.007,0.0004,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20590000,0.78,-0.016,-0.0032,-0.63,-0.0084,-0.014,0.014,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0063,0.0069,0.00038,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20690000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.015,0.015,-0.0096,-0.018,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0063,0.0069,0.00037,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20790000,0.78,-0.016,-0.0032,-0.63,-0.0068,-0.014,0.015,-0.008,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0062,0.0068,0.00036,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20890000,0.78,-0.016,-0.0033,-0.63,-0.007,-0.014,0.014,-0.0086,-0.018,-3.7e+02,-0.0013,-0.0059,2.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0062,0.0068,0.00035,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20990000,0.78,-0.016,-0.0033,-0.63,-0.0054,-0.012,0.015,-0.0083,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0062,0.0067,0.00034,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21090000,0.78,-0.016,-0.0033,-0.63,-0.0065,-0.012,0.015,-0.0092,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0061,0.0067,0.00034,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21190000,0.78,-0.016,-0.0033,-0.63,-0.0066,-0.011,0.014,-0.0097,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.4e-07,2.3e-06,0.0061,0.0067,0.00033,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21290000,0.78,-0.016,-0.0034,-0.63,-0.0062,-0.012,0.016,-0.0097,-0.022,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,9.3e-05,9.8e-05,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0061,0.0066,0.00032,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21390000,0.78,-0.016,-0.0034,-0.63,-0.0055,-0.0074,0.016,-0.0085,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.006,0.0066,0.00031,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21490000,0.78,-0.016,-0.0034,-0.63,-0.0061,-0.0083,0.016,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21590000,0.78,-0.016,-0.0034,-0.63,-0.0047,-0.0066,0.016,-0.008,-0.014,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21690000,0.78,-0.016,-0.0034,-0.63,-0.0063,-0.0077,0.017,-0.0093,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.0059,0.0065,0.00029,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21790000,0.78,-0.016,-0.0032,-0.63,-0.0054,-0.0054,0.016,-0.0081,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21890000,0.78,-0.016,-0.0033,-0.63,-0.006,-0.0063,0.016,-0.0088,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21990000,0.78,-0.016,-0.0032,-0.63,-0.0059,-0.0035,0.017,-0.0082,-0.0069,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0058,0.0064,0.00027,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 +22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22190000,0.78,-0.016,-0.0032,-0.63,-0.0043,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22490000,0.78,-0.016,-0.0033,-0.63,-0.00016,-0.006,0.018,-0.0055,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0056,0.02,-0.0026,-0.0059,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0057,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0048,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00046,-0.043,-0.0096,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.048,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00037,-0.00011,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00053,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.044,-0.4,0.0006,0.0037,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0069,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,6.3e-05,0.0012,0.00059,0.0011,0.0012,1,1 +24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,6.3e-05,0.0012,0.00059,0.0011,0.0012,1,1 +24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,6.3e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0068,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.2e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.1e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.9e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,6.1e-05,0.0012,0.00057,0.0011,0.0012,1,1 +25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,6e-05,0.0012,0.00057,0.0011,0.0011,1,1 +25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00062,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,6e-05,0.0011,0.00057,0.0011,0.0011,1,1 +25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.9e-05,0.0011,0.00057,0.0011,0.0011,1,1 +25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1 +25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.061,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,5.7e-05,0.0011,0.00056,0.001,0.0011,1,1 +25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,5.6e-05,0.0011,0.00055,0.001,0.0011,1,1 +26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,5.5e-05,0.0011,0.00055,0.00098,0.0011,1,1 +26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,5.4e-05,0.001,0.00054,0.00094,0.001,1,1 +26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0058,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1 +26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1 +26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0066,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.9e-05,0.00093,0.0005,0.00084,0.00093,1,1 +26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,4.7e-05,0.00088,0.00048,0.0008,0.00088,1,1 +26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,4.4e-05,0.00082,0.00045,0.00074,0.00082,1,1 +26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,4.2e-05,0.00078,0.00042,0.00069,0.00077,1,1 +26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,4e-05,0.00073,0.00039,0.00065,0.00073,1,1 +26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00058,3.7e-05,0.00066,0.00036,0.00059,0.00066,1,1 +27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,3.4e-05,0.00059,0.00032,0.00053,0.00059,1,1 +27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.16,-0.036,0.47,-0.0075,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,3.2e-05,0.00055,0.00029,0.00049,0.00054,1,1 +27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,3.1e-05,0.00052,0.00026,0.00046,0.00051,1,1 +27390000,0.76,0.078,-0.033,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,3e-05,0.0005,0.00024,0.00044,0.00049,1,1 +27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.9e-05,0.00049,0.00022,0.00043,0.00048,1,1 +27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.9e-05,0.00048,0.0002,0.00042,0.00048,1,1 +27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.9e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.00041,2.9e-05,0.00048,0.00019,0.00042,0.00047,1,1 +27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.4e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0056,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.8e-05,0.00047,0.00018,0.00041,0.00047,1,1 +27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0056,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.8e-05,0.00047,0.00017,0.0004,0.00047,1,1 +27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0056,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.8e-05,0.00047,0.00016,0.0004,0.00046,1,1 +28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.0051,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2.7e-05,0.00046,0.00015,0.00039,0.00046,1,1 +28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.0051,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2.7e-05,0.00046,0.00015,0.00038,0.00045,1,1 +28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0048,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00014,0.00038,0.00045,1,1 +28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.7e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0046,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00014,0.00037,0.00045,1,1 +28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00045,1,1 +28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.1e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00044,1,1 +28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00044,1,1 +28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.2e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1 +28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1 +28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0039,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1 +29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29390000,0.78,7.3e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.6e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0034,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1 +29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.4e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1 +29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1 +29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00043,1,1 +29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.3e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1 +29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.003,-0.028,-0.027,0,0,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1 +29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1 +30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,0.0001,0.00036,0.00042,1,1 +30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.7e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,9.9e-05,0.00036,0.00042,1,1 +30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.7e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,9.8e-05,0.00036,0.00042,1,1 +30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.5e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.11,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.8e-05,0.00036,0.00042,1,1 +30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.4e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.7e-05,0.00036,0.00042,1,1 +30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-7.1e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.6e-05,0.00036,0.00042,1,1 +30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.6e-05,0.00036,0.00042,1,1 +30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.1e-06,0.075,-0.0097,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.5e-05,0.00036,0.00042,1,1 +30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,2.6e-05,0.00042,9.5e-05,0.00036,0.00042,1,1 +30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,2.6e-05,0.00042,9.4e-05,0.00036,0.00041,1,1 +31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,2.6e-05,0.00042,9.4e-05,0.00036,0.00041,1,1 +31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1 +31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1 +31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1 +31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00035,2.6e-05,0.00042,9.2e-05,0.00036,0.00041,1,1 +31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0039,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1 +31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.6,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1 +31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.0021,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1 +31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0015,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.00041,1,1 +31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00054,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.00041,1,1 +32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00015,-0.11,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.0004,1,1 +32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2.6e-05,0.00041,9.1e-05,0.00036,0.0004,1,1 +32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2.6e-05,0.00041,9e-05,0.00036,0.0004,1,1 +32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2.6e-05,0.00041,9e-05,0.00036,0.0004,1,1 +32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 +32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 +32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 +32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 +32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 +32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1 +33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1 +33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1 +33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.7e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.5e-05,0.0004,8.9e-05,0.00035,0.00039,1,1 +33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.00096,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,2.4e-05,0.0004,8.6e-05,0.00032,0.00039,1,1 +33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00044,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,2.1e-05,0.00039,7.7e-05,0.00024,0.00039,1,1 +33590000,0.99,-0.0082,-2.9e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,1.7e-05,0.00039,6.3e-05,0.00015,0.00039,1,1 +33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.1e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00017,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,1.4e-05,0.00039,5e-05,9.7e-05,0.00038,1,1 +33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00053,-0.0066,-0.025,0,0,0.00015,0.0001,0.0024,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,1.3e-05,0.00038,3.7e-05,6.2e-05,0.00038,1,1 +33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00075,-0.0053,-0.025,0,0,0.00015,0.0001,0.0021,0.04,0.046,0.042,0.32,0.32,0.065,2.8e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5.1e-05,1.2e-05,0.00038,2.8e-05,4.2e-05,0.00038,1,1 +33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.8e-05,0.0018,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,1.1e-05,0.00038,2.1e-05,3e-05,0.00038,1,1 +34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.064,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0017,0.038,0.046,0.033,0.33,0.33,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,1.1e-05,0.00038,1.8e-05,2.4e-05,0.00038,1,1 +34190000,0.75,-0.014,0.0071,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0016,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,1.1e-05,0.00038,1.5e-05,1.9e-05,0.00038,1,1 +34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.7e-05,0.0015,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,1.1e-05,0.00038,1.3e-05,1.6e-05,0.00038,1,1 +34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0041,-0.11,-0.2,-0.044,0.46,8.9e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0015,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.5e-05,1.1e-05,0.00038,1.1e-05,1.4e-05,0.00038,1,1 +34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,4.7e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0014,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.4e-05,1.1e-05,0.00038,1e-05,1.2e-05,0.00038,1,1 +34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0039,-0.11,-0.2,-0.044,0.46,-5e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0014,0.057,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.2e-05,1e-05,0.00038,9.2e-06,1.1e-05,0.00038,1,1 +34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.5e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0014,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.2e-05,1e-05,0.00038,8.5e-06,9.9e-06,0.00038,1,1 +34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0014,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2.1e-05,1e-05,0.00038,7.9e-06,9.1e-06,0.00038,1,1 +34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.7e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0013,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2e-05,1e-05,0.00038,7.4e-06,8.4e-06,0.00038,1,1 +34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0013,0.091,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2e-05,1e-05,0.00038,7.1e-06,7.9e-06,0.00038,1,1 +35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00022,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0013,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.9e-05,1e-05,0.00038,6.7e-06,7.4e-06,0.00038,1,1 +35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00026,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0013,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.9e-05,1e-05,0.00038,6.4e-06,7e-06,0.00038,1,1 +35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0013,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,6.1e-06,6.6e-06,0.00038,1,1 +35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0013,0.13,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,5.9e-06,6.3e-06,0.00038,1,1 +35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00045,-0.0016,-0.025,0,0,0.00013,9.2e-05,0.0013,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,5.7e-06,6e-06,0.00038,1,1 +35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00042,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0013,0.15,0.21,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.5e-06,5.8e-06,0.00038,1,1 +35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00048,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0013,0.16,0.22,0.011,0.69,0.78,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.4e-06,5.6e-06,0.00038,1,1 +35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9.1e-05,0.0013,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.2e-06,5.3e-06,0.00038,1,1 +35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.0005,-0.0015,-0.025,0,0,0.00013,9e-05,0.0013,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.1e-06,5.2e-06,0.00038,1,1 +35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0015,-0.025,0,0,0.00013,9e-05,0.0013,0.19,0.27,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5e-06,5e-06,0.00037,1,1 +36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,9e-05,0.0013,0.21,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,1e-05,0.00038,4.9e-06,4.8e-06,0.00037,1,1 +36190000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0012,0.22,0.3,0.0086,0.97,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.8e-06,4.7e-06,0.00037,1,1 +36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00059,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0012,0.23,0.32,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.7e-06,4.6e-06,0.00037,1,1 +36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0012,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.6e-06,4.4e-06,0.00037,1,1 +36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00055,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.6e-06,4.3e-06,0.00037,1,1 +36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00059,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.28,0.37,0.0076,1.3,1.6,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.5e-06,4.2e-06,0.00037,1,1 +36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.4e-06,4.1e-06,0.00037,1,1 +36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00065,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.4e-06,4e-06,0.00037,1,1 +36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00068,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0012,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.3e-06,3.9e-06,0.00037,1,1 +36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0012,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.3e-06,3.9e-06,0.00037,1,1 +37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.6e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0012,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.8e-06,0.00037,1,1 +37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.6e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0012,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.7e-06,0.00037,1,1 +37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.0007,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.7e-06,0.00037,1,1 +37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00072,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.42,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.6e-06,0.00037,1,1 +37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.5e-06,0.00037,1,1 +37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.5e-06,0.00037,1,1 +37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.0012,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4e-06,3.4e-06,0.00037,1,1 +37790000,0.65,-0.0068,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.0012,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.5e-05,1e-05,0.00038,4e-06,3.4e-06,0.00037,1,1 +37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.068,0.0043,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.52,0.65,0.0065,3.3,4.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.3e-06,0.00037,1,1 +37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.54,0.67,0.0065,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.3e-06,0.00037,1,1 +38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.0012,0.56,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.2e-06,0.00037,1,1 +38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00079,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.58,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.2e-06,0.00037,1,1 +38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00079,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.0012,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.1e-06,0.00037,1,1 +38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0039,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.63,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.1e-06,0.00037,1,1 +38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.65,0.8,0.0065,5,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1 +38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.68,0.82,0.0065,5.4,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1 +38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.7,0.85,0.0065,5.7,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1 +38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00081,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.72,0.88,0.0065,6.1,7.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,2.9e-06,0.00037,1,1 +38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.00081,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.74,0.89,0.0065,6.5,8.2,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.8e-06,2.9e-06,0.00037,1,1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 6cb6d950815c..0ca0e5b75d9f 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -1,351 +1,351 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00054,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,5e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00066,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.9e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.7e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00056,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00049,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.3e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.3e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-7.7e-08,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3.3e-08,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00039,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-7e-09,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.1e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00035,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00039,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-7.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-7.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.3e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2490000,1,-0.011,-0.014,0.00047,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.3e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-1.9e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-1.8e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2790000,1,-0.01,-0.013,0.00037,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2990000,1,-0.01,-0.013,0.00031,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-2.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-2.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3190000,1,-0.01,-0.013,0.00056,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.2e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00021,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.4e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.2e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.4e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,2.9e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,2.9e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.0071,0.00018,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,2.5e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3690000,1,-0.0095,-0.013,0.00052,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,2.5e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00017,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3890000,1,-0.0094,-0.013,0.00063,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,2.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4090000,1,-0.0093,-0.012,0.00076,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-4.8e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.9e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-4.8e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1.9e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4290000,1,-0.0095,-0.012,0.00074,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.3e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,1.7e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,1.7e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4490000,1,-0.0094,-0.012,0.00076,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,1.5e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-5.7e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00016,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,1.5e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4690000,1,-0.0094,-0.012,0.00076,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.1e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4790000,1,-0.0093,-0.012,0.00086,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.1e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4890000,1,-0.0092,-0.012,0.0009,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-6.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-6.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5090000,1,-0.0091,-0.011,0.00096,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-6.8e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-6.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.3e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,9.3e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00013,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.4e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5590000,1,-0.0088,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.4e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.6e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.6e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5990000,1,-0.0088,-0.012,0.00086,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6190000,1,-0.0089,-0.011,0.00068,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6290000,1,-0.0089,-0.011,0.00071,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6390000,1,-0.0089,-0.011,0.00072,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6590000,1,-0.009,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6690000,1,-0.0089,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6790000,1,-0.009,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6890000,1,-0.0088,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6990000,-0.29,0.024,-0.0065,0.96,-0.0055,0.0091,-0.037,0.0023,0.0053,-0.055,-0.0016,-0.0056,-8.7e-05,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0012,0.0012,0.072,0.16,0.16,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1 -7090000,-0.28,0.025,-0.0064,0.96,-0.026,-0.00083,-0.037,0.0022,0.0052,-0.056,-0.0015,-0.0055,-8.7e-05,0,0,-0.13,-0.099,-0.021,0.51,0.075,-0.029,-0.065,0,0,0.0012,0.0012,0.058,0.16,0.16,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00099,0.0013,1,1 -7190000,-0.28,0.026,-0.0064,0.96,-0.047,-0.0082,-0.036,0.00063,0.0038,-0.058,-0.0015,-0.0055,-8.6e-05,3.9e-05,-1e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.054,0.17,0.17,0.029,0.16,0.16,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.00094,0.0013,1,1 -7290000,-0.28,0.026,-0.0064,0.96,-0.07,-0.017,-0.033,-0.0034,0.0023,-0.054,-0.0015,-0.0054,-8.5e-05,0.00011,-5e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.053,0.18,0.18,0.028,0.19,0.19,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00093,0.0013,1,1 -7390000,-0.28,0.026,-0.0062,0.96,-0.091,-0.024,-0.031,-0.0098,-8.5e-05,-0.052,-0.0015,-0.0054,-8.4e-05,0.00016,-4e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.052,0.19,0.19,0.027,0.22,0.22,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00092,0.0013,1,1 -7490000,-0.28,0.026,-0.0062,0.96,-0.11,-0.032,-0.025,-0.015,-0.0034,-0.046,-0.0015,-0.0053,-8.1e-05,0.00033,7.2e-07,-0.13,-0.1,-0.022,0.5,0.077,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.2,0.2,0.026,0.26,0.26,0.063,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1 -7590000,-0.28,0.026,-0.0063,0.96,-0.13,-0.041,-0.021,-0.024,-0.0083,-0.04,-0.0015,-0.0052,-8e-05,0.00045,-2.7e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.22,0.21,0.025,0.3,0.3,0.062,6.6e-05,6.5e-05,4.6e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00091,0.0013,1,1 -7690000,-0.28,0.026,-0.0063,0.96,-0.16,-0.051,-0.02,-0.034,-0.015,-0.036,-0.0014,-0.0051,-7.9e-05,0.00056,-6.8e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.23,0.23,0.025,0.34,0.34,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1 -7790000,-0.28,0.026,-0.0062,0.96,-0.18,-0.061,-0.022,-0.041,-0.025,-0.041,-0.0014,-0.005,-7.8e-05,0.00088,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.26,0.25,0.024,0.39,0.39,0.061,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7890000,-0.28,0.026,-0.0062,0.96,-0.2,-0.071,-0.022,-0.057,-0.033,-0.044,-0.0013,-0.0049,-7.7e-05,0.00099,-0.00028,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.28,0.28,0.023,0.45,0.45,0.06,6.4e-05,6.4e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1 -7990000,-0.28,0.026,-0.0061,0.96,-0.22,-0.078,-0.018,-0.08,-0.039,-0.04,-0.0013,-0.0049,-7.7e-05,0.00089,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.3,0.3,0.022,0.51,0.51,0.059,6.3e-05,6.3e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1 -8090000,-0.28,0.026,-0.006,0.96,-0.25,-0.09,-0.019,-0.1,-0.053,-0.043,-0.0013,-0.0049,-8e-05,0.00093,-0.00038,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.33,0.33,0.022,0.57,0.57,0.059,6.2e-05,6.2e-05,4.6e-06,0.04,0.04,0.0014,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1 -8190000,-0.28,0.026,-0.0061,0.96,-0.27,-0.1,-0.014,-0.12,-0.069,-0.036,-0.0012,-0.0048,-8.2e-05,0.00096,-0.0005,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.36,0.36,0.021,0.64,0.64,0.058,6.1e-05,6.1e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1 -8290000,-0.28,0.026,-0.0061,0.96,-0.3,-0.11,-0.013,-0.16,-0.077,-0.036,-0.0012,-0.005,-8.4e-05,0.0007,-0.00042,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.02,0.72,0.72,0.057,6e-05,6e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1 -8390000,-0.28,0.026,-0.0061,0.96,-0.33,-0.12,-0.011,-0.2,-0.089,-0.034,-0.0012,-0.005,-8.5e-05,0.00063,-0.00041,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.43,0.43,0.02,0.81,0.8,0.057,5.9e-05,5.9e-05,4.6e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8490000,-0.28,0.026,-0.0059,0.96,-0.35,-0.12,-0.012,-0.23,-0.094,-0.039,-0.0013,-0.005,-8.2e-05,0.00062,-0.00029,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.47,0.46,0.019,0.9,0.9,0.056,5.8e-05,5.7e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8590000,-0.28,0.027,-0.0059,0.96,-0.38,-0.14,-0.0073,-0.26,-0.12,-0.034,-0.0012,-0.0049,-8.2e-05,0.00079,-0.00042,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.51,0.51,0.019,1,1,0.055,5.6e-05,5.5e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8690000,-0.28,0.027,-0.0059,0.96,-0.4,-0.14,-0.0089,-0.3,-0.13,-0.035,-0.0012,-0.0049,-8.2e-05,0.00071,-0.00035,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.56,0.55,0.018,1.1,1.1,0.055,5.5e-05,5.4e-05,4.6e-06,0.04,0.04,0.001,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8790000,-0.28,0.027,-0.0059,0.96,-0.43,-0.15,-0.0084,-0.35,-0.14,-0.032,-0.0012,-0.005,-8.5e-05,0.00052,-0.0004,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.61,0.6,0.018,1.2,1.2,0.055,5.3e-05,5.2e-05,4.6e-06,0.04,0.04,0.00099,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8890000,-0.28,0.027,-0.0059,0.96,-0.46,-0.16,-0.0039,-0.38,-0.16,-0.026,-0.0012,-0.0049,-8.1e-05,0.00064,-0.00031,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.66,0.65,0.017,1.4,1.4,0.054,5.1e-05,5e-05,4.5e-06,0.04,0.04,0.00095,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1 -8990000,-0.28,0.027,-0.0058,0.96,-0.47,-0.17,-0.0028,-0.41,-0.17,-0.029,-0.0013,-0.0047,-7.5e-05,0.001,-0.0003,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.72,0.7,0.017,1.5,1.5,0.054,4.9e-05,4.8e-05,4.5e-06,0.04,0.04,0.00091,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9090000,-0.28,0.027,-0.0056,0.96,-0.5,-0.18,-0.0038,-0.47,-0.17,-0.029,-0.0014,-0.0048,-7.2e-05,0.00081,-2.1e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.77,0.76,0.016,1.7,1.7,0.053,4.7e-05,4.6e-05,4.5e-06,0.04,0.04,0.00087,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9190000,-0.28,0.027,-0.0055,0.96,-0.53,-0.18,-0.0029,-0.52,-0.18,-0.029,-0.0015,-0.0048,-6.9e-05,0.0008,0.00012,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.84,0.82,0.016,1.9,1.9,0.052,4.5e-05,4.4e-05,4.5e-06,0.04,0.04,0.00084,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9290000,-0.28,0.027,-0.0054,0.96,-0.56,-0.19,-0.0011,-0.56,-0.21,-0.026,-0.0014,-0.0047,-6.7e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.9,0.88,0.016,2.1,2.1,0.052,4.3e-05,4.2e-05,4.5e-06,0.04,0.04,0.0008,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9390000,-0.28,0.027,-0.0054,0.96,-0.023,-0.0084,0.0003,-0.57,-0.21,-0.026,-0.0013,-0.0047,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.052,4.2e-05,4e-05,4.5e-06,0.04,0.04,0.00077,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9490000,-0.28,0.027,-0.0053,0.96,-0.049,-0.017,0.0021,-0.58,-0.21,-0.023,-0.0014,-0.0048,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.051,4e-05,3.8e-05,4.5e-06,0.04,0.04,0.00074,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9590000,-0.28,0.027,-0.0056,0.96,-0.076,-0.023,0.0023,-0.58,-0.21,-0.024,-0.0012,-0.0048,-8e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,51,51,0.05,3.8e-05,3.7e-05,4.5e-06,0.04,0.04,0.00072,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9690000,-0.28,0.027,-0.0057,0.96,-0.1,-0.031,0.0054,-0.59,-0.21,-0.023,-0.0012,-0.0048,-8.2e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,52,52,0.05,3.6e-05,3.5e-05,4.5e-06,0.04,0.04,0.00069,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9790000,-0.28,0.027,-0.0059,0.96,-0.13,-0.038,0.0041,-0.59,-0.22,-0.023,-0.001,-0.005,-9.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,35,35,0.05,3.4e-05,3.3e-05,4.5e-06,0.04,0.04,0.00067,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9890000,-0.28,0.027,-0.0058,0.96,-0.16,-0.047,0.0057,-0.61,-0.22,-0.023,-0.0011,-0.0049,-8.9e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,37,37,0.049,3.2e-05,3.1e-05,4.5e-06,0.04,0.04,0.00064,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 -9990000,-0.28,0.027,-0.006,0.96,-0.18,-0.051,0.0065,-0.61,-0.22,-0.025,-0.00096,-0.005,-9.6e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.014,28,28,0.049,3.1e-05,3e-05,4.5e-06,0.04,0.04,0.00062,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10090000,-0.28,0.027,-0.0061,0.96,-0.21,-0.054,0.0078,-0.63,-0.23,-0.023,-0.00084,-0.0051,-0.0001,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.013,30,30,0.049,2.9e-05,2.8e-05,4.5e-06,0.04,0.04,0.0006,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10190000,-0.28,0.027,-0.0064,0.96,-0.23,-0.056,0.0087,-0.64,-0.23,-0.024,-0.00067,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,25,25,0.048,2.8e-05,2.7e-05,4.5e-06,0.04,0.04,0.00058,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10290000,-0.28,0.027,-0.0064,0.96,-0.26,-0.065,0.0079,-0.66,-0.23,-0.023,-0.00072,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,27,27,0.048,2.6e-05,2.5e-05,4.5e-06,0.04,0.04,0.00057,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10390000,-0.28,0.028,-0.0063,0.96,-0.012,-0.0081,-0.0025,-7.9e-05,-0.00028,-0.023,-0.00074,-0.0049,-0.0001,0.001,0.00015,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,2.5e-05,2.4e-05,4.5e-06,0.04,0.04,0.00055,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10490000,-0.28,0.027,-0.0064,0.96,-0.041,-0.014,0.0066,-0.0027,-0.0013,-0.018,-0.00066,-0.005,-0.00011,0.00082,2.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,2.4e-05,2.3e-05,4.5e-06,0.04,0.04,0.00054,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10590000,-0.28,0.027,-0.0063,0.96,-0.052,-0.013,0.012,-0.0032,-0.00096,-0.016,-0.00073,-0.005,-0.0001,0.0014,7.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,2.2e-05,2.1e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10690000,-0.28,0.027,-0.0063,0.96,-0.081,-0.018,0.015,-0.0099,-0.0025,-0.013,-0.0007,-0.005,-0.00011,0.0014,2.4e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 -10790000,-0.28,0.027,-0.0062,0.96,-0.079,-0.021,0.013,-7.5e-06,-0.0018,-0.012,-0.00072,-0.005,-0.00011,0.0035,-0.0011,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.095,0.095,0.17,0.13,0.13,0.062,2e-05,1.9e-05,4.5e-06,0.039,0.039,0.00051,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 -10890000,-0.28,0.027,-0.006,0.96,-0.11,-0.03,0.0093,-0.0092,-0.0044,-0.015,-0.00083,-0.005,-0.0001,0.0036,-0.00084,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 -10990000,-0.28,0.026,-0.006,0.96,-0.096,-0.031,0.016,-0.0034,-0.0023,-0.0093,-0.00085,-0.0052,-0.00011,0.0077,-0.0021,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.083,0.083,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 -11090000,-0.28,0.027,-0.0064,0.96,-0.12,-0.039,0.019,-0.014,-0.0055,-0.0055,-0.00072,-0.0052,-0.00011,0.0078,-0.0025,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.096,0.097,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,4.5e-06,0.039,0.039,0.00049,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 -11190000,-0.28,0.025,-0.0065,0.96,-0.1,-0.034,0.026,-0.0065,-0.0031,0.00085,-0.00071,-0.0053,-0.00011,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.079,0.079,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 -11290000,-0.28,0.025,-0.0066,0.96,-0.13,-0.038,0.025,-0.018,-0.0066,0.00091,-0.00071,-0.0054,-0.00012,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.094,0.094,0.077,0.078,0.078,0.069,1.5e-05,1.4e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 -11390000,-0.28,0.024,-0.0065,0.96,-0.11,-0.032,0.016,-0.01,-0.004,-0.008,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.078,0.078,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.8e-05,0.0013,0.0012,0.00085,0.0013,1,1 -11490000,-0.28,0.024,-0.0064,0.96,-0.13,-0.036,0.021,-0.022,-0.0074,-0.002,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.093,0.093,0.057,0.069,0.069,0.067,1.3e-05,1.3e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1 -11590000,-0.28,0.023,-0.0065,0.96,-0.11,-0.029,0.019,-0.013,-0.0046,-0.0033,-0.00079,-0.0056,-0.00012,0.027,-0.0085,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00098,0.048,0.077,0.077,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 -11690000,-0.28,0.022,-0.0065,0.96,-0.12,-0.035,0.019,-0.024,-0.0078,-0.0047,-0.00081,-0.0057,-0.00012,0.027,-0.0083,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00099,0.048,0.092,0.092,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 -11790000,-0.28,0.021,-0.0063,0.96,-0.097,-0.033,0.02,-0.014,-0.0064,-0.0019,-0.0009,-0.0057,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00091,0.00087,0.048,0.076,0.076,0.037,0.053,0.053,0.063,1.1e-05,1.1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 -11890000,-0.28,0.021,-0.0065,0.96,-0.11,-0.037,0.018,-0.024,-0.0097,-0.0012,-0.00088,-0.0058,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00091,0.00087,0.048,0.089,0.089,0.034,0.06,0.06,0.063,1.1e-05,1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 -11990000,-0.28,0.02,-0.0066,0.96,-0.091,-0.028,0.015,-0.017,-0.0064,-0.005,-0.0009,-0.0059,-0.00012,0.039,-0.011,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.076,0.076,0.03,0.062,0.062,0.061,1e-05,9.8e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1 -12090000,-0.28,0.02,-0.0066,0.96,-0.1,-0.03,0.019,-0.027,-0.0092,0.0011,-0.00086,-0.0058,-0.00012,0.039,-0.012,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.089,0.088,0.027,0.071,0.071,0.06,9.8e-06,9.3e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00081,0.0013,1,1 -12190000,-0.28,0.019,-0.0067,0.96,-0.084,-0.018,0.018,-0.014,-0.0032,0.0029,-0.00082,-0.0059,-0.00012,0.045,-0.013,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.07,0.07,0.024,0.057,0.057,0.058,9.2e-06,8.8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 -12290000,-0.28,0.019,-0.0068,0.96,-0.09,-0.017,0.017,-0.023,-0.0048,0.004,-0.00079,-0.0059,-0.00012,0.045,-0.014,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.081,0.081,0.022,0.065,0.065,0.058,8.9e-06,8.5e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 -12390000,-0.28,0.019,-0.0068,0.96,-0.073,-0.012,0.015,-0.013,-0.0027,-0.002,-0.00078,-0.0059,-0.00012,0.048,-0.015,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00066,0.00063,0.047,0.066,0.065,0.02,0.054,0.054,0.056,8.4e-06,8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 -12490000,-0.28,0.019,-0.0069,0.96,-0.081,-0.013,0.019,-0.021,-0.004,9.6e-05,-0.00076,-0.0059,-0.00013,0.048,-0.016,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00066,0.00064,0.047,0.075,0.075,0.018,0.062,0.062,0.055,8.1e-06,7.7e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 -12590000,-0.28,0.018,-0.0068,0.96,-0.065,-0.011,0.021,-0.01,-0.0039,0.0019,-0.00076,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00058,0.047,0.061,0.061,0.017,0.052,0.052,0.054,7.7e-06,7.4e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 -12690000,-0.28,0.018,-0.0067,0.96,-0.072,-0.0098,0.02,-0.017,-0.0049,0.0035,-0.00075,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00059,0.047,0.069,0.069,0.015,0.059,0.059,0.053,7.4e-06,7e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 -12790000,-0.28,0.018,-0.0065,0.96,-0.056,-0.015,0.022,-0.01,-0.0078,0.0057,-0.00082,-0.0059,-0.00013,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.061,0.061,0.014,0.061,0.061,0.051,7.1e-06,6.7e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 -12890000,-0.28,0.018,-0.0065,0.96,-0.061,-0.016,0.023,-0.016,-0.0096,0.0088,-0.00084,-0.0059,-0.00012,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.069,0.069,0.013,0.07,0.07,0.051,6.8e-06,6.5e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 -12990000,-0.28,0.017,-0.0065,0.96,-0.05,-0.013,0.023,-0.008,-0.0066,0.01,-0.00088,-0.0059,-0.00012,0.056,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.047,0.055,0.055,0.012,0.056,0.056,0.05,6.5e-06,6.2e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 -13090000,-0.28,0.017,-0.0064,0.96,-0.054,-0.015,0.021,-0.013,-0.0083,0.0089,-0.00091,-0.0059,-0.00012,0.056,-0.018,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.046,0.062,0.062,0.011,0.065,0.065,0.049,6.3e-06,5.9e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 -13190000,-0.28,0.017,-0.0063,0.96,-0.046,-0.015,0.02,-0.0097,-0.0091,0.0096,-0.00094,-0.0059,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.055,0.055,0.011,0.066,0.066,0.047,6e-06,5.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13290000,-0.28,0.017,-0.0064,0.96,-0.049,-0.015,0.017,-0.015,-0.011,0.009,-0.00092,-0.0058,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.061,0.061,0.01,0.075,0.075,0.047,5.8e-06,5.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13390000,-0.28,0.017,-0.0064,0.96,-0.04,-0.011,0.017,-0.0074,-0.007,0.0097,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,5.6e-06,5.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13490000,-0.28,0.017,-0.0064,0.96,-0.044,-0.014,0.017,-0.012,-0.0083,0.006,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.054,0.054,0.009,0.068,0.068,0.045,5.4e-06,5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 -13590000,-0.28,0.017,-0.0064,0.96,-0.035,-0.01,0.018,-0.0035,-0.0057,0.0045,-0.00088,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00045,0.046,0.045,0.045,0.0085,0.055,0.055,0.044,5.2e-06,4.9e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13690000,-0.28,0.017,-0.0063,0.96,-0.037,-0.0095,0.019,-0.0071,-0.0067,0.0072,-0.00089,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00046,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,5e-06,4.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13790000,-0.28,0.016,-0.0064,0.96,-0.029,-0.0071,0.019,0.00061,-0.0035,0.0068,-0.00089,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4.8e-06,4.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13890000,-0.28,0.016,-0.0063,0.96,-0.031,-0.0086,0.02,-0.0022,-0.0044,0.0091,-0.00092,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,4.7e-06,4.4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1 -13990000,-0.28,0.016,-0.0062,0.96,-0.03,-0.012,0.018,-0.00073,-0.0048,0.008,-0.00094,-0.0059,-0.00012,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.039,0.039,0.0073,0.05,0.05,0.041,4.5e-06,4.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14090000,-0.28,0.016,-0.0064,0.96,-0.031,-0.0062,0.02,-0.004,-0.0053,0.0046,-0.00087,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,4.4e-06,4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14190000,-0.28,0.016,-0.0064,0.96,-0.025,-0.0047,0.02,-0.00094,-0.004,0.0049,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.036,0.036,0.007,0.049,0.049,0.04,4.2e-06,3.9e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14290000,-0.28,0.016,-0.0064,0.96,-0.028,-0.0051,0.018,-0.0036,-0.0044,0.0092,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.04,0.04,0.0069,0.055,0.055,0.039,4.1e-06,3.8e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14390000,-0.28,0.016,-0.0064,0.96,-0.026,-0.0045,0.019,-0.00096,-0.0049,0.014,-0.00083,-0.0059,-0.00012,0.064,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,4e-06,3.6e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14490000,-0.28,0.016,-0.0066,0.96,-0.026,-0.0039,0.023,-0.0037,-0.005,0.016,-0.00079,-0.0059,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00042,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.8e-06,3.5e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14590000,-0.28,0.016,-0.0067,0.96,-0.028,-0.0054,0.021,-0.0038,-0.0053,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.7e-06,3.4e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14690000,-0.28,0.016,-0.0067,0.96,-0.029,-0.0058,0.021,-0.0067,-0.006,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.6e-06,3.3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 -14790000,-0.28,0.016,-0.0068,0.96,-0.03,-0.003,0.021,-0.0052,-0.0014,0.015,-0.0008,-0.0058,-0.00012,0.065,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.031,0.031,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14890000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0012,0.026,-0.0086,-0.002,0.016,-0.00081,-0.0057,-0.00012,0.066,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.00041,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -14990000,-0.28,0.016,-0.0067,0.96,-0.031,-0.003,0.028,-0.0069,-0.003,0.018,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15090000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0042,0.032,-0.01,-0.0033,0.021,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.032,0.032,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15190000,-0.28,0.016,-0.0068,0.96,-0.03,-0.0022,0.033,-0.008,-0.0026,0.023,-0.0008,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15290000,-0.28,0.016,-0.0069,0.96,-0.034,-0.0024,0.032,-0.012,-0.0032,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15390000,-0.28,0.016,-0.0069,0.96,-0.032,-0.0042,0.032,-0.0092,-0.0026,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.027,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15490000,-0.28,0.016,-0.007,0.96,-0.034,-0.0018,0.032,-0.012,-0.003,0.021,-0.00082,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.029,0.0065,0.05,0.05,0.034,2.8e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15590000,-0.28,0.016,-0.0069,0.96,-0.03,-0.006,0.032,-0.0077,-0.0061,0.02,-0.00085,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15690000,-0.28,0.016,-0.0068,0.96,-0.032,-0.0041,0.032,-0.01,-0.0067,0.021,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15790000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0028,0.032,-0.0077,-0.0057,0.023,-0.00092,-0.0057,-0.00012,0.068,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.024,0.024,0.0066,0.043,0.044,0.033,2.6e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15890000,-0.28,0.016,-0.0069,0.96,-0.029,-0.0041,0.033,-0.011,-0.0058,0.023,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 -15990000,-0.28,0.016,-0.0068,0.96,-0.027,-0.0035,0.03,-0.0091,-0.0049,0.022,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16090000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0023,0.028,-0.012,-0.005,0.022,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.025,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16190000,-0.28,0.016,-0.0068,0.96,-0.026,-0.002,0.027,-0.011,-0.0041,0.019,-0.00086,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16290000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0011,0.027,-0.014,-0.0043,0.021,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.024,0.024,0.007,0.048,0.048,0.033,2.3e-06,2e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16390000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0015,0.027,-0.011,-0.0041,0.021,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16490000,-0.28,0.016,-0.0069,0.96,-0.033,-0.00051,0.029,-0.014,-0.0041,0.025,-0.00086,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.023,0.023,0.0072,0.047,0.047,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16590000,-0.28,0.016,-0.0069,0.96,-0.036,1.4e-05,0.033,-0.012,-0.0035,0.025,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.021,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16690000,-0.28,0.016,-0.0069,0.96,-0.039,0.0036,0.033,-0.016,-0.0035,0.026,-0.00089,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16790000,-0.28,0.016,-0.0068,0.96,-0.039,0.0034,0.032,-0.013,-0.0031,0.026,-0.00091,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0073,0.042,0.042,0.033,2e-06,1.7e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16890000,-0.28,0.016,-0.0067,0.96,-0.039,0.0029,0.033,-0.017,-0.0032,0.025,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -16990000,-0.28,0.016,-0.0067,0.96,-0.036,0.0033,0.033,-0.015,-0.0034,0.024,-0.00094,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.049,0.049,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -17090000,-0.28,0.016,-0.0068,0.96,-0.041,0.0053,0.033,-0.019,-0.0029,0.023,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.9e-06,1.6e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -17190000,-0.28,0.016,-0.0069,0.96,-0.039,0.0071,0.034,-0.018,-0.0046,0.026,-0.00093,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0076,0.057,0.057,0.033,1.8e-06,1.6e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -17290000,-0.28,0.016,-0.0069,0.96,-0.042,0.0077,0.034,-0.022,-0.0035,0.026,-0.00092,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.023,0.024,0.0077,0.062,0.063,0.033,1.8e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -17390000,-0.28,0.016,-0.0069,0.96,-0.032,0.013,0.033,-0.014,-0.002,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -17490000,-0.28,0.016,-0.0069,0.96,-0.032,0.014,0.033,-0.017,-0.00051,0.028,-0.00094,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.022,0.0078,0.058,0.058,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 -17590000,-0.28,0.016,-0.0069,0.96,-0.032,0.012,0.032,-0.016,-0.00075,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 -17690000,-0.28,0.016,-0.007,0.96,-0.033,0.012,0.033,-0.019,0.0003,0.028,-0.00096,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.02,0.02,0.0078,0.054,0.054,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 -17790000,-0.28,0.016,-0.007,0.96,-0.033,0.013,0.033,-0.018,0.0011,0.033,-0.00097,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 -17890000,-0.28,0.016,-0.0069,0.96,-0.037,0.014,0.033,-0.021,0.0022,0.038,-0.00098,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.021,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 -17990000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.017,0.0047,0.038,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 -18090000,-0.28,0.016,-0.007,0.96,-0.037,0.016,0.032,-0.021,0.0061,0.037,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.008,0.057,0.057,0.034,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 -18190000,-0.28,0.016,-0.007,0.96,-0.034,0.013,0.033,-0.016,0.004,0.035,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18290000,-0.28,0.016,-0.007,0.96,-0.037,0.013,0.031,-0.02,0.005,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.019,0.008,0.053,0.054,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18390000,-0.28,0.016,-0.0069,0.96,-0.033,0.013,0.031,-0.014,0.0042,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0079,0.046,0.047,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18490000,-0.28,0.016,-0.0069,0.96,-0.037,0.012,0.03,-0.018,0.005,0.034,-0.001,-0.0057,-0.00013,0.072,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.018,0.008,0.051,0.051,0.034,1.3e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18590000,-0.28,0.016,-0.0068,0.96,-0.035,0.012,0.03,-0.015,0.0045,0.037,-0.001,-0.0057,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18690000,-0.28,0.016,-0.0067,0.96,-0.035,0.011,0.028,-0.017,0.0053,0.035,-0.0011,-0.0058,-0.00013,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18790000,-0.28,0.015,-0.0067,0.96,-0.031,0.011,0.028,-0.014,0.0046,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18890000,-0.28,0.015,-0.0067,0.96,-0.032,0.011,0.026,-0.017,0.0057,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 -18990000,-0.28,0.015,-0.0066,0.96,-0.029,0.011,0.027,-0.015,0.005,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.015,0.0079,0.042,0.042,0.034,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19090000,-0.28,0.015,-0.0067,0.96,-0.029,0.012,0.027,-0.017,0.0056,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.016,0.0079,0.045,0.046,0.035,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19190000,-0.28,0.016,-0.0066,0.96,-0.026,0.013,0.027,-0.015,0.0056,0.028,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.8e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19290000,-0.28,0.016,-0.0066,0.96,-0.027,0.013,0.027,-0.018,0.0067,0.027,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,9.7e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19390000,-0.28,0.015,-0.0067,0.96,-0.025,0.011,0.028,-0.016,0.0067,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,9.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19490000,-0.28,0.015,-0.0068,0.96,-0.028,0.012,0.028,-0.019,0.008,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1.1e-06,9.3e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19590000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.03,-0.016,0.0063,0.026,-0.0011,-0.0058,-0.00016,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0077,0.039,0.04,0.035,1.1e-06,9e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19690000,-0.28,0.016,-0.0067,0.96,-0.024,0.011,0.028,-0.019,0.007,0.026,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.9e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19790000,-0.28,0.015,-0.0068,0.96,-0.021,0.011,0.026,-0.019,0.0075,0.022,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,1e-06,8.7e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19890000,-0.28,0.016,-0.0068,0.96,-0.023,0.011,0.027,-0.021,0.0087,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,1e-06,8.6e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 -19990000,-0.28,0.016,-0.0068,0.96,-0.02,0.012,0.024,-0.016,0.0081,0.017,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.7e-07,8.3e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -20090000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.024,-0.018,0.0093,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0076,0.047,0.048,0.035,9.7e-07,8.2e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -20190000,-0.28,0.016,-0.0068,0.96,-0.023,0.013,0.025,-0.019,0.0097,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0075,0.05,0.05,0.035,9.4e-07,8e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -20290000,-0.28,0.016,-0.0068,0.96,-0.021,0.015,0.025,-0.022,0.011,0.021,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.3e-07,7.9e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -20390000,-0.28,0.016,-0.0067,0.96,-0.019,0.013,0.025,-0.022,0.01,0.022,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,9.1e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -20490000,-0.28,0.016,-0.0067,0.96,-0.017,0.015,0.025,-0.024,0.011,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,9e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 -20590000,-0.28,0.016,-0.0066,0.96,-0.017,0.014,0.025,-0.024,0.01,0.018,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0074,0.064,0.065,0.035,8.8e-07,7.5e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20690000,-0.28,0.016,-0.0066,0.96,-0.016,0.014,0.026,-0.025,0.012,0.019,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.7e-07,7.4e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20790000,-0.28,0.016,-0.006,0.96,-0.01,0.01,0.01,-0.019,0.0088,0.017,-0.0012,-0.0058,-0.00018,0.072,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.017,0.0073,0.057,0.057,0.035,8.4e-07,7.1e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20890000,-0.28,0.011,0.0027,0.96,-0.0058,-5.9e-05,-0.11,-0.021,0.0092,0.011,-0.0012,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00034,0.046,0.017,0.018,0.0073,0.061,0.062,0.035,8.3e-07,7.1e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -20990000,-0.28,0.0071,0.0057,0.96,0.0086,-0.017,-0.25,-0.017,0.007,-0.004,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.016,0.0072,0.052,0.052,0.034,8e-07,6.9e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -21090000,-0.28,0.0076,0.0042,0.96,0.022,-0.029,-0.37,-0.016,0.005,-0.035,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.017,0.0072,0.056,0.057,0.035,8e-07,6.8e-07,4.2e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 -21190000,-0.28,0.0095,0.0015,0.96,0.028,-0.035,-0.49,-0.013,0.0038,-0.071,-0.0011,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.7e-07,6.6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21290000,-0.28,0.011,-0.00054,0.96,0.026,-0.037,-0.62,-0.011,0.0011,-0.13,-0.0011,-0.0058,-0.00019,0.072,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.7e-07,6.5e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21390000,-0.28,0.012,-0.002,0.96,0.019,-0.029,-0.75,-0.013,0.0046,-0.19,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.016,0.017,0.007,0.054,0.055,0.035,7.5e-07,6.4e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21490000,-0.28,0.012,-0.0028,0.96,0.013,-0.027,-0.88,-0.011,0.0015,-0.28,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.017,0.018,0.007,0.059,0.06,0.035,7.4e-07,6.3e-07,4.1e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21590000,-0.28,0.012,-0.0034,0.96,0.0009,-0.021,-1,-0.015,0.0065,-0.37,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.017,0.018,0.0069,0.061,0.063,0.034,7.3e-07,6.2e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21690000,-0.28,0.012,-0.0037,0.96,-0.0046,-0.017,-1.1,-0.015,0.004,-0.48,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0069,0.066,0.068,0.035,7.2e-07,6.1e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21790000,-0.28,0.012,-0.0041,0.96,-0.011,-0.0087,-1.3,-0.017,0.01,-0.6,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.019,0.0069,0.069,0.07,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21890000,-0.28,0.013,-0.0044,0.96,-0.017,-0.0041,-1.4,-0.018,0.01,-0.74,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -21990000,-0.28,0.013,-0.0052,0.96,-0.022,0.0043,-1.4,-0.024,0.018,-0.88,-0.0011,-0.0058,-8.8e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0068,0.077,0.079,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -22090000,-0.28,0.014,-0.0058,0.96,-0.025,0.0075,-1.4,-0.025,0.018,-1,-0.0011,-0.0058,-8.2e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0068,0.083,0.085,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -22190000,-0.28,0.014,-0.0063,0.96,-0.032,0.014,-1.4,-0.03,0.025,-1.2,-0.0011,-0.0058,-5.9e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22290000,-0.28,0.014,-0.007,0.96,-0.04,0.019,-1.4,-0.034,0.027,-1.3,-0.0011,-0.0058,-6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22390000,-0.28,0.015,-0.0073,0.96,-0.047,0.026,-1.4,-0.04,0.031,-1.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.094,0.096,0.034,6.4e-07,5.5e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22490000,-0.28,0.015,-0.0074,0.96,-0.053,0.032,-1.4,-0.045,0.034,-1.6,-0.0011,-0.0058,-6.4e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0066,0.1,0.1,0.034,6.4e-07,5.4e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22590000,-0.28,0.016,-0.0073,0.96,-0.058,0.038,-1.4,-0.046,0.038,-1.7,-0.0011,-0.0058,-5.7e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22690000,-0.28,0.016,-0.0072,0.96,-0.062,0.042,-1.4,-0.053,0.042,-1.9,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22790000,-0.28,0.016,-0.0071,0.96,-0.069,0.047,-1.4,-0.059,0.045,-2,-0.0011,-0.0058,-6.6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22890000,-0.28,0.017,-0.0072,0.96,-0.074,0.051,-1.4,-0.065,0.048,-2.2,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22990000,-0.28,0.017,-0.007,0.96,-0.076,0.051,-1.4,-0.068,0.047,-2.3,-0.0011,-0.0058,-6.3e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23090000,-0.28,0.017,-0.007,0.96,-0.082,0.055,-1.4,-0.075,0.053,-2.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0064,0.13,0.13,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23190000,-0.28,0.017,-0.0069,0.96,-0.084,0.05,-1.4,-0.074,0.049,-2.6,-0.0011,-0.0058,-8.4e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.9e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23290000,-0.28,0.018,-0.0073,0.96,-0.09,0.054,-1.4,-0.083,0.053,-2.7,-0.0011,-0.0058,-8e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.14,0.14,0.034,5.6e-07,4.8e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23390000,-0.28,0.018,-0.0073,0.96,-0.089,0.056,-1.4,-0.077,0.055,-2.9,-0.0011,-0.0058,-9.8e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23490000,-0.28,0.018,-0.0073,0.96,-0.096,0.057,-1.4,-0.088,0.059,-3,-0.0011,-0.0058,-9e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.051,-1.4,-0.083,0.049,-3.2,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23690000,-0.28,0.019,-0.008,0.96,-0.093,0.053,-1.3,-0.092,0.053,-3.3,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23790000,-0.28,0.021,-0.0095,0.96,-0.077,0.049,-0.95,-0.082,0.049,-3.4,-0.0012,-0.0058,-0.00012,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00039,0.00036,0.045,0.021,0.022,0.0061,0.16,0.16,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23890000,-0.28,0.026,-0.012,0.96,-0.071,0.05,-0.52,-0.089,0.053,-3.5,-0.0012,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00042,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23990000,-0.28,0.028,-0.014,0.96,-0.061,0.048,-0.13,-0.077,0.048,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -24090000,-0.28,0.027,-0.014,0.96,-0.067,0.055,0.1,-0.082,0.053,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -24190000,-0.28,0.023,-0.011,0.96,-0.071,0.052,0.089,-0.069,0.04,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -24290000,-0.28,0.02,-0.0093,0.96,-0.076,0.055,0.068,-0.076,0.045,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.048,0.084,-0.058,0.036,-3.6,-0.0013,-0.0058,-0.00016,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.02,0.022,0.006,0.19,0.19,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -24490000,-0.28,0.019,-0.0087,0.96,-0.054,0.044,0.081,-0.063,0.039,-3.6,-0.0013,-0.0058,-0.00014,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.021,0.023,0.006,0.2,0.2,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.042,0.077,-0.045,0.033,-3.6,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.022,0.0059,0.2,0.2,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24690000,-0.28,0.019,-0.0099,0.96,-0.041,0.041,0.076,-0.049,0.037,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24790000,-0.28,0.018,-0.01,0.96,-0.034,0.04,0.068,-0.037,0.029,-3.5,-0.0013,-0.0058,-0.00017,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0059,0.21,0.21,0.032,4.7e-07,4.1e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24890000,-0.28,0.017,-0.0099,0.96,-0.033,0.042,0.058,-0.04,0.032,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0059,0.22,0.22,0.032,4.7e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24990000,-0.28,0.017,-0.0097,0.96,-0.021,0.043,0.05,-0.026,0.027,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25090000,-0.28,0.017,-0.01,0.96,-0.016,0.043,0.048,-0.027,0.031,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.23,0.23,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25190000,-0.28,0.017,-0.01,0.96,-0.006,0.038,0.048,-0.011,0.021,-3.5,-0.0013,-0.0059,-0.0002,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25290000,-0.28,0.016,-0.01,0.96,-0.0013,0.041,0.043,-0.012,0.026,-3.5,-0.0013,-0.0059,-0.00021,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25390000,-0.28,0.016,-0.011,0.96,0.0076,0.039,0.041,-0.0022,0.02,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25490000,-0.28,0.016,-0.011,0.96,0.012,0.04,0.041,-0.0021,0.024,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25590000,-0.28,0.016,-0.011,0.96,0.017,0.035,0.042,0.0049,0.0094,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25690000,-0.28,0.015,-0.01,0.96,0.018,0.034,0.031,0.0066,0.013,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25790000,-0.28,0.015,-0.01,0.96,0.028,0.029,0.031,0.014,0.0031,-3.5,-0.0014,-0.0058,-0.00025,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.2e-07,3.7e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25890000,-0.28,0.015,-0.01,0.96,0.034,0.029,0.033,0.017,0.0067,-3.5,-0.0014,-0.0058,-0.00026,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.2e-07,3.7e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -25990000,-0.28,0.015,-0.01,0.96,0.036,0.024,0.027,0.013,-0.004,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.27,0.27,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26090000,-0.28,0.015,-0.0099,0.96,0.041,0.024,0.025,0.017,-0.0023,-3.5,-0.0014,-0.0058,-0.00027,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26190000,-0.28,0.015,-0.0098,0.96,0.046,0.015,0.021,0.02,-0.018,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26290000,-0.28,0.016,-0.0098,0.96,0.046,0.014,0.015,0.024,-0.016,-3.5,-0.0014,-0.0058,-0.00029,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0051,0.019,0.015,-0.03,-3.5,-0.0014,-0.0058,-0.0003,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4e-07,3.5e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26490000,-0.28,0.016,-0.009,0.96,0.046,0.0028,0.028,0.02,-0.03,-3.5,-0.0014,-0.0058,-0.00031,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.0071,0.029,0.019,-0.042,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26690000,-0.28,0.016,-0.0083,0.96,0.047,-0.011,0.027,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26790000,-0.27,0.015,-0.0081,0.96,0.049,-0.017,0.027,0.02,-0.055,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26890000,-0.27,0.015,-0.0074,0.96,0.055,-0.02,0.022,0.026,-0.057,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -26990000,-0.27,0.016,-0.0069,0.96,0.056,-0.026,0.021,0.018,-0.064,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27090000,-0.27,0.016,-0.0067,0.96,0.058,-0.033,0.025,0.024,-0.067,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.33,0.33,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27190000,-0.27,0.016,-0.0068,0.96,0.058,-0.036,0.027,0.014,-0.069,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27290000,-0.27,0.017,-0.0069,0.96,0.066,-0.041,0.14,0.02,-0.073,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27390000,-0.27,0.019,-0.0081,0.96,0.07,-0.034,0.46,0.0048,-0.026,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27490000,-0.27,0.021,-0.0093,0.96,0.076,-0.037,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.016,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27590000,-0.27,0.02,-0.0093,0.96,0.067,-0.039,0.87,0.0064,-0.02,-3.4,-0.0014,-0.0058,-0.00032,0.074,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27690000,-0.27,0.017,-0.0084,0.96,0.061,-0.036,0.78,0.013,-0.024,-3.3,-0.0014,-0.0058,-0.00031,0.075,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -27790000,-0.27,0.016,-0.0072,0.96,0.058,-0.034,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27890000,-0.27,0.016,-0.0068,0.96,0.064,-0.04,0.81,0.016,-0.023,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27990000,-0.27,0.016,-0.0072,0.96,0.064,-0.042,0.8,0.019,-0.026,-3.1,-0.0014,-0.0058,-0.00029,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28090000,-0.27,0.016,-0.0075,0.96,0.068,-0.043,0.8,0.026,-0.03,-3,-0.0014,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28190000,-0.27,0.016,-0.0069,0.96,0.065,-0.041,0.81,0.027,-0.032,-2.9,-0.0013,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.085,0.085,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28290000,-0.27,0.017,-0.0064,0.96,0.069,-0.044,0.81,0.033,-0.037,-2.9,-0.0013,-0.0058,-0.00027,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.016,0.018,0.0054,0.089,0.09,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28390000,-0.27,0.017,-0.0063,0.96,0.07,-0.046,0.81,0.035,-0.038,-2.8,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0054,0.091,0.092,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28490000,-0.27,0.018,-0.0066,0.96,0.073,-0.049,0.81,0.043,-0.042,-2.7,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.095,0.097,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28590000,-0.27,0.018,-0.0066,0.96,0.065,-0.049,0.81,0.043,-0.045,-2.6,-0.0013,-0.0058,-0.00023,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.099,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28690000,-0.27,0.017,-0.0064,0.96,0.064,-0.05,0.81,0.05,-0.05,-2.6,-0.0013,-0.0058,-0.00024,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28790000,-0.27,0.017,-0.0058,0.96,0.062,-0.049,0.81,0.051,-0.049,-2.5,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28890000,-0.27,0.016,-0.0056,0.96,0.065,-0.051,0.81,0.057,-0.054,-2.4,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28990000,-0.27,0.016,-0.0054,0.96,0.063,-0.048,0.81,0.058,-0.054,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29090000,-0.27,0.017,-0.0052,0.96,0.067,-0.05,0.81,0.066,-0.059,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29190000,-0.27,0.017,-0.0051,0.96,0.067,-0.049,0.8,0.067,-0.058,-2.2,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29290000,-0.27,0.017,-0.0054,0.96,0.071,-0.054,0.81,0.076,-0.062,-2.1,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29390000,-0.27,0.016,-0.0059,0.96,0.067,-0.051,0.81,0.074,-0.059,-2,-0.0013,-0.0058,-0.00014,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29490000,-0.27,0.016,-0.0059,0.96,0.07,-0.052,0.81,0.081,-0.065,-2,-0.0013,-0.0058,-0.00013,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.05,0.81,0.08,-0.063,-1.9,-0.0013,-0.0058,-0.00011,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.018,0.021,0.0053,0.14,0.14,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.049,0.81,0.087,-0.068,-1.8,-0.0013,-0.0058,-9.8e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.019,0.022,0.0053,0.15,0.15,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.042,0.8,0.084,-0.064,-1.7,-0.0013,-0.0058,-6.9e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29890000,-0.27,0.016,-0.005,0.96,0.07,-0.044,0.8,0.092,-0.069,-1.7,-0.0013,-0.0058,-6.2e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.041,0.8,0.087,-0.068,-1.6,-0.0013,-0.0058,-4.8e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30090000,-0.27,0.017,-0.0053,0.96,0.067,-0.041,0.8,0.094,-0.07,-1.5,-0.0013,-0.0058,-6.2e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.089,-0.061,-1.5,-0.0013,-0.0058,-5e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.17,0.17,0.031,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.096,-0.065,-1.4,-0.0013,-0.0058,-4.9e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.029,0.8,0.095,-0.059,-1.3,-0.0013,-0.0058,-1.9e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.18,0.18,0.03,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.028,0.8,0.1,-0.062,-1.2,-0.0013,-0.0058,-1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30590000,-0.27,0.017,-0.0056,0.96,0.061,-0.026,0.8,0.097,-0.058,-1.2,-0.0013,-0.0058,1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30690000,-0.27,0.017,-0.006,0.96,0.058,-0.026,0.8,0.1,-0.061,-1.1,-0.0013,-0.0058,1.1e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00035,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.016,0.8,0.095,-0.049,-1,-0.0012,-0.0058,3.6e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.012,0.79,0.099,-0.05,-0.95,-0.0012,-0.0058,2.6e-05,0.072,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30990000,-0.27,0.016,-0.0054,0.96,0.046,-0.01,0.79,0.095,-0.048,-0.88,-0.0012,-0.0058,3e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0087,0.79,0.099,-0.049,-0.81,-0.0012,-0.0058,2.2e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31190000,-0.27,0.017,-0.0057,0.96,0.042,-0.0051,0.8,0.093,-0.044,-0.74,-0.0012,-0.0058,4.6e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0033,0.8,0.096,-0.045,-0.67,-0.0012,-0.0058,5.2e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0017,0.8,0.09,-0.042,-0.59,-0.0012,-0.0058,5.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0051,0.8,0.095,-0.041,-0.52,-0.0012,-0.0058,4.8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31590000,-0.27,0.017,-0.0052,0.96,0.036,0.007,0.8,0.092,-0.037,-0.45,-0.0012,-0.0058,6.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31690000,-0.27,0.017,-0.0052,0.96,0.04,0.0082,0.8,0.097,-0.037,-0.38,-0.0012,-0.0058,7.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31790000,-0.27,0.018,-0.0054,0.96,0.034,0.014,0.8,0.093,-0.027,-0.3,-0.0012,-0.0058,9e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31890000,-0.27,0.018,-0.0052,0.96,0.032,0.016,0.8,0.097,-0.025,-0.23,-0.0012,-0.0058,9.4e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -31990000,-0.27,0.017,-0.0055,0.96,0.029,0.017,0.79,0.094,-0.02,-0.17,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32090000,-0.27,0.017,-0.0059,0.96,0.03,0.021,0.8,0.098,-0.018,-0.096,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32190000,-0.27,0.017,-0.0061,0.96,0.027,0.029,0.8,0.093,-0.0092,-0.027,-0.0012,-0.0058,9.7e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32290000,-0.27,0.017,-0.006,0.96,0.027,0.031,0.8,0.096,-0.0063,0.042,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32390000,-0.27,0.017,-0.0062,0.96,0.023,0.033,0.79,0.092,-0.0029,0.12,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.092,-0.077,0.091,0.0054,0.12,-0.0012,-0.0058,9.6e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32590000,-0.27,0.016,-0.0092,0.96,-0.014,0.09,-0.08,0.091,-0.0025,0.1,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.021,0.023,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32690000,-0.27,0.016,-0.0092,0.96,-0.01,0.097,-0.081,0.09,0.0069,0.088,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32790000,-0.27,0.016,-0.009,0.96,-0.0062,0.095,-0.082,0.092,-0.0016,0.073,-0.0012,-0.0058,7.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32890000,-0.27,0.016,-0.009,0.96,-0.0066,0.1,-0.084,0.09,0.0078,0.058,-0.0012,-0.0058,8.1e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32990000,-0.27,0.016,-0.0088,0.96,-0.0026,0.095,-0.083,0.091,-0.006,0.044,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33090000,-0.27,0.016,-0.0088,0.96,0.0013,0.1,-0.08,0.091,0.0037,0.037,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33190000,-0.27,0.016,-0.0086,0.96,0.0057,0.096,-0.079,0.092,-0.012,0.029,-0.0012,-0.0058,4e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33290000,-0.27,0.016,-0.0087,0.96,0.0098,0.099,-0.079,0.093,-0.0027,0.021,-0.0013,-0.0058,5.7e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33390000,-0.27,0.016,-0.0086,0.96,0.014,0.095,-0.077,0.092,-0.012,0.012,-0.0013,-0.0058,4.6e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33490000,-0.27,0.016,-0.0086,0.96,0.02,0.099,-0.076,0.095,-0.0019,0.0028,-0.0013,-0.0058,5.4e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33590000,-0.27,0.016,-0.0084,0.96,0.023,0.096,-0.073,0.094,-0.015,-0.0051,-0.0013,-0.0058,4.8e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33690000,-0.27,0.016,-0.0084,0.96,0.026,0.099,-0.074,0.095,-0.0061,-0.013,-0.0013,-0.0058,5.3e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33790000,-0.27,0.016,-0.0083,0.96,0.029,0.096,-0.068,0.092,-0.02,-0.02,-0.0013,-0.0058,3.3e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33890000,-0.27,0.016,-0.0083,0.96,0.033,0.097,-0.068,0.095,-0.01,-0.027,-0.0013,-0.0058,4.8e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33990000,-0.27,0.016,-0.0082,0.96,0.036,0.095,-0.064,0.094,-0.019,-0.03,-0.0013,-0.0057,3.3e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0094,-0.035,-0.0013,-0.0057,3.6e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34190000,-0.27,0.016,-0.0081,0.96,0.04,0.096,-0.06,0.092,-0.021,-0.038,-0.0013,-0.0057,3e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.022,0.005,0.36,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34290000,-0.26,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.012,-0.044,-0.0013,-0.0057,4e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34390000,-0.26,0.016,-0.0078,0.96,0.043,0.095,-0.054,0.091,-0.023,-0.048,-0.0013,-0.0057,3e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34490000,-0.26,0.016,-0.0079,0.96,0.046,0.099,-0.052,0.095,-0.014,-0.051,-0.0013,-0.0057,4.2e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34590000,-0.26,0.016,-0.0078,0.96,0.049,0.092,0.74,0.09,-0.028,-0.022,-0.0013,-0.0057,3e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34690000,-0.26,0.015,-0.0078,0.96,0.058,0.092,1.7,0.095,-0.019,0.097,-0.0013,-0.0057,3.5e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34790000,-0.26,0.015,-0.0077,0.96,0.063,0.086,2.7,0.088,-0.032,0.28,-0.0013,-0.0057,2.6e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34890000,-0.26,0.015,-0.0077,0.96,0.071,0.086,3.7,0.094,-0.023,0.57,-0.0013,-0.0057,3.2e-05,0.079,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,4.9e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.6e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.5e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.7e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.5e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2490000,1,-0.011,-0.014,0.00048,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.5e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-2.1e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2790000,1,-0.01,-0.013,0.00038,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +2990000,1,-0.01,-0.013,0.00032,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-3.1e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-3.1e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3190000,1,-0.01,-0.013,0.00057,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.5e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3490000,1,-0.0097,-0.013,0.00059,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3690000,1,-0.0095,-0.013,0.00053,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.8e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3890000,1,-0.0094,-0.013,0.00064,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4090000,1,-0.0093,-0.012,0.00077,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-5.2e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-5.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4290000,1,-0.0095,-0.012,0.00075,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.7e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.7e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4490000,1,-0.0094,-0.012,0.00077,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-6.2e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-6.2e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4690000,1,-0.0094,-0.012,0.00077,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4790000,1,-0.0093,-0.012,0.00087,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4890000,1,-0.0092,-0.012,0.00091,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-7e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-7e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5090000,1,-0.0091,-0.011,0.00097,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-7.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5690000,1,-0.0089,-0.011,0.0009,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5790000,1,-0.0088,-0.011,0.00086,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5890000,1,-0.0088,-0.011,0.00089,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +5990000,1,-0.0088,-0.012,0.00087,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6090000,1,-0.0088,-0.011,0.00068,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6190000,1,-0.0089,-0.011,0.00069,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6290000,1,-0.0089,-0.011,0.00072,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6390000,1,-0.0089,-0.011,0.00073,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6490000,1,-0.0089,-0.011,0.00063,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.8e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6590000,1,-0.009,-0.011,0.00056,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 +6690000,1,-0.0089,-0.011,0.00052,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,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 +6790000,1,-0.009,-0.011,0.00048,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-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 +6890000,1,-0.0088,-0.011,0.0004,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-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 +6990000,-0.29,0.024,-0.0063,0.96,-0.2,-0.03,-0.037,-0.11,-0.017,-0.055,-0.00076,-0.0097,-0.0002,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1 +7090000,-0.28,0.025,-0.0064,0.96,-0.24,-0.045,-0.038,-0.15,-0.025,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.022,0.51,0.075,-0.029,-0.065,0,0,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1 +7190000,-0.28,0.025,-0.0064,0.96,-0.26,-0.053,-0.037,-0.17,-0.031,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.2e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1 +7290000,-0.28,0.025,-0.0065,0.96,-0.29,-0.062,-0.034,-0.2,-0.038,-0.055,-0.00059,-0.01,-0.00021,-0.00088,-0.00017,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1 +7390000,-0.28,0.024,-0.0064,0.96,-0.3,-0.068,-0.032,-0.23,-0.044,-0.052,-0.00058,-0.01,-0.00021,-0.0011,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00086,0.0013,1,1 +7490000,-0.28,0.024,-0.0065,0.96,-0.32,-0.075,-0.026,-0.26,-0.052,-0.046,-0.00057,-0.0099,-0.00021,-0.0015,-0.00025,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1 +7590000,-0.28,0.024,-0.0066,0.96,-0.34,-0.082,-0.022,-0.28,-0.061,-0.041,-0.00055,-0.0098,-0.00021,-0.0016,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00085,0.0013,1,1 +7690000,-0.28,0.024,-0.0066,0.96,-0.35,-0.091,-0.022,-0.31,-0.071,-0.036,-0.00053,-0.0097,-0.00021,-0.0017,-0.00019,-0.13,-0.1,-0.022,0.5,0.079,-0.031,-0.068,0,0,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.00084,0.0013,1,1 +7790000,-0.28,0.023,-0.0064,0.96,-0.36,-0.1,-0.024,-0.34,-0.085,-0.041,-0.00046,-0.0096,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.00084,0.0013,1,1 +7890000,-0.28,0.023,-0.0065,0.96,-0.37,-0.11,-0.025,-0.37,-0.097,-0.045,-0.00044,-0.0095,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00085,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.00083,0.0013,1,1 +7990000,-0.28,0.023,-0.0065,0.96,-0.39,-0.11,-0.021,-0.4,-0.11,-0.041,-0.00047,-0.0094,-0.0002,-0.0016,-0.00017,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0012,0.00083,0.0013,1,1 +8090000,-0.28,0.023,-0.0064,0.96,-0.41,-0.12,-0.022,-0.44,-0.12,-0.044,-0.0004,-0.0094,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0008,0.00082,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,8.8e-05,0.0013,0.0012,0.00083,0.0013,1,1 +8190000,-0.28,0.022,-0.0064,0.96,-0.41,-0.14,-0.017,-0.46,-0.14,-0.038,-0.00033,-0.0092,-0.0002,-0.0016,-0.00023,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00077,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.6e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8290000,-0.28,0.022,-0.0066,0.96,-0.44,-0.14,-0.016,-0.51,-0.15,-0.038,-0.00039,-0.0093,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00075,0.00077,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.4e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8390000,-0.28,0.022,-0.0066,0.96,-0.45,-0.14,-0.015,-0.55,-0.16,-0.036,-0.00039,-0.0092,-0.0002,-0.0017,-0.00018,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8490000,-0.28,0.022,-0.0066,0.96,-0.46,-0.14,-0.016,-0.58,-0.17,-0.041,-0.00048,-0.0091,-0.00019,-0.0016,-9.5e-05,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0007,0.00072,0.053,0.82,0.82,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8590000,-0.28,0.021,-0.0064,0.96,-0.45,-0.15,-0.012,-0.6,-0.19,-0.036,-0.00042,-0.0089,-0.00019,-0.0016,-9.3e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.068,0,0,0.00068,0.0007,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8e-05,0.0013,0.0012,0.00081,0.0013,1,1 +8690000,-0.28,0.021,-0.0066,0.96,-0.47,-0.15,-0.014,-0.64,-0.2,-0.037,-0.00048,-0.0088,-0.00019,-0.0016,-5.5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00066,0.00068,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,7.9e-05,0.0013,0.0012,0.00081,0.0013,1,1 +8790000,-0.28,0.021,-0.0066,0.96,-0.48,-0.16,-0.013,-0.68,-0.22,-0.035,-0.00046,-0.0088,-0.00018,-0.0016,-5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00064,0.00066,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,7.8e-05,0.0013,0.0012,0.00081,0.0013,1,1 +8890000,-0.28,0.021,-0.0066,0.96,-0.47,-0.16,-0.0094,-0.68,-0.23,-0.029,-0.00051,-0.0085,-0.00018,-0.0016,5.8e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00063,0.00064,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,7.7e-05,0.0013,0.0012,0.0008,0.0013,1,1 +8990000,-0.28,0.02,-0.0064,0.96,-0.45,-0.16,-0.0089,-0.68,-0.24,-0.032,-0.00055,-0.0082,-0.00017,-0.0013,0.00016,-0.13,-0.1,-0.023,0.5,0.08,-0.032,-0.069,0,0,0.00061,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,7.6e-05,0.0013,0.0012,0.0008,0.0013,1,1 +9090000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.01,-0.72,-0.22,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00033,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.0006,0.00061,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,7.5e-05,0.0013,0.0012,0.0008,0.0013,1,1 +9190000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.0096,-0.74,-0.22,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00058,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9290000,-0.28,0.02,-0.0062,0.96,-0.46,-0.15,-0.0082,-0.74,-0.24,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00057,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9390000,-0.28,0.019,-0.006,0.96,-0.45,-0.17,-0.0071,-0.75,-0.27,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.0005,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00056,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,7.3e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9490000,-0.28,0.019,-0.0061,0.96,-0.46,-0.16,-0.0055,-0.78,-0.27,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00059,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00055,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,7.2e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9590000,-0.28,0.019,-0.0061,0.96,-0.47,-0.18,-0.0054,-0.82,-0.32,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00046,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.2e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9690000,-0.28,0.019,-0.006,0.96,-0.47,-0.19,-0.0026,-0.83,-0.35,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00045,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00055,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9790000,-0.28,0.019,-0.006,0.96,-0.48,-0.2,-0.004,-0.88,-0.39,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00038,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9890000,-0.28,0.019,-0.0059,0.96,-0.47,-0.21,-0.0028,-0.88,-0.41,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00044,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9990000,-0.28,0.019,-0.0059,0.96,-0.49,-0.22,-0.0021,-0.93,-0.44,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00037,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10090000,-0.28,0.019,-0.0058,0.96,-0.49,-0.23,-0.00087,-0.96,-0.5,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10190000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-3e-05,-0.97,-0.56,-0.031,-0.00028,-0.007,-0.00015,-0.00026,0.00016,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10290000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-0.0012,-0.98,-0.57,-0.03,-0.00034,-0.0069,-0.00014,-0.00014,0.00022,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10390000,-0.28,0.019,-0.0056,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00014,-0.03,-0.00038,-0.0067,-0.00014,1.3e-05,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10490000,-0.28,0.019,-0.0056,0.96,-0.01,-0.0085,0.0071,0.00025,-0.0008,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00023,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00051,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10590000,-0.28,0.019,-0.0055,0.96,-0.021,-0.0072,0.013,-0.0011,-0.00056,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00057,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10690000,-0.28,0.019,-0.0054,0.96,-0.033,-0.0096,0.016,-0.0038,-0.0014,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00056,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10790000,-0.28,0.019,-0.0053,0.96,-0.033,-0.013,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,2.6e-05,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10890000,-0.28,0.019,-0.0052,0.96,-0.043,-0.018,0.01,-0.0036,-0.0034,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.00017,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10990000,-0.28,0.019,-0.0052,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00057,-0.0064,-0.00012,0.0058,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.9e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11090000,-0.28,0.019,-0.0053,0.96,-0.05,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00046,-0.0063,-0.00013,0.006,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.9e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11190000,-0.28,0.018,-0.0054,0.96,-0.041,-0.025,0.027,-0.002,-0.0027,-0.0011,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.8e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11290000,-0.28,0.018,-0.0054,0.96,-0.05,-0.027,0.026,-0.0065,-0.0052,-0.00073,-0.00048,-0.0063,-0.00013,0.013,0.0014,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.8e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11390000,-0.28,0.018,-0.0053,0.96,-0.043,-0.023,0.017,-0.0037,-0.0033,-0.0092,-0.00053,-0.0063,-0.00013,0.019,0.0028,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11490000,-0.28,0.018,-0.0052,0.96,-0.05,-0.025,0.021,-0.0082,-0.0059,-0.003,-0.00054,-0.0063,-0.00012,0.019,0.003,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11590000,-0.28,0.018,-0.0053,0.96,-0.044,-0.021,0.019,-0.005,-0.0038,-0.0041,-0.00058,-0.0063,-0.00012,0.025,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00031,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11690000,-0.28,0.017,-0.0053,0.96,-0.051,-0.025,0.019,-0.0097,-0.0061,-0.0053,-0.00062,-0.0063,-0.00012,0.024,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.088,0.088,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11790000,-0.28,0.017,-0.0052,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.00071,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 +11890000,-0.28,0.017,-0.0054,0.96,-0.049,-0.027,0.018,-0.01,-0.0079,-0.0016,-0.0007,-0.0063,-0.00012,0.03,0.0044,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 +11990000,-0.28,0.017,-0.0054,0.96,-0.039,-0.021,0.015,-0.0064,-0.0052,-0.0052,-0.00073,-0.0063,-0.00012,0.036,0.0065,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 +12090000,-0.28,0.017,-0.0053,0.96,-0.045,-0.022,0.018,-0.011,-0.0074,0.00087,-0.0007,-0.0062,-0.00012,0.037,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 +12190000,-0.28,0.017,-0.0053,0.96,-0.038,-0.013,0.017,-0.0054,-0.0028,0.0028,-0.00066,-0.0062,-0.00012,0.042,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12290000,-0.28,0.017,-0.0054,0.96,-0.04,-0.011,0.016,-0.0094,-0.004,0.0038,-0.00064,-0.0062,-0.00012,0.043,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12390000,-0.28,0.016,-0.0054,0.96,-0.033,-0.0082,0.014,-0.0051,-0.0026,-0.0022,-0.00063,-0.0062,-0.00012,0.046,0.0086,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12490000,-0.28,0.016,-0.0054,0.96,-0.036,-0.0092,0.018,-0.0087,-0.0035,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12590000,-0.28,0.016,-0.0053,0.96,-0.03,-0.008,0.019,-0.0035,-0.0039,0.0017,-0.00062,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12690000,-0.28,0.016,-0.0053,0.96,-0.033,-0.0061,0.019,-0.0066,-0.0046,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12790000,-0.28,0.016,-0.0051,0.96,-0.023,-0.012,0.02,-0.0016,-0.0076,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.5e-06,7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 +12890000,-0.28,0.016,-0.0051,0.96,-0.025,-0.012,0.021,-0.0039,-0.0089,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0071,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 +12990000,-0.28,0.016,-0.0051,0.96,-0.021,-0.0096,0.022,-0.0012,-0.0062,0.0096,-0.00076,-0.0061,-0.00012,0.054,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 +13090000,-0.28,0.016,-0.0051,0.96,-0.023,-0.011,0.019,-0.0033,-0.0075,0.0084,-0.0008,-0.006,-0.00011,0.054,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.0079,0.0082,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 +13190000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.018,-0.0017,-0.0085,0.009,-0.00082,-0.006,-0.00011,0.055,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 +13290000,-0.28,0.016,-0.005,0.96,-0.02,-0.011,0.016,-0.0037,-0.0097,0.0083,-0.00081,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0073,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13390000,-0.28,0.016,-0.005,0.96,-0.017,-0.0081,0.015,-0.0014,-0.0067,0.0089,-0.00079,-0.006,-0.00011,0.057,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.9e-05,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13490000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.015,-0.0032,-0.0078,0.0051,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,0.0001,0.0001,0.051,0.053,0.053,0.009,0.068,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13590000,-0.28,0.016,-0.005,0.96,-0.014,-0.0072,0.016,0.0017,-0.0055,0.0036,-0.00077,-0.006,-0.00011,0.059,0.0088,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,9.2e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13690000,-0.28,0.016,-0.0049,0.96,-0.015,-0.0064,0.016,0.00027,-0.0063,0.0062,-0.0008,-0.0059,-0.00011,0.059,0.0091,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.3e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0055,0.0058,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +13790000,-0.28,0.015,-0.0049,0.96,-0.011,-0.0044,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.06,0.0089,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.7e-05,8.6e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +13890000,-0.28,0.015,-0.0048,0.96,-0.012,-0.0055,0.017,0.0044,-0.0038,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0091,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.8e-05,8.7e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +13990000,-0.28,0.015,-0.0048,0.96,-0.014,-0.0093,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0095,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.07,0,0,8.3e-05,8.2e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14090000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0034,0.017,0.0023,-0.0048,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14190000,-0.28,0.015,-0.005,0.96,-0.01,-0.0023,0.017,0.0036,-0.0038,0.0033,-0.00074,-0.0059,-0.00011,0.062,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14290000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0026,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.062,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0042,0.0045,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14390000,-0.28,0.015,-0.0049,0.96,-0.012,-0.0022,0.017,0.0036,-0.0046,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0088,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14490000,-0.28,0.015,-0.0051,0.96,-0.012,-0.0015,0.02,0.0023,-0.0046,0.014,-0.00071,-0.0059,-0.00012,0.063,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14590000,-0.28,0.015,-0.0051,0.96,-0.015,-0.0032,0.018,0.0007,-0.0051,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.4e-05,7.3e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14690000,-0.28,0.015,-0.0051,0.96,-0.016,-0.0035,0.018,-0.00089,-0.0056,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0088,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.5e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14790000,-0.28,0.015,-0.0052,0.96,-0.019,-0.00093,0.018,-0.00059,-0.0012,0.013,-0.00073,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14890000,-0.28,0.015,-0.0051,0.96,-0.02,0.00099,0.022,-0.0027,-0.0015,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.3e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14990000,-0.28,0.015,-0.0051,0.96,-0.02,-0.001,0.025,-0.0022,-0.0027,0.016,-0.00074,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.1e-05,6.9e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0033,0.0036,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +15090000,-0.28,0.015,-0.005,0.96,-0.021,-0.0021,0.029,-0.0043,-0.0028,0.018,-0.00075,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +15190000,-0.28,0.016,-0.0052,0.96,-0.021,-0.00028,0.029,-0.0034,-0.0022,0.02,-0.00073,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +15290000,-0.28,0.016,-0.0052,0.96,-0.024,-0.00035,0.029,-0.0059,-0.0026,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 +15390000,-0.28,0.016,-0.0053,0.96,-0.023,-0.0023,0.028,-0.0046,-0.0022,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15490000,-0.28,0.016,-0.0053,0.96,-0.025,0.00021,0.028,-0.007,-0.0024,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.003,0.0033,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15590000,-0.28,0.016,-0.0053,0.96,-0.022,-0.0041,0.028,-0.0033,-0.0056,0.017,-0.00079,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15690000,-0.28,0.016,-0.0052,0.96,-0.024,-0.0021,0.028,-0.0049,-0.0059,0.018,-0.00083,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15790000,-0.28,0.015,-0.0052,0.96,-0.021,-0.00088,0.028,-0.0035,-0.0051,0.019,-0.00087,-0.0058,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15890000,-0.28,0.016,-0.0053,0.96,-0.021,-0.0021,0.029,-0.0059,-0.005,0.019,-0.00084,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15990000,-0.28,0.015,-0.0052,0.96,-0.02,-0.0017,0.026,-0.0049,-0.0043,0.018,-0.00083,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16090000,-0.28,0.016,-0.0052,0.96,-0.022,-0.00036,0.024,-0.0072,-0.0042,0.018,-0.00082,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16190000,-0.28,0.016,-0.0052,0.96,-0.02,-0.0002,0.023,-0.0071,-0.0035,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16290000,-0.28,0.015,-0.0052,0.96,-0.022,0.00077,0.022,-0.009,-0.0035,0.016,-0.00081,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16390000,-0.28,0.015,-0.0051,0.96,-0.023,0.00023,0.023,-0.007,-0.0034,0.017,-0.00082,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16490000,-0.28,0.016,-0.0052,0.96,-0.027,0.0013,0.025,-0.0098,-0.0033,0.021,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16590000,-0.28,0.016,-0.0052,0.96,-0.031,0.0017,0.029,-0.0085,-0.0028,0.021,-0.00082,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16690000,-0.28,0.015,-0.0053,0.96,-0.034,0.0053,0.029,-0.011,-0.0026,0.021,-0.00084,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16790000,-0.28,0.015,-0.0051,0.96,-0.035,0.005,0.028,-0.0096,-0.0024,0.021,-0.00086,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16890000,-0.28,0.015,-0.005,0.96,-0.035,0.0046,0.029,-0.013,-0.0023,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16990000,-0.28,0.015,-0.0051,0.96,-0.032,0.005,0.029,-0.011,-0.0025,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0024,0.0027,0.0004,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17090000,-0.28,0.015,-0.0052,0.96,-0.037,0.007,0.028,-0.015,-0.0019,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17190000,-0.28,0.015,-0.0053,0.96,-0.036,0.0088,0.03,-0.014,-0.0036,0.021,-0.00089,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17290000,-0.28,0.015,-0.0053,0.96,-0.039,0.0095,0.029,-0.017,-0.0023,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00039,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17390000,-0.28,0.015,-0.0052,0.96,-0.029,0.014,0.029,-0.01,-0.001,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17490000,-0.28,0.015,-0.0053,0.96,-0.029,0.016,0.029,-0.013,0.00056,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0023,0.0026,0.00038,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17590000,-0.28,0.015,-0.0053,0.96,-0.029,0.014,0.028,-0.012,0.0001,0.02,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.7e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17690000,-0.28,0.015,-0.0054,0.96,-0.03,0.014,0.029,-0.015,0.0013,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17790000,-0.28,0.015,-0.0054,0.96,-0.031,0.014,0.029,-0.015,0.0021,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17890000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.017,0.0033,0.032,-0.00094,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17990000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.014,0.0055,0.033,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00036,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 +18090000,-0.28,0.015,-0.0054,0.96,-0.035,0.017,0.028,-0.018,0.0071,0.031,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18190000,-0.28,0.015,-0.0053,0.96,-0.032,0.015,0.028,-0.013,0.0048,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18290000,-0.28,0.015,-0.0053,0.96,-0.036,0.015,0.027,-0.017,0.006,0.028,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18390000,-0.28,0.015,-0.0052,0.96,-0.032,0.014,0.027,-0.012,0.005,0.027,-0.00099,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0024,0.00034,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18490000,-0.28,0.015,-0.0052,0.96,-0.036,0.013,0.026,-0.015,0.006,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.5e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18590000,-0.28,0.015,-0.0051,0.96,-0.034,0.013,0.026,-0.013,0.0053,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18690000,-0.28,0.015,-0.0051,0.96,-0.034,0.012,0.024,-0.015,0.0063,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18790000,-0.28,0.015,-0.0051,0.96,-0.031,0.012,0.024,-0.012,0.0054,0.028,-0.001,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0021,0.0024,0.00032,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18890000,-0.28,0.015,-0.005,0.96,-0.031,0.012,0.022,-0.015,0.0067,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18990000,-0.28,0.015,-0.005,0.96,-0.029,0.013,0.023,-0.013,0.0058,0.027,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19090000,-0.28,0.015,-0.005,0.96,-0.028,0.013,0.023,-0.016,0.0066,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19190000,-0.28,0.015,-0.005,0.96,-0.026,0.014,0.023,-0.014,0.0065,0.023,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19290000,-0.28,0.015,-0.0049,0.96,-0.027,0.014,0.024,-0.016,0.0078,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19390000,-0.28,0.015,-0.0051,0.96,-0.025,0.013,0.025,-0.014,0.0076,0.021,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19490000,-0.28,0.015,-0.0052,0.96,-0.028,0.014,0.024,-0.018,0.0091,0.021,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19590000,-0.28,0.015,-0.005,0.96,-0.024,0.015,0.026,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19690000,-0.28,0.015,-0.005,0.96,-0.025,0.013,0.025,-0.018,0.0081,0.02,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19790000,-0.28,0.015,-0.0051,0.96,-0.022,0.013,0.023,-0.018,0.0088,0.017,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19890000,-0.28,0.015,-0.0052,0.96,-0.023,0.013,0.023,-0.02,0.01,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19990000,-0.28,0.015,-0.0052,0.96,-0.02,0.014,0.021,-0.015,0.0093,0.012,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20090000,-0.28,0.015,-0.0052,0.96,-0.023,0.017,0.021,-0.018,0.011,0.015,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20990000,-0.29,0.0064,0.0073,0.96,0.0086,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0057,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0041,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0098,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22590000,-0.29,0.015,-0.0054,0.96,-0.057,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 +23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.075,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0089,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00081,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0082,0.0099,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0083,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26990000,-0.29,0.015,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27490000,-0.29,0.02,-0.0069,0.96,0.071,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.05,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.064,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00011,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29890000,-0.29,0.015,-0.0025,0.96,0.07,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.095,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30590000,-0.29,0.016,-0.0031,0.96,0.061,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30790000,-0.29,0.016,-0.0032,0.96,0.052,-0.015,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.099,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0033,0.8,0.096,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31390000,-0.29,0.015,-0.003,0.96,0.035,0.0017,0.8,0.09,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31490000,-0.29,0.016,-0.0027,0.96,0.037,0.005,0.8,0.095,-0.037,-0.52,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0068,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-3e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,2.1e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31990000,-0.29,0.016,-0.0027,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,1.2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32090000,-0.29,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,8.1e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.006,-0.028,-0.0012,-0.0058,3.9e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.097,-0.0033,0.042,-0.0012,-0.0058,7.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32390000,-0.28,0.016,-0.0034,0.96,0.024,0.032,0.79,0.093,0.00041,0.12,-0.0012,-0.0058,5.9e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0081,0.12,-0.0012,-0.0058,3.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0011,0.1,-0.0012,-0.0058,-1.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32690000,-0.29,0.015,-0.0065,0.96,-0.0087,0.091,-0.082,0.091,0.0099,0.087,-0.0012,-0.0058,-1.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32790000,-0.29,0.015,-0.0063,0.96,-0.0048,0.09,-0.083,0.092,0.0024,0.072,-0.0012,-0.0058,-6.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32890000,-0.29,0.015,-0.0063,0.96,-0.0052,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32990000,-0.29,0.015,-0.0062,0.96,-0.0014,0.091,-0.084,0.092,-0.0019,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +33090000,-0.29,0.015,-0.0061,0.96,0.0025,0.097,-0.081,0.092,0.0074,0.036,-0.0013,-0.0058,-9.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +33190000,-0.29,0.015,-0.0061,0.96,0.0066,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0015,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0067,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.096,0.0026,0.0017,-0.0013,-0.0058,-2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.6e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0013,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0054,-0.028,-0.0013,-0.0058,-2.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.014,-0.032,-0.0013,-0.0057,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.0041,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.0061,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34390000,-0.29,0.015,-0.0053,0.96,0.043,0.096,-0.055,0.093,-0.018,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0082,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.091,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.096,-0.012,0.095,-0.0013,-0.0057,-3.6e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34790000,-0.29,0.014,-0.0052,0.96,0.052,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.6e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.095,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 From 9f799be855808ed5fa5e345d9c18309bb927d056 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 5 Apr 2024 16:23:05 +0200 Subject: [PATCH 086/652] Navigator: remove unused method Signed-off-by: Silvan Fuhrer --- src/modules/navigator/navigator.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 5efcb45bf054..03a1ea621e89 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -266,7 +266,6 @@ class Navigator : public ModuleBase, public ModuleParams int get_loiter_min_alt() const { return _param_min_ltr_alt.get(); } int get_landing_abort_min_alt() const { return _param_mis_lnd_abrt_alt.get(); } float get_param_mis_takeoff_alt() const { return _param_mis_takeoff_alt.get(); } - int get_takeoff_land_required() const { return _para_mis_takeoff_land_req.get(); } float get_yaw_timeout() const { return _param_mis_yaw_tmt.get(); } float get_yaw_threshold() const { return math::radians(_param_mis_yaw_err.get()); } @@ -406,7 +405,6 @@ class Navigator : public ModuleBase, public ModuleParams // non-navigator parameters: Mission (MIS_*) (ParamFloat) _param_mis_takeoff_alt, - (ParamInt) _para_mis_takeoff_land_req, (ParamFloat) _param_mis_yaw_tmt, (ParamFloat) _param_mis_yaw_err, (ParamFloat) _param_mis_payload_delivery_timeout, From 93ed9109772bed0719f75394f8129cbe24bac1f2 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 5 Apr 2024 16:31:49 +0200 Subject: [PATCH 087/652] FeasibilityChecks: only require both or neither TO/LND when landed Signed-off-by: Silvan Fuhrer --- .../navigator/MissionFeasibility/FeasibilityChecker.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp index b27ef969aaeb..c684f0119d9b 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp @@ -587,7 +587,10 @@ bool FeasibilityChecker::checkTakeoffLandAvailable() break; case 5: - if (!_is_landed && !_has_vtol_approach) { + if (_is_landed) { + result = hasMissionBothOrNeitherTakeoffAndLanding(); + + } else if (!_has_vtol_approach) { result = _landing_valid; if (!result) { @@ -595,9 +598,6 @@ bool FeasibilityChecker::checkTakeoffLandAvailable() events::send(events::ID("feasibility_mis_in_air_landing_req"), {events::Log::Error, events::LogInternal::Info}, "Mission rejected: Landing waypoint/pattern required"); } - - } else { - result = hasMissionBothOrNeitherTakeoffAndLanding(); } break; From 64505b4b9c776656c2f8382834d8b2a9ccbe3a3a Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 5 Apr 2024 16:39:12 +0200 Subject: [PATCH 088/652] Mission params: update description of MIS_TKO_LAND_REQ Signed-off-by: Silvan Fuhrer --- src/modules/navigator/mission_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 051f3c816b22..3a824bb8a080 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -68,7 +68,7 @@ PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 2.5f); * @value 2 Require a landing * @value 3 Require a takeoff and a landing * @value 4 Require both a takeoff and a landing, or neither - * @value 5 Same as previous, but require a landing if in air and no valid VTOL landing approach is present + * @value 5 Same as previous when landed, in-air require landing only if no valid VTOL approach is present * @group Mission */ PARAM_DEFINE_INT32(MIS_TKO_LAND_REQ, 0); From 297ddabe70c3c562b4dc00fb5d54511222836c87 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Tue, 9 Apr 2024 09:19:41 -0600 Subject: [PATCH 089/652] drivers: rc_input only publish if more than 0 rc channels filled (fixes GHST auto scan) --- src/drivers/rc_input/RCInput.cpp | 60 ++++++++++++++++++++++---------- src/drivers/rc_input/RCInput.hpp | 8 ++--- 2 files changed, 45 insertions(+), 23 deletions(-) diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index bea3af194c16..12cd1ab0bf40 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -191,7 +191,7 @@ RCInput::task_spawn(int argc, char *argv[]) return PX4_ERROR; } -void +int32_t RCInput::fill_rc_in(uint16_t raw_rc_count_local, uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS], hrt_abstime now, bool frame_drop, bool failsafe, @@ -262,6 +262,8 @@ RCInput::fill_rc_in(uint16_t raw_rc_count_local, _input_rc.rc_lost = (valid_chans == 0); _input_rc.rc_lost_frame_count = frame_drops; _input_rc.rc_total_frame_count = 0; + + return valid_chans; } void RCInput::set_rc_scan_state(RC_SCAN newState) @@ -494,9 +496,12 @@ void RCInput::Run() if (rc_updated) { // we have a new SBUS frame. Publish it. _input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_SBUS; - fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, - sbus_frame_drop, sbus_failsafe, frame_drops); - _rc_scan_locked = true; + int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, + sbus_frame_drop, sbus_failsafe, frame_drops); + + if (valid_chans > 0) { + _rc_scan_locked = true; + } } } @@ -533,9 +538,12 @@ void RCInput::Run() if (rc_updated) { // we have a new DSM frame. Publish it. _input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_DSM; - fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, - false, false, frame_drops, dsm_rssi); - _rc_scan_locked = true; + int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, + false, false, frame_drops, dsm_rssi); + + if (valid_chans > 0) { + _rc_scan_locked = true; + } } } @@ -580,9 +588,12 @@ void RCInput::Run() if (lost_count == 0) { // we have a new ST24 frame. Publish it. _input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_ST24; - fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, - false, false, frame_drops, st24_rssi); - _rc_scan_locked = true; + int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, + false, false, frame_drops, st24_rssi); + + if (valid_chans > 0) { + _rc_scan_locked = true; + } } else { // if the lost count > 0 means that there is an RC loss @@ -629,9 +640,12 @@ void RCInput::Run() if (rc_updated) { // we have a new SUMD frame. Publish it. _input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_SUMD; - fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, - false, sumd_failsafe, frame_drops, sumd_rssi); - _rc_scan_locked = true; + int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, + false, sumd_failsafe, frame_drops, sumd_rssi); + + if (valid_chans > 0) { + _rc_scan_locked = true; + } } } @@ -657,8 +671,12 @@ void RCInput::Run() // we have a new PPM frame. Publish it. rc_updated = true; _input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM; - fill_rc_in(ppm_decoded_channels, ppm_buffer, cycle_timestamp, false, false, 0); - _rc_scan_locked = true; + int32_t valid_chans = fill_rc_in(ppm_decoded_channels, ppm_buffer, cycle_timestamp, false, false, 0); + + if (valid_chans > 0) { + _rc_scan_locked = true; + } + _input_rc.rc_ppm_frame_length = ppm_frame_length; _input_rc.timestamp_last_signal = ppm_last_valid_decode; } @@ -699,7 +717,7 @@ void RCInput::Run() if (rc_updated) { // we have a new CRSF frame. Publish it. _input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_CRSF; - fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0); + int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0); // on Pixhawk (-related) boards we cannot write to the RC UART // another option is to use a different UART port @@ -711,7 +729,9 @@ void RCInput::Run() #endif /* BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT */ - _rc_scan_locked = true; + if (valid_chans > 0) { + _rc_scan_locked = true; + } if (_crsf_telemetry) { _crsf_telemetry->update(cycle_timestamp); @@ -749,7 +769,7 @@ void RCInput::Run() if (rc_updated) { // we have a new GHST frame. Publish it. _input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_GHST; - fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, ghst_rssi); + int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, ghst_rssi); // ghst telemetry works on fmu-v5 // on other Pixhawk (-related) boards we cannot write to the RC UART @@ -762,7 +782,9 @@ void RCInput::Run() #endif /* BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT */ - _rc_scan_locked = true; + if (valid_chans > 0) { + _rc_scan_locked = true; + } if (_ghst_telemetry) { _ghst_telemetry->update(cycle_timestamp); diff --git a/src/drivers/rc_input/RCInput.hpp b/src/drivers/rc_input/RCInput.hpp index be781471c840..626d84d88cc4 100644 --- a/src/drivers/rc_input/RCInput.hpp +++ b/src/drivers/rc_input/RCInput.hpp @@ -118,10 +118,10 @@ class RCInput : public ModuleBase, public ModuleParams, public px4::Sch bool bind_spektrum(int arg = DSMX8_BIND_PULSES) const; #endif // SPEKTRUM_POWER - void fill_rc_in(uint16_t raw_rc_count_local, - uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS], - hrt_abstime now, bool frame_drop, bool failsafe, - unsigned frame_drops, int rssi); + int32_t fill_rc_in(uint16_t raw_rc_count_local, + uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS], + hrt_abstime now, bool frame_drop, bool failsafe, + unsigned frame_drops, int rssi); void set_rc_scan_state(RC_SCAN _rc_scan_state); From a73df4752f96eba9281b19b9d6b8ffadda4d8447 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 3 Apr 2024 06:48:09 -0700 Subject: [PATCH 090/652] px4_fmu-v6x:Add Holybro Pixhawk Jetson Baseboard ver 0x100 --- platforms/common/pab_manifest.c | 24 +++++++++++++----------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/platforms/common/pab_manifest.c b/platforms/common/pab_manifest.c index 979bb5ecbc9b..05cfa809969d 100644 --- a/platforms/common/pab_manifest.c +++ b/platforms/common/pab_manifest.c @@ -356,20 +356,22 @@ static const px4_hw_mft_item_t base_configuration_17[] = { }, }; +// BASE ID 0x100 Holybro Pixhawk Jetson Baseboard Alaised to ID 0 static px4_hw_mft_list_entry_t mft_lists[] = { // ver_rev - {HW_BASE_ID(0), base_configuration_0, arraySize(base_configuration_0)}, // std Base with PX4IO - {HW_BASE_ID(1), base_configuration_1, arraySize(base_configuration_1)}, // std Base No PX4IO - {HW_BASE_ID(2), base_configuration_0, arraySize(base_configuration_0)}, // CUAV Base - {HW_BASE_ID(3), base_configuration_3, arraySize(base_configuration_3)}, // NXP T1 PHY - {HW_BASE_ID(4), base_configuration_0, arraySize(base_configuration_0)}, // HB CM4 base - {HW_BASE_ID(5), base_configuration_5, arraySize(base_configuration_5)}, // HB Mini - {HW_BASE_ID(8), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 8 Aliased to 0 - {HW_BASE_ID(9), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 9 - {HW_BASE_ID(10), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 10 - {HW_BASE_ID(16), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 16 - {HW_BASE_ID(17), base_configuration_17, arraySize(base_configuration_17)}, // Auterion Skynode ver 17 + {HW_BASE_ID(0), base_configuration_0, arraySize(base_configuration_0)}, // std Base with PX4IO + {HW_BASE_ID(1), base_configuration_1, arraySize(base_configuration_1)}, // std Base No PX4IO + {HW_BASE_ID(2), base_configuration_0, arraySize(base_configuration_0)}, // CUAV Base + {HW_BASE_ID(3), base_configuration_3, arraySize(base_configuration_3)}, // NXP T1 PHY + {HW_BASE_ID(4), base_configuration_0, arraySize(base_configuration_0)}, // HB CM4 base + {HW_BASE_ID(5), base_configuration_5, arraySize(base_configuration_5)}, // HB Mini + {HW_BASE_ID(8), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 8 Aliased to 0 + {HW_BASE_ID(9), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 9 + {HW_BASE_ID(10), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 10 + {HW_BASE_ID(16), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 16 + {HW_BASE_ID(17), base_configuration_17, arraySize(base_configuration_17)}, // Auterion Skynode ver 17 + {HW_BASE_ID(0x100), base_configuration_0, arraySize(base_configuration_0)}, // Holybro Pixhawk Jetson Baseboard ver 0x100 Alaised to ID 0 }; /************************************************************************************ From d8fabd11d04861890c792db320f66960ed9fbe75 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Tue, 9 Apr 2024 12:35:42 -0700 Subject: [PATCH 091/652] Send mavlink manual control buttons field in manual control input topic (#22988) Pass along button states from manual control mavlink message in new buttons field in manual control input topic --- boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp | 2 +- msg/ManualControlSetpoint.msg | 2 ++ src/modules/mavlink/mavlink_receiver.cpp | 2 ++ 3 files changed, 5 insertions(+), 1 deletion(-) diff --git a/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp b/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp index a40bd8eda219..cf7e9283428b 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp +++ b/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp @@ -125,7 +125,7 @@ void elrs_led_task() orb_copy(ORB_ID(manual_control_input), manual_control_input_fd, &setpoint_req); - _cmd = (ControllerInput)setpoint_req.aux1; + _cmd = (ControllerInput)setpoint_req.buttons; // skip duplicate cmds if (_cmd == _prev_cmd) { diff --git a/msg/ManualControlSetpoint.msg b/msg/ManualControlSetpoint.msg index 4e4e305fd0a8..95fa62228344 100644 --- a/msg/ManualControlSetpoint.msg +++ b/msg/ManualControlSetpoint.msg @@ -37,6 +37,8 @@ float32 aux6 bool sticks_moving +uint16 buttons # From uint16 buttons field of Mavlink manual_control message + # TOPICS manual_control_setpoint manual_control_input # DEPRECATED: float32 x # DEPRECATED: float32 y diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 6030d9b651ba..928d744b4707 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2089,6 +2089,8 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) // For backwards compatibility at the moment interpret throttle in range [0,1000] manual_control_setpoint.throttle = ((mavlink_manual_control.z / 1000.f) * 2.f) - 1.f; manual_control_setpoint.yaw = mavlink_manual_control.r / 1000.f; + // Pass along the button states + manual_control_setpoint.buttons = mavlink_manual_control.buttons; manual_control_setpoint.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink->get_instance_id(); manual_control_setpoint.timestamp = manual_control_setpoint.timestamp_sample = hrt_absolute_time(); manual_control_setpoint.valid = true; From f9c65cd4c6e5badeeafca90aa1ced27feace71bf Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 10 Apr 2024 09:08:25 +1000 Subject: [PATCH 092/652] Vuepress removal /changes for vitepress (#22972) * Vuepress removal /changes for vitepress * generate_msg_docs.py - README is index in vitepress --- Jenkinsfile | 2 -- Tools/msg/generate_msg_docs.py | 16 ++++++++-------- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 3a5947369e84..d7f166b5fe4d 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -171,10 +171,8 @@ pipeline { sh('cp airframes.md PX4-user_guide/en/airframes/airframe_reference.md') sh('cp parameters.md PX4-user_guide/en/advanced_config/parameter_reference.md') sh('cp -R modules/*.md PX4-user_guide/en/modules/') - sh('cp -R graph_*.json PX4-user_guide/.vuepress/public/en/middleware/') // vuepress sh('cp -R graph_*.json PX4-user_guide/public/middleware/') // vitepress sh('cp -R msg_docs/*.md PX4-user_guide/en/msg_docs/') - sh('cp -R failsafe_sim/* PX4-user_guide/.vuepress/public/en/config/failsafe') // vuepress sh('cp -R failsafe_sim/* PX4-user_guide/public/config/failsafe') // vitepress sh('cd PX4-user_guide; git status; git add .; git commit -a -m "Update PX4 Firmware metadata `date`" || true') sh('cd PX4-user_guide; git push origin main || true') diff --git a/Tools/msg/generate_msg_docs.py b/Tools/msg/generate_msg_docs.py index 81a998fbf393..620646f2fd15 100755 --- a/Tools/msg/generate_msg_docs.py +++ b/Tools/msg/generate_msg_docs.py @@ -81,13 +81,13 @@ def get_msgs_list(msgdir): with open(output_file, 'w') as content_file: content_file.write(markdown_output) - readme_markdown_file_link='- [%s](%s.md)' % (msg_name,msg_name) + index_markdown_file_link='- [%s](%s.md)' % (msg_name,msg_name) if summary_description: - readme_markdown_file_link+=" — %s" % summary_description - filelist_in_markdown+=readme_markdown_file_link+"\n" + index_markdown_file_link+=" — %s" % summary_description + filelist_in_markdown+=index_markdown_file_link+"\n" - # Write out the README.md file - readme_text="""# uORB Message Reference + # Write out the index.md file + index_text="""# uORB Message Reference :::note This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code. @@ -98,6 +98,6 @@ def get_msgs_list(msgdir): %s """ % (filelist_in_markdown) - readme_file = os.path.join(output_dir, 'README.md') - with open(readme_file, 'w') as content_file: - content_file.write(readme_text) + index_file = os.path.join(output_dir, 'index.md') + with open(index_file, 'w') as content_file: + content_file.write(index_text) From 7bfad2502bea6f411998aa602d74c2ca9a0cbaa2 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 10 Apr 2024 14:09:22 +0200 Subject: [PATCH 093/652] Update NuttX --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 61958c53056b..cc880bbecd21 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 61958c53056b5c3fb828f18a097de57d9bed0fda +Subproject commit cc880bbecd215f5541e4b6d922123fc46f8ccb72 From f8df7d16216a80f0640d19e5892be5542b66a156 Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Tue, 9 Apr 2024 15:58:20 -0700 Subject: [PATCH 094/652] Move Voxl from microdds client to uxrce dds client --- boards/modalai/voxl2/target/voxl-px4-start | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/boards/modalai/voxl2/target/voxl-px4-start b/boards/modalai/voxl2/target/voxl-px4-start index c994e0118a02..ad9804451b33 100755 --- a/boards/modalai/voxl2/target/voxl-px4-start +++ b/boards/modalai/voxl2/target/voxl-px4-start @@ -213,8 +213,8 @@ navigator start # This bridge allows raw data packets to be sent over UART to the ESC voxl2_io_bridge start -# Start microdds_client for ros2 offboard messages from agent over localhost -microdds_client start -t udp -h 127.0.0.1 -p 8888 +# Start uxrce_dds_client for ros2 offboard messages from agent over localhost +uxrce_dds_client start -t udp -h 127.0.0.1 -p 8888 # On M0052 there is only one IMU. So, PX4 needs to # publish IMU samples externally for VIO to use. From b544ea99d5f4332d05fb8c422d0b51411603dcbf Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Tue, 9 Apr 2024 15:01:06 -0700 Subject: [PATCH 095/652] Enabled voxl2-slpi dsp_sbus driver in build --- boards/modalai/voxl2-slpi/src/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/modalai/voxl2-slpi/src/CMakeLists.txt b/boards/modalai/voxl2-slpi/src/CMakeLists.txt index 6ccb1facf6c5..4675d2e77a56 100644 --- a/boards/modalai/voxl2-slpi/src/CMakeLists.txt +++ b/boards/modalai/voxl2-slpi/src/CMakeLists.txt @@ -49,5 +49,5 @@ add_subdirectory(${PX4_BOARD_DIR}/src/drivers/mavlink_rc_in) # add_subdirectory(${PX4_BOARD_DIR}/src/drivers/spektrum_rc) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl) -# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_sbus) +add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_sbus) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/elrs_led) From cc11e1fbbf80c303f745b06920031f34e7c04b95 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Thu, 4 Apr 2024 14:28:09 -0600 Subject: [PATCH 096/652] drivers: broadcom AFBR fix close to ground false readings --- .../broadcom/afbrs50/AFBRS50.cpp | 256 +++++++++--------- .../broadcom/afbrs50/AFBRS50.hpp | 2 +- .../broadcom/afbrs50/parameters.c | 4 +- 3 files changed, 132 insertions(+), 130 deletions(-) diff --git a/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp b/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp index 44195305158f..91e3366d5ec8 100644 --- a/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp +++ b/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp @@ -118,142 +118,145 @@ void AFBRS50::ProcessMeasurement(argus_hnd_t *hnd) int AFBRS50::init() { - if (_hnd != nullptr) { - // retry - Argus_Deinit(_hnd); - Argus_DestroyHandle(_hnd); - _hnd = nullptr; - } - - _hnd = Argus_CreateHandle(); - - if (_hnd == nullptr) { - PX4_ERR("Handle not initialized"); - return PX4_ERROR; - } - - // Initialize the S2PI hardware required by the API. - S2PI_Init(BROADCOM_AFBR_S50_S2PI_SPI_BUS, SPI_BAUD_RATE); - - int32_t mode_param = _p_sens_afbr_mode.get(); - - if (mode_param < 0 || mode_param > 3) { - PX4_ERR("Invalid mode parameter: %li", mode_param); - return PX4_ERROR; - } - - argus_mode_t mode = ARGUS_MODE_LONG_RANGE; - - switch (mode_param) { - case 0: - mode = ARGUS_MODE_SHORT_RANGE; - break; - - case 1: - mode = ARGUS_MODE_LONG_RANGE; - break; - - case 2: - mode = ARGUS_MODE_HIGH_SPEED_SHORT_RANGE; - break; - - case 3: - mode = ARGUS_MODE_HIGH_SPEED_LONG_RANGE; - break; - - default: - break; - } - - status_t status = Argus_InitMode(_hnd, BROADCOM_AFBR_S50_S2PI_SPI_BUS, mode); + // Retry initialization 3 times + for (int32_t i = 0; i < 3; i++) { + if (_hnd != nullptr) { + // retry + Argus_Deinit(_hnd); + Argus_DestroyHandle(_hnd); + _hnd = nullptr; + } - if (status == STATUS_OK) { - uint32_t id = Argus_GetChipID(_hnd); - uint32_t value = Argus_GetAPIVersion(); - uint8_t a = (value >> 24) & 0xFFU; - uint8_t b = (value >> 16) & 0xFFU; - uint8_t c = value & 0xFFFFU; - PX4_INFO_RAW("AFBR-S50 Chip ID: %u, API Version: %u v%d.%d.%d\n", (uint)id, (uint)value, a, b, c); + _hnd = Argus_CreateHandle(); - argus_module_version_t mv = Argus_GetModuleVersion(_hnd); + if (_hnd == nullptr) { + PX4_ERR("Handle not initialized"); + return PX4_ERROR; + } - switch (mv) { - case AFBR_S50MV85G_V1: + // Initialize the S2PI hardware required by the API. + S2PI_Init(BROADCOM_AFBR_S50_S2PI_SPI_BUS, SPI_BAUD_RATE); - // FALLTHROUGH - case AFBR_S50MV85G_V2: + int32_t mode_param = _p_sens_afbr_mode.get(); - // FALLTHROUGH - case AFBR_S50MV85G_V3: - _min_distance = 0.08f; - _max_distance = 10.f; - _px4_rangefinder.set_min_distance(_min_distance); - _px4_rangefinder.set_max_distance(_max_distance); - _px4_rangefinder.set_fov(math::radians(6.f)); - PX4_INFO_RAW("AFBR-S50MV85G\n"); - break; + if (mode_param < 0 || mode_param > 3) { + PX4_ERR("Invalid mode parameter: %li", mode_param); + return PX4_ERROR; + } - case AFBR_S50LV85D_V1: - _min_distance = 0.08f; - _max_distance = 30.f; - _px4_rangefinder.set_min_distance(_min_distance); - _px4_rangefinder.set_max_distance(_max_distance); - _px4_rangefinder.set_fov(math::radians(6.f)); - PX4_INFO_RAW("AFBR-S50LV85D\n"); - break; + argus_mode_t mode = ARGUS_MODE_SHORT_RANGE; - case AFBR_S50LX85D_V1: - _min_distance = 0.08f; - _max_distance = 50.f; - _px4_rangefinder.set_min_distance(_min_distance); - _px4_rangefinder.set_max_distance(_max_distance); - _px4_rangefinder.set_fov(math::radians(6.f)); - PX4_INFO_RAW("AFBR-S50LX85D\n"); + switch (mode_param) { + case 0: + mode = ARGUS_MODE_SHORT_RANGE; break; - case AFBR_S50MV68B_V1: - _min_distance = 0.08f; - _max_distance = 10.f; - _px4_rangefinder.set_min_distance(_min_distance); - _px4_rangefinder.set_max_distance(_max_distance); - _px4_rangefinder.set_fov(math::radians(1.f)); - PX4_INFO_RAW("AFBR-S50MV68B (v1)\n"); + case 1: + mode = ARGUS_MODE_LONG_RANGE; break; - case AFBR_S50MV85I_V1: - _min_distance = 0.08f; - _max_distance = 5.f; - _px4_rangefinder.set_min_distance(_min_distance); - _px4_rangefinder.set_max_distance(_max_distance); - _px4_rangefinder.set_fov(math::radians(6.f)); - PX4_INFO_RAW("AFBR-S50MV85I (v1)\n"); + case 2: + mode = ARGUS_MODE_HIGH_SPEED_SHORT_RANGE; break; - case AFBR_S50SV85K_V1: - _min_distance = 0.08f; - _max_distance = 10.f; - _px4_rangefinder.set_min_distance(_min_distance); - _px4_rangefinder.set_max_distance(_max_distance); - _px4_rangefinder.set_fov(math::radians(4.f)); - PX4_INFO_RAW("AFBR-S50SV85K (v1)\n"); + case 3: + mode = ARGUS_MODE_HIGH_SPEED_LONG_RANGE; break; default: break; } - if (_testing) { - _state = STATE::TEST; + status_t status = Argus_InitMode(_hnd, BROADCOM_AFBR_S50_S2PI_SPI_BUS, mode); - } else { - _state = STATE::CONFIGURE; - } + if (status == STATUS_OK) { + uint32_t id = Argus_GetChipID(_hnd); + uint32_t value = Argus_GetAPIVersion(); + uint8_t a = (value >> 24) & 0xFFU; + uint8_t b = (value >> 16) & 0xFFU; + uint8_t c = value & 0xFFFFU; + PX4_INFO_RAW("AFBR-S50 Chip ID: %u, API Version: %u v%d.%d.%d\n", (uint)id, (uint)value, a, b, c); + + argus_module_version_t mv = Argus_GetModuleVersion(_hnd); + + switch (mv) { + case AFBR_S50MV85G_V1: + + // FALLTHROUGH + case AFBR_S50MV85G_V2: + + // FALLTHROUGH + case AFBR_S50MV85G_V3: + _min_distance = 0.0f; + _max_distance = 10.f; + _px4_rangefinder.set_min_distance(_min_distance); + _px4_rangefinder.set_max_distance(_max_distance); + _px4_rangefinder.set_fov(math::radians(6.f)); + PX4_INFO_RAW("AFBR-S50MV85G\n"); + break; + + case AFBR_S50LV85D_V1: + _min_distance = 0.0f; + _max_distance = 30.f; + _px4_rangefinder.set_min_distance(_min_distance); + _px4_rangefinder.set_max_distance(_max_distance); + _px4_rangefinder.set_fov(math::radians(6.f)); + PX4_INFO_RAW("AFBR-S50LV85D\n"); + break; + + case AFBR_S50LX85D_V1: + _min_distance = 0.0f; + _max_distance = 50.f; + _px4_rangefinder.set_min_distance(_min_distance); + _px4_rangefinder.set_max_distance(_max_distance); + _px4_rangefinder.set_fov(math::radians(6.f)); + PX4_INFO_RAW("AFBR-S50LX85D\n"); + break; + + case AFBR_S50MV68B_V1: + _min_distance = 0.0f; + _max_distance = 10.f; + _px4_rangefinder.set_min_distance(_min_distance); + _px4_rangefinder.set_max_distance(_max_distance); + _px4_rangefinder.set_fov(math::radians(1.f)); + PX4_INFO_RAW("AFBR-S50MV68B (v1)\n"); + break; + + case AFBR_S50MV85I_V1: + _min_distance = 0.0f; + _max_distance = 5.f; + _px4_rangefinder.set_min_distance(_min_distance); + _px4_rangefinder.set_max_distance(_max_distance); + _px4_rangefinder.set_fov(math::radians(6.f)); + PX4_INFO_RAW("AFBR-S50MV85I (v1)\n"); + break; + + case AFBR_S50SV85K_V1: + _min_distance = 0.0f; + _max_distance = 10.f; + _px4_rangefinder.set_min_distance(_min_distance); + _px4_rangefinder.set_max_distance(_max_distance); + _px4_rangefinder.set_fov(math::radians(4.f)); + PX4_INFO_RAW("AFBR-S50SV85K (v1)\n"); + break; + + default: + break; + } - ScheduleDelayed(_measure_interval); - return PX4_OK; + if (_testing) { + _state = STATE::TEST; - } else { - PX4_ERR("Argus_InitMode failed: %ld", status); + } else { + _state = STATE::CONFIGURE; + } + + ScheduleDelayed(_measure_interval); + return PX4_OK; + + } else { + PX4_ERR("Argus_InitMode failed: %ld", status); + } } return PX4_ERROR; @@ -284,7 +287,7 @@ void AFBRS50::Run() case STATE::CONFIGURE: { _current_rate = (uint32_t)_p_sens_afbr_s_rate.get(); - status_t status = set_rate(_current_rate); + status_t status = set_rate_and_dfm(_current_rate, DFM_MODE_OFF); if (status != STATUS_OK) { PX4_ERR("CONFIGURE status not okay: %i", (int)status); @@ -292,14 +295,6 @@ void AFBRS50::Run() ScheduleNow(); } - status = Argus_SetConfigurationDFMMode(_hnd, DFM_MODE_8X); - - if (status != STATUS_OK) { - PX4_ERR("Argus_SetConfigurationDFMMode status not okay: %i", (int)status); - _state = STATE::STOP; - ScheduleNow(); - } - status = Argus_SetConfigurationSmartPowerSaveEnabled(_hnd, false); if (status != STATUS_OK) { @@ -352,7 +347,7 @@ void AFBRS50::Evaluate_rate() && (_current_rate != (uint32_t)_p_sens_afbr_l_rate.get())) { _current_rate = (uint32_t)_p_sens_afbr_l_rate.get(); - status = set_rate(_current_rate); + status = set_rate_and_dfm(_current_rate, DFM_MODE_8X); if (status != STATUS_OK) { PX4_ERR("set_rate status not okay: %i", (int)status); @@ -366,7 +361,7 @@ void AFBRS50::Evaluate_rate() && (_current_rate != (uint32_t)_p_sens_afbr_s_rate.get())) { _current_rate = (uint32_t)_p_sens_afbr_s_rate.get(); - status = set_rate(_current_rate); + status = set_rate_and_dfm(_current_rate, DFM_MODE_OFF); if (status != STATUS_OK) { PX4_ERR("set_rate status not okay: %i", (int)status); @@ -400,13 +395,20 @@ void AFBRS50::print_info() get_info(); } -status_t AFBRS50::set_rate(uint32_t rate_hz) +status_t AFBRS50::set_rate_and_dfm(uint32_t rate_hz, argus_dfm_mode_t dfm_mode) { while (Argus_GetStatus(_hnd) != STATUS_IDLE) { px4_usleep(1_ms); } - status_t status = Argus_SetConfigurationFrameTime(_hnd, (1000000 / rate_hz)); + status_t status = Argus_SetConfigurationDFMMode(_hnd, dfm_mode); + + if (status != STATUS_OK) { + PX4_ERR("Argus_SetConfigurationDFMMode status not okay: %i", (int)status); + return status; + } + + status = Argus_SetConfigurationFrameTime(_hnd, (1000000 / rate_hz)); if (status != STATUS_OK) { PX4_ERR("Argus_SetConfigurationFrameTime status not okay: %i", (int)status); diff --git a/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.hpp b/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.hpp index 2ad767b2fa3a..7b24c5b4baeb 100644 --- a/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.hpp +++ b/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.hpp @@ -85,7 +85,7 @@ class AFBRS50 : public ModuleParams, public px4::ScheduledWorkItem static status_t measurement_ready_callback(status_t status, argus_hnd_t *hnd); void get_info(); - status_t set_rate(uint32_t rate_hz); + status_t set_rate_and_dfm(uint32_t rate_hz, argus_dfm_mode_t dfm_mode); argus_hnd_t *_hnd{nullptr}; diff --git a/src/drivers/distance_sensor/broadcom/afbrs50/parameters.c b/src/drivers/distance_sensor/broadcom/afbrs50/parameters.c index 28ef2a17c1aa..26f3683e96d8 100644 --- a/src/drivers/distance_sensor/broadcom/afbrs50/parameters.c +++ b/src/drivers/distance_sensor/broadcom/afbrs50/parameters.c @@ -46,7 +46,7 @@ * @value 2 High Speed Short Range Mode * @value 3 High Speed Long Range Mode */ -PARAM_DEFINE_INT32(SENS_AFBR_MODE, 1); +PARAM_DEFINE_INT32(SENS_AFBR_MODE, 0); /** * AFBR Rangefinder Short Range Rate @@ -85,7 +85,7 @@ PARAM_DEFINE_INT32(SENS_AFBR_L_RATE, 25); * @group Sensors * */ -PARAM_DEFINE_INT32(SENS_AFBR_THRESH, 5); +PARAM_DEFINE_INT32(SENS_AFBR_THRESH, 4); /** From 6a7555c0055f65da69402750d66112196284c7e1 Mon Sep 17 00:00:00 2001 From: Konrad Date: Wed, 10 Apr 2024 10:32:42 +0200 Subject: [PATCH 097/652] mission_base: fix to set the end of mission item always, if the mission can't be properly loaded or started --- src/modules/navigator/mission_base.cpp | 29 ++++++++++++++++++-------- src/modules/navigator/mission_base.h | 3 ++- 2 files changed, 22 insertions(+), 10 deletions(-) diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index 026cefaba2c5..595f548c8357 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -356,7 +356,7 @@ MissionBase::on_active() void MissionBase::update_mission() { - if (_mission.count == 0u || !_is_current_planned_mission_item_valid || !_navigator->get_mission_result()->valid) { + if (_mission.count == 0u || !_is_current_planned_mission_item_valid || !isMissionValid()) { if (_land_detected_sub.get().landed) { /* landed, refusing to take off without a mission */ mavlink_log_critical(_navigator->get_mavlink_log_pub(), "No valid mission available, refusing takeoff\t"); @@ -441,24 +441,33 @@ MissionBase::advance_mission() void MissionBase::set_mission_items() { - if (_is_current_planned_mission_item_valid) { + bool set_end_of_mission{false}; + + if (_is_current_planned_mission_item_valid && _mission_type == MissionType::MISSION_TYPE_MISSION && isMissionValid()) { /* By default set the mission item to the current planned mission item. Depending on request, it can be altered. */ - loadCurrentMissionItem(); + if (loadCurrentMissionItem()) { + /* force vtol land */ + if (_navigator->force_vtol() && _mission_item.nav_cmd == NAV_CMD_LAND) { + _mission_item.nav_cmd = NAV_CMD_VTOL_LAND; + } - /* force vtol land */ - if (_navigator->force_vtol() && _mission_item.nav_cmd == NAV_CMD_LAND) { - _mission_item.nav_cmd = NAV_CMD_VTOL_LAND; - } + setActiveMissionItems(); - setActiveMissionItems(); + } else { + set_end_of_mission = true; + } } else { + set_end_of_mission = true; + } + + if (set_end_of_mission) { setEndOfMissionItems(); _navigator->mode_completed(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION); } } -void MissionBase::loadCurrentMissionItem() +bool MissionBase::loadCurrentMissionItem() { const dm_item_t dm_item = static_cast(_mission.mission_dataman_id); bool success = _dataman_cache.loadWait(dm_item, _mission.current_seq, reinterpret_cast(&_mission_item), @@ -469,6 +478,8 @@ void MissionBase::loadCurrentMissionItem() events::send(events::ID("mission_item_set_failed"), events::Log::Error, "Mission item could not be set"); } + + return success; } void MissionBase::setEndOfMissionItems() diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index 1b788106f4a3..76f07882b773 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -250,8 +250,9 @@ class MissionBase : public MissionBlock, public ModuleParams * @brief Load current mission item * * Load current mission item from dataman cache. + * @return true, if the mission item could be loaded, false otherwise */ - void loadCurrentMissionItem(); + bool loadCurrentMissionItem(); /** * Set the mission result From 6fec452c4bcaca51c203d648f1d23fe563714012 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 9 Apr 2024 09:59:49 +0200 Subject: [PATCH 098/652] FW position control: catapult/hand-launch: do not cut throttle if not landed Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 4bb1d5ee3188..f8d8844ef05b 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1609,7 +1609,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _att_sp.thrust_body[0] = _param_fw_thr_idle.get(); } else { - _att_sp.thrust_body[0] = (_landed) ? min(_param_fw_thr_idle.get(), 1.f) : get_tecs_thrust(); + _att_sp.thrust_body[0] = get_tecs_thrust(); } _att_sp.pitch_body = get_tecs_pitch(); From 974ead401525f74c5c90c5bdbffdb4ff7279ac05 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 9 Apr 2024 10:22:42 +0200 Subject: [PATCH 099/652] FW position control: catapult/hand-launch: enable without launch detection Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index f8d8844ef05b..610ddad03a5f 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1551,8 +1551,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _launchDetector.forceSetFlyState(); } - if (!_launch_detected && _launchDetector.getLaunchDetected() > launch_detection_status_s::STATE_WAITING_FOR_LAUNCH - && _param_fw_laun_detcn_on.get()) { + if (!_launch_detected && _launchDetector.getLaunchDetected() > launch_detection_status_s::STATE_WAITING_FOR_LAUNCH) { _launch_detected = true; _launch_global_position = global_position; _takeoff_ground_alt = _current_altitude; @@ -1577,8 +1576,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo } /* Set control values depending on the detection state */ - if (_launchDetector.getLaunchDetected() > launch_detection_status_s::STATE_WAITING_FOR_LAUNCH - && _param_fw_laun_detcn_on.get()) { + if (_launchDetector.getLaunchDetected() > launch_detection_status_s::STATE_WAITING_FOR_LAUNCH) { /* Launch has been detected, hence we have to control the plane. */ float target_airspeed = adapt_airspeed_setpoint(control_interval, takeoff_airspeed, adjusted_min_airspeed, ground_speed, From 05672f343dab78a381d67631fb006ec352ef2c12 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 9 Apr 2024 10:25:46 +0200 Subject: [PATCH 100/652] TECS: check if integrator update is finit prior applying Signed-off-by: Silvan Fuhrer --- src/lib/tecs/TECS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index b0d9c43b2058..b3148c4a7c17 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -576,7 +576,7 @@ void TECSControl::_calcThrottleControlUpdate(float dt, const STERateLimit &limit // Calculate a throttle demand from the integrated total energy rate error // This will be added to the total throttle demand to compensate for steady state errors - _throttle_integ_state = _throttle_integ_state + throttle_integ_input; + _throttle_integ_state = PX4_ISFINITE(throttle_integ_input) ? _throttle_integ_state + throttle_integ_input : 0.f; } else { _throttle_integ_state = 0.0f; From 5fab21d09909446ba7c59cd145eb07a5941f27a0 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 5 Apr 2024 15:48:50 +0200 Subject: [PATCH 101/652] MissionBase: hasMissionLandStart should only return true if mission is valid Signed-off-by: Silvan Fuhrer --- src/modules/navigator/mission_base.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index 76f07882b773..405291969e4d 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -118,12 +118,12 @@ class MissionBase : public MissionBlock, public ModuleParams void getNextPositionItems(int32_t start_index, int32_t items_index[], size_t &num_found_items, uint8_t max_num_items); /** - * @brief Has Mission a Land Start or Land Item + * @brief Mission has a land start, a land, and is valid * - * @return true If mission has a land start of land item and a land item + * @return true If mission has a land start and a land item and is valid * @return false otherwise */ - bool hasMissionLandStart() const { return _mission.land_start_index >= 0 && _mission.land_index >= 0;}; + bool hasMissionLandStart() const { return _mission.land_start_index >= 0 && _mission.land_index >= 0 && isMissionValid();}; /** * @brief Go to next Mission Item * Go to next non jump mission item From 926e7878afc6ce804b0b4c097fbf94d405841f42 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 11 Apr 2024 10:39:49 +0200 Subject: [PATCH 102/652] RT: only chose mission RTL if mission is valid Signed-off-by: Silvan Fuhrer --- src/modules/navigator/rtl.cpp | 3 ++- src/modules/navigator/rtl.h | 5 +++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index bfa5d486be45..2b6bd55b3f91 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -617,7 +617,8 @@ void RTL::parameters_update() bool RTL::hasMissionLandStart() const { - return _mission_sub.get().land_start_index >= 0 && _mission_sub.get().land_index >= 0; + return _mission_sub.get().land_start_index >= 0 && _mission_sub.get().land_index >= 0 + && _navigator->get_mission_result()->valid; } bool RTL::hasVtolLandApproach(const PositionYawSetpoint &rtl_position) const diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h index ac6a5a75d774..e7b720bd6152 100644 --- a/src/modules/navigator/rtl.h +++ b/src/modules/navigator/rtl.h @@ -97,6 +97,11 @@ class RTL : public NavigatorMode, public ModuleParams }; private: + + /** + * @brief Check mission landing validity + * @return true if mission has a land start, a land and is valid + */ bool hasMissionLandStart() const; /** From 8a8f481c293042e5dc6058810813e7b6c0e1a59a Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Thu, 11 Apr 2024 13:27:54 -0800 Subject: [PATCH 103/652] remove PGA460 from COMMON_DISTANCE_SENSOR --- src/drivers/distance_sensor/Kconfig | 1 - 1 file changed, 1 deletion(-) diff --git a/src/drivers/distance_sensor/Kconfig b/src/drivers/distance_sensor/Kconfig index 3c93bcb07b5b..43c8f3cc9227 100644 --- a/src/drivers/distance_sensor/Kconfig +++ b/src/drivers/distance_sensor/Kconfig @@ -9,7 +9,6 @@ menu "Distance sensors" select DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL select DRIVERS_DISTANCE_SENSOR_LL40LS select DRIVERS_DISTANCE_SENSOR_MB12XX - select DRIVERS_DISTANCE_SENSOR_PGA460 select DRIVERS_DISTANCE_SENSOR_SRF02 select DRIVERS_DISTANCE_SENSOR_TERARANGER select DRIVERS_DISTANCE_SENSOR_TF02PRO From 65cc153d4736ae62d7115a6db570b2631d3c4f06 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Thu, 11 Apr 2024 13:30:34 -0800 Subject: [PATCH 104/652] remove LIS2MDL from COMMON_MAGNETOMETER --- boards/px4/fmu-v5/debug.px4board | 1 - src/drivers/magnetometer/Kconfig | 1 - 2 files changed, 2 deletions(-) diff --git a/boards/px4/fmu-v5/debug.px4board b/boards/px4/fmu-v5/debug.px4board index 0b8ab3fc3e99..99b978fc4af3 100644 --- a/boards/px4/fmu-v5/debug.px4board +++ b/boards/px4/fmu-v5/debug.px4board @@ -37,7 +37,6 @@ CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y -CONFIG_DRIVERS_MAGNETOMETER_LIS2MDL=y CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y CONFIG_DRIVERS_MAGNETOMETER_LSM303AGR=y CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y diff --git a/src/drivers/magnetometer/Kconfig b/src/drivers/magnetometer/Kconfig index 99bb90f54e2c..39ed3db84a3b 100644 --- a/src/drivers/magnetometer/Kconfig +++ b/src/drivers/magnetometer/Kconfig @@ -9,7 +9,6 @@ menu "Magnetometer" select DRIVERS_MAGNETOMETER_QMC5883L select DRIVERS_MAGNETOMETER_ISENTEK_IST8308 select DRIVERS_MAGNETOMETER_ISENTEK_IST8310 - select DRIVERS_MAGNETOMETER_LIS2MDL select DRIVERS_MAGNETOMETER_LIS3MDL select DRIVERS_MAGNETOMETER_LSM303AGR select DRIVERS_MAGNETOMETER_RM3100 From 528ad1e87d4aba286be9a5133ba775e922d2005b Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Sun, 3 Mar 2024 19:13:28 -0400 Subject: [PATCH 105/652] boards: ARK Pi6X Initial Commit --- .ci/Jenkinsfile-compile | 2 + .github/workflows/compile_nuttx.yml | 1 + .vscode/cmake-variants.yaml | 10 + boards/ark/pi6x/bootloader.px4board | 3 + boards/ark/pi6x/default.px4board | 70 +++ .../ark/pi6x/extras/ark_pi6x_bootloader.bin | Bin 0 -> 46152 bytes boards/ark/pi6x/firmware.prototype | 13 + boards/ark/pi6x/init/rc.board_defaults | 33 ++ boards/ark/pi6x/init/rc.board_sensors | 34 ++ boards/ark/pi6x/nuttx-config/Kconfig | 17 + .../pi6x/nuttx-config/bootloader/defconfig | 95 ++++ boards/ark/pi6x/nuttx-config/include/board.h | 512 ++++++++++++++++++ .../pi6x/nuttx-config/include/board_dma_map.h | 81 +++ boards/ark/pi6x/nuttx-config/nsh/defconfig | 274 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 ++++++++ .../ark/pi6x/nuttx-config/scripts/script.ld | 229 ++++++++ boards/ark/pi6x/src/CMakeLists.txt | 77 +++ boards/ark/pi6x/src/board_config.h | 402 ++++++++++++++ boards/ark/pi6x/src/bootloader_main.c | 85 +++ boards/ark/pi6x/src/can.c | 142 +++++ boards/ark/pi6x/src/hw_config.h | 129 +++++ boards/ark/pi6x/src/i2c.cpp | 40 ++ boards/ark/pi6x/src/init.c | 293 ++++++++++ boards/ark/pi6x/src/led.c | 234 ++++++++ boards/ark/pi6x/src/mtd.cpp | 55 ++ boards/ark/pi6x/src/sdio.c | 177 ++++++ boards/ark/pi6x/src/spi.cpp | 83 +++ boards/ark/pi6x/src/spix_sync.c | 309 +++++++++++ boards/ark/pi6x/src/spix_sync.h | 42 ++ boards/ark/pi6x/src/timer_config.cpp | 88 +++ boards/ark/pi6x/src/usb.c | 105 ++++ .../px4_work_queue/WorkQueueManager.hpp | 2 +- .../src/bootloader/stm/stm32_common/main.c | 8 + .../broadcom/afbrs50/API/Src/s2pi.c | 6 +- 34 files changed, 3862 insertions(+), 4 deletions(-) create mode 100644 boards/ark/pi6x/bootloader.px4board create mode 100644 boards/ark/pi6x/default.px4board create mode 100755 boards/ark/pi6x/extras/ark_pi6x_bootloader.bin create mode 100644 boards/ark/pi6x/firmware.prototype create mode 100644 boards/ark/pi6x/init/rc.board_defaults create mode 100644 boards/ark/pi6x/init/rc.board_sensors create mode 100644 boards/ark/pi6x/nuttx-config/Kconfig create mode 100644 boards/ark/pi6x/nuttx-config/bootloader/defconfig create mode 100644 boards/ark/pi6x/nuttx-config/include/board.h create mode 100644 boards/ark/pi6x/nuttx-config/include/board_dma_map.h create mode 100644 boards/ark/pi6x/nuttx-config/nsh/defconfig create mode 100644 boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/ark/pi6x/nuttx-config/scripts/script.ld create mode 100644 boards/ark/pi6x/src/CMakeLists.txt create mode 100644 boards/ark/pi6x/src/board_config.h create mode 100644 boards/ark/pi6x/src/bootloader_main.c create mode 100644 boards/ark/pi6x/src/can.c create mode 100644 boards/ark/pi6x/src/hw_config.h create mode 100644 boards/ark/pi6x/src/i2c.cpp create mode 100644 boards/ark/pi6x/src/init.c create mode 100644 boards/ark/pi6x/src/led.c create mode 100644 boards/ark/pi6x/src/mtd.cpp create mode 100644 boards/ark/pi6x/src/sdio.c create mode 100644 boards/ark/pi6x/src/spi.cpp create mode 100644 boards/ark/pi6x/src/spix_sync.c create mode 100644 boards/ark/pi6x/src/spix_sync.h create mode 100644 boards/ark/pi6x/src/timer_config.cpp create mode 100644 boards/ark/pi6x/src/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 04c8c210b94a..0431761e98f1 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -46,6 +46,8 @@ pipeline { "ark_cannode_default", "ark_fmu-v6x_bootloader", "ark_fmu-v6x_default", + "ark_pi6x_bootloader", + "ark_pi6x_default" "atl_mantis-edu_default", "av_x-v1_default", "bitcraze_crazyflie21_default", diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml index cf42be021321..5468e51d2049 100644 --- a/.github/workflows/compile_nuttx.yml +++ b/.github/workflows/compile_nuttx.yml @@ -25,6 +25,7 @@ jobs: ark_can-rtk-gps, ark_cannode, ark_fmu-v6x, + ark_pi6x, ark_septentrio-gps, atl_mantis-edu, av_x-v1, diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index c2a057d68669..ef05fbdbae15 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -181,6 +181,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_fmu-v6x_default + ark_pi6x_bootloader: + short: ark_pi6x_bootloader + buildType: MinSizeRel + settings: + CONFIG: ark_pi6x_bootloader + ark_pi6x_default: + short: ark_pi6x_default + buildType: MinSizeRel + settings: + CONFIG: ark_pi6x_default atl_mantis-edu_default: short: atl_mantis-edu buildType: MinSizeRel diff --git a/boards/ark/pi6x/bootloader.px4board b/boards/ark/pi6x/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/ark/pi6x/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board new file mode 100644 index 000000000000..98f6300f579c --- /dev/null +++ b/boards/ark/pi6x/default.px4board @@ -0,0 +1,70 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS5" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS2" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_COMMON_LIGHT=y +CONFIG_DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA=y +CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +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 +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/ark/pi6x/extras/ark_pi6x_bootloader.bin b/boards/ark/pi6x/extras/ark_pi6x_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..ef4d19d36c9bd09307b24c6b50de52290a9c1753 GIT binary patch literal 46152 zcmeFZdwf$>x<9=3CCP3ZXnH}?3pB|t*fvE2En37&NW$(VXbb2Z1V>Yfx+{!Sz!_Ag z1d3W^<_uDt;o{7oI3tQmQ>e#^wH46uGM>{wJEu??s-S@ubcYtQd(H2=66(yT^M2m< zzxR({KA)Yn_TFo+^{lm?^{nT*s?$iOh9knO?Ek&~?->052M5U2U--h|tv~&x=7Vqh zG~USyAJ4XZ+ZVIp*V02080n`k|{J!c26!kng0Id#8ivIu{#{KEyP01 zMETQjiaYfOZ>}jOO3e^a(guif*C0_=547}^{-&jGY(gCXA4lEk=^Lnkkb4XW~hUv z2}m7)h-7Xh^oc&pp=i;9J_}H0Ir{Amv=+&4;fFeIL`gpDIpmJ3{h6go{TzqFqI7?z zA8j}=e(y)xGG=W>nHeP(bAso%Y5=4N@OT_ny|5P8!Uad>9 zqg+`gTVGX3XKNRC+vOSinO)56>;P#Yc6O0^{c|MIZYQ%@PIo=aFttJpAttiG(3mxk zm>5etzH%xIcNA%+`-m!-kE#Yzetb*6c^@e;^X?Sy z@dmoW!=XP%=7N4}YrG2kl<3z_Uj3Sr#U6$^(-7-qJ@gw}bNIr>dSXd0uD|^F`nXPF zaa_uozbq>Ox!5ct{)Izy)|su$uFVei)b7iVSDg=F=JS}k%Yo=q=G3x+udY735_xvu z^26(yuGoT8|5EZ^D|3n|_}h0S-&oC%F-k$H39$gjKu40N0S|$D$3 zvdVEy=~A|b*+P`dYPQU5C(0*7$xTGem8~9=#MRp{pD#zoF1g03@LWw_a&44S<%2rW zb(xPAYSBU!)>Z8^I?wT0hQ{fqb_Wf7MsDoqT+rj>E|)vwJdDT<^8LvkVoLA6Em!DF zpJyvbcj+U~iDK|v3fz~=cN*uFMV|Hr*5hu%ysF6Eg~0Q8_9XazCe7|8Nbd=TL-?h@L!N_0hb<^0axZlq}_Pd zNPA@}rY$UyIVGN3oX!Oc#PYmdWRA+mZFUU#X$fO7*4m^}#XB7oX%c86F4LriOj1d- zpUa#Ml~1cfX@i?s48?J#R1Z@Qcb2{- zGAQDO1u;fm4;1C@wunYlj-cK6c1Z(Xik+aJq(-b zQ3FYhG{E z1lLPJhW&T>Y3G%UtQ=jJ@0^;k8`n$0EH*1Abn>+N!WX4ITjTzIE>4-R^0V!@rgrWU z5bNeK2$`Gy{av)*|6lr-l{2%8_7QDnm{fLlX-|@KSzm^;v?tkhe_w{Hv}eNH2l_JR zmiAmDJ=m8amG(?5l>0IYOM8q(m3uC4vo?(8wrvjWSpzJjJX=qLirge`T2DINJ;g6VFMr+L)U-l}TfA3Qj1Eb9$I5 zf6%?rU~OY>5><8ymt#C}k8W;{M!KdYIU`wes{C?`#P#xeT~1Qxm%>U#r_&9wj+^aV zj_BId!rw$oFgfgr==ZEIrAldjy_eMqH~r;2dEiWd%lTWU5@2#Z@~2cW-6UtoUsb4U zr1TO{fLc}zU^eCuB}LUp;KGztwNzn*>mS!n($5qI`MwN?w(TcsCNcW%QZsFwZ+jt= z&*ujH7~2iBZ>&mWp*f=wd-|(H89zv}UTHb#DqQ0EJ%z}_O3>;yu%bR%C2`wON^c+lpfzaj}dRaeT#(; zuF+bnY8r{z1S)b@m=leb8;iwX*rXfXH~=6AL`4hYSc)2DYX-{^(oNS?{OXJP2tdl5sRdo zClp<2u&Xoer1t~j@H~Zm0Q1?rQkg)8(2rN+iLeQ9{wYgn)OW^|EKqH>B|f&dm0cij zFVwnIWn3PinOHRLD}hvrenZQT^_6}vP~PQ7==%+z@8OVZG!F2Nci-5^OOs^me|f~h zyvmuFI-*FBQhqyPmWYz4@{+;Fn8KkOMp=oGvheJ|5fgB(f0(vag?&da{ipoCJj?fM zIaYqtVes#1dbX+cJeS7@#}lF)R{5YF>3gb4YCczG=ag5Q-X>%d{p#Q@vHm8W{n z2SR`%9(CU}LV~ecjbuaqqH2z`R{$7nP4vl^BXpnU>Xl|)IU|ywUdOyz^GJcjDgP5@ zB%80|u`@pUO*nKQJh7YENpdcq9G}n307s+j2^XM-_eYFP%&YW^x588=Vos8*OKm2+ zc}t}&_(q87zXPqZ!B-=1b`Y$3BCCP$1&upRw)!+BiE?67>aUm?shc9JuZ4~Q-S?8* zhQ?I+urCqi_BBzS@%uC1FkrF~Ys}|FOxhHSQVW}+ye%;qnwi~<>t+A90Y-UZ zI2ahK_fFJb&=~L5V~(n@O7@NH_VsS&z`3(lUE6DNjl9#rwXIb2MAw}qIhTu`n&lOq zBg=_tkEa0G!~mOUT{a(Ao5nNk;KjTYa*AhFg@(p(=u()UtU0;N!6_?8c@M@n-y|8D z3mUI+r_1QalRxASI%!=E#LCrj!Ejz$1LxJ8A|}(aiw%@JE@&pAX_*GJreYJL{ATFj zfQ67OrOod6CO}*5jlg5Td{b)lX_%Wd*k)*^kbD40v=K;hqL6^+Bc|bi+Bi{4aci-v zCduK@P2qUo@)ff^?Y;R4=wA8 zaP~w=fCQ8sHc4u;S$=2*<(|F`SmcWoGX4VA5FIO{+txTqezHCs;=?OeP>jD}^sJM& zbK5epdSmgm2K+I%7y1I#na)UtHf9UAms5PB%nn*QiQ=n|nMCs|f%QbWPUV1WU-`qK zUhH$HueMXrSQ8y#i`N9{0)6ma?E^UFht~Kkk3H+q`njNqu{8<6*i$2Xw@J#Bg8@$Y zVkA1+CaC~p$30OK#kucESl~UC{~U?pnW34r>irZme>kI>;+_Cwy@>tAfc1Ie5NT=G zlgz*3DgZTOGU=M)lm(-vCMMs6eJF}01(12@E;vq#S<6e=2V6Ezv5zuYI;onrL#f~Q z;1SnfY0z2|{n=~zU=j9?>`{-;Dx0J;_b->l2Z*?58KcY_iqOKT2fJzdvYfpZby4|^ zjuE6sI!07_6dy|R86T^42>xRYRHDrD<;aUY56L?{-GMY&3H$_WY{++45vR-z0?4@XA8(Tn&SPk+e;&4Am;T2%g+uR;;EUQH8*Qys@PB`NUl_b^uvV?5UtBM= zF(-lfS{o>{vSFnXr~Ti6xL#xB{5;k#QEnX;*Xyj``mJjP>jgi3(lT@|KZrV9>3@9CjLS4Ehqw)bYVP1yBbY zTL<`SxIbckpI-IWGl1-A%JV**d46Jn}`&9JG}<+^)Ln8)bKoMsxo%TEl8t8`LwJowg^o7t$8_ zof@=E*Bxz>(hh#>9O=u=HpzlkzpPoh;x7Bfo;Y@b{mGs<)WIp*Va={6B?*TvjL`j} zW_Wj?s`06MjkLuyUi$1jKZ8?>2YIQ@N6a7AaL?&?u+PQqV4jQJaSHFqbJ_SNPt}0p z(mg42FiXMx*uxvNaa0uRbLfP?<30T&A7xD|~8wt)!8jlcq}<(kV4-H&M8>sYIA| zK2*v}<0WS64hi$|^baxkv^u;Sm-nPf%802`B{pVeK}mvK>loK%kXu1P>IU*lz=3DY z^@khi9Ao^*tZrsng8X(1GliLzZC|LG>$%O z7sX$MLu7c7#6@tDnaSAR3?u-{iGG~Bm?U^oWx!3?-earY?OhtrcY*2+e1z7w1;XOTL?q9LY{@c}ChH z=_HalK`NGvmNlTiQ$~uUr`2D9iW^6y^xF^RN^E|Cr0w0rfUi)skP9~nB+J!CdWG1% zK|wem@wc=>+$}ItPb}BE{@}Rg7?bas8}zSKwB&rit@5RiUos${JjW^i;SCbA!z9H7nHWmL z=DFH{>x)ST#dvZoAc7Y)jOp6Gw`(wpLmk`03L2BZmz=rE0kILz?fIcSGGhW%2}>#$ z%L`PK&E0fn^PeiCT$12VkoFdaLw{2lTdm_;KVwn@3^0>Zelw_ErIcU!e;OFAN&t=*O_UNic%x3@ADh@miFSUX8uQ1}87`4Ya^q2?Kw zygyq9{iC6h_o#dll}oY!?dvMZ;!fHfLi07?@rY?KP=ImzN}kq4VWg67IP~&6SyGug ze)btpIP`}>4djS$XeVeUt2`Y(55CYlm0U|TW46JHhtryx&#Cz4rgtc9&jCfDl%4L- zl(Ksso*;EKu=3IebP;_m_XKZqDlEsX3WxqHd^*5U3bcXzfD?-?F~}Ytv5xPG0q@V; zlxi=-DmD5JgYP!B5Ywj-z7jKS8VJy}O4ly!hw(tGTu(Vv%DH?`cdU1lDQPk@o3qCi z5!tSaWl_EJp5;kCI>yhBQqFi5uz^*Q!o&oQIzkg7wBX;Y5u((O{$q`htbEwKevH52 zY74J~SEV)7IW+z#2f0#tmJ~E|wM>MQk8<|oKi6ZG-QyEi)HufZ`5@N1vU?DGy(BIp z$`hl}FNx{PK&IRaJeojGfo`pd;B7e6@|{E>ssE5Du8zg`Nrz=OrSy zEIJw#8}ZF1%n2Po%q8W>A{_pDO-_tovm&RKnUUC#<0Y0kn^?eg{nZhme5ndqJHoD?|35^Y-m}VzQH@mOBSDWY_t7lLICDBi{7QJgBjop(SmmdqytIhE z)v(u2yyMzOO_DL6miQ|CCzP>6^d;f`xpLvo6gX#cLn?C(mj*9!ks;z*=~ z+I$c^_Pe-_;u_dTeMK5^YX2M3wM2bxpRoGD+19GeI^HBEN<5{g)*G2Go`D5BJeRra?;#`*^w zyRPVL1FP%~Q!7kXlM#JBHUf>5$USOkrhMQS?2tiz`R`;9j8k|FH~-(sAguB`;QUzK zbUl&aJPlp@{>pAg0mK z$Owb~`jO~+>=rgw`7lhf+Cd8#XvK*rlq7=cZGhy)_8#FDt!;G@Na3*j3PYem5e^{g4}?Z|Q9OGBO*`Ids!H|LzY^Ddk6G z89G}3kP=A?Z5O<_^C=no%k8BK8HUM{cpUB4FENXuuceoF!6Jz-e` zhd3|`+89=u8D{c@nQ^&27zYjIb!wvh&`1TqivI!c0GSs%46A%IN=z%tsrG^HR)$7b zrAZnMy$5<0#kE)8jmnLB=^AM}xKolftBvH`*haEvcA+Of!UsBKsv*2j%_wH_ANGuw zKT!4F$xRd=GDdT|ZBia~(jD>wBh!&0Pj7n3k^FgzoZa+tYEtoqfKiH*lt8V_x}v%9 zCE55cY1Gh7=~iO*4*3s`mwFlY<&>v{vxZ+W`Q{K!lx zKBs)f2g{KO_~zT=i1$Zpc`;JUB42DVtDJ*o%HxU7XF;=3N|VnAc&y@MBbOo+I0&gX z{CC<85p|8w)oo$SMsWE*8G#;5)S4NSRw)~Sm1w8d%pzZc`l9j~U0**A7q_0D%~|6* ziSmWYi@JzThbVth$Dq)`-{B8~A<&h7$GdUG6l3R&Q2If2sg&MP?sbAxR+0ft0j%Kl zu_>#IS}Xm6P)W5m`b{lzg7kibcctT5(5RPmZjH21oo?WIk8){` zb?LYc%D3kJqM(^ox`qb>_0V5y-0XTo<3e?Yfd{63Jxn0G&^e*+h*I6emL$mx?5UJ* zJ&Sq`jd3!&?tm|S-8P5z*kXApw7O)*B9Gun>Q2LcL+=cpB5Ql`md+C|D#O}8+}sro^#@46mgyt8LK=bT^KBMF?C zC3D%_pwMUP;mFD!Zajm$vxjh2&&oEw-<}6JZd=g?=x)=uuqI;amC2x>jPKz%qw}2S zUC6x#zewAR`9YhlF=#IrC7tt&CNo*?PSjU{npPH}KKshTwmp}1 zwyQ$E&#oKPUV--nHyIu#!m_CLj#5~)hBf~*z?qi>i23dSm7uF37yK^3n4S;78zjJr z%>hn46cEwIUn4Z{Y-H|Q8^WQCmhgq>T#xS*=v>2VOXZ`Xlp&oMZxYMtt~DCEYFgjPI?2lXQ%iAs4((Yh8*S*~6GCepNa;RsPmoK-hjB_PeFbq(~#70q{#)upK@ui6x?ZMBQZaS{B0!u`wZ3%6cmZvR?E6+yuLy8lB%B8q84ic;)e)VwF!)DLJ zCMl}*{UKjX#4Ksg1DKD|sJ=#NbUqAhr;;a?RRuNrj#(*Y!6`z{Eq(CrFH6h z5|hQY30X7!FCK8f%P`UcEl=uHuV;>I?zhh$?}Ju*{+z2%H+VMCr;kka9amrQ(0ATP zHh6NJ_{Mg&A=N`UEv5PWJ_l=7;u$+2iQ!}P3C^Yfn=Q1UjipBd2LOrha`#Hy!*lT{ zaAx#;_*>`0HEKOP_M8vXx^^tBDjdsqR<`!F;thEDhuhWHp$(VD-^4=WZZM!%&`-Bk{%2 z@=ZfjzfM~0d;)2{jtHM>ZH>v&)Ai<#x)q5ll3Yty>{)iw*Nz&&&%fFpsZ+C+sXK#O z^|Z#BM0sYYVueMDEv9deo;S?2LPzuKAssjv3hP(Uh*5il4eR~c@7kfZy`NT6-e!km z#lxC5-{lSKb6}@6Lf1laO53)n)i&+`V=cw(>03(s$!c&d&TXpKV34S0*KQ_edcVOy z@30rnq4!S3#?^V+)lCLgaSTEu9!QbS1RMwIWKOX$wrtT)tnA5l^#w!FmxP*)ZAtxP zeR2x}zIYQ_tdkAWkv?zICe@34SNtY*1LW6R29K(n2(_AT9BmJvoS`SOyS_?gw}-c> zwPYl8XqZ@NE+Hbrjf6I1zb(MrXp3{C=OZOHhN1Opiss*jUa+8fhmFz#=flZT9on(_ zxQBODT3{F1UMNaN3080OK%|8zMhy>+VU#h|*h2Y6L*rJp-j*!o`3!)qCv1Rrj91mgh)lP*cSa#{ z%mzdoPy>bH5u_A~pCOGxAtSfNM6q=t`uWR+F+S+T7cTTkq?j=T8Qr#2_B5O7?4?QPL9Vieii6&7~H~#9njbI9~V`md=phjgQA>$w;!uJL% znU2~%%rITWW8=cT2Ok&>Ln?u{>l@>WW$;b&RU*dRo-VgX0G}=%6s8LN6rN2$}lKB+qT);k9*k$67sPK^?=E z5a{C<$a~5R&F{j8-_Y24o=u!13-biowkKw#3FbVFRy68Ugh zj$8p7`BHhgeB85&<2rIGK?UWc@|?;F*w3|)C(7Z+126a)v{h|?_ajSX-(~Omg_WXm zh%>f0QSZX?a#>#zC#Txu+=c_fqo`SXdp4f)#(lhyJ1kh!*yR#kG`i#3$1S*E~QZ~w)U}8 zOeM>me&g|b=27p34P>hKTF{B7R=q`Sj!!{;Pq`!A^@4-_92|C@t~-O7sA^lOq?X}l zGW+lPxPfvUcc-Ve#TPTZT$0|*3~4Oe{fz#|&|n=j3u<-P+q_uD2cBcUQws)FRs1 z%ih%`@(X1VKK}=t53yiWtD>In5qv%9T$`SW`C&OX<}Q!gCU?okLOKRj2VHB^r=m3t zH%~jHah;W4ma5+MMBd>m3!T-4PNwAeqG)+MGt-(_H-nneDvgDth1LUkKw>K4S>kh7 za^+l;vz&R`U8d z`Jj5QfjnoHelPREN!;E-YIhRXIYE!aHB=9=QsK!J=&+PVzS?ylNm|BCDE;d0>-Y)n zZ*oa@6t&D%y!T&c&vQC^HaOu4$v747LeM+snfcD@!(LG-*gQj{1`qbT^Y2+D6_mZNpjpY;BkJL-as5q>b$ICeJvYt`K>`&jbX+34UyzXP4Hrvt(+rS_b%(nYsC3r!CJ|i^C@g97nru2;0oNc(g zhVrNBX1CMg^W+&_N^`b!KEPexx*As5Je~Dxf7DVyOhNDlt-hu)8yccG=sruorrtm9 z>KI@FNiw>q_ssk2;+#j;MD0fKb3%-d0L{-hD(Pb!xOL@yb2x4d?G3Q|M|_EdqBfN; znBx;+5o|>+S`#f#ZG=>&qV-TuTXz#IvnF7{0Jt5W5&P0e=ymut7$CD%(XsgvuP1KZ zNo_($+&pMM3c7Uqj&_w_q%q9}{!M`taTM(_%7BV=(UpdXM-e1I+Fn(oyPEovF45`R zEtQL##OluZ>TT0 zfN?vw-0kdn-x*g-6px*A*3B2ImoSSLITYTp7(zzkHq6vb0Z^w0sS) z74vPN_?oq`UV92wxne#qR^IMlwhn$y<5-A6u-h6r$iu0V(o%Og$mcf5zDN3WQ&^S1 znN_)ake`dIf>qgjSe3as3G<9`#CICE7ExgaE8>2v6b?j%Sy5wTjEzL_7(`7;Qn|*R zQ2DWz>0o9L`Z?2ZsO&vDCiZb0u`4E`DbczO(npd8~Qr_Wj4 z1WEmKSi+i@FeYh7S@cV91^v=e-GMgQpn+j5&)R9* z6pjz@EF8KsO!4zwI**_;0;M&W6N)PWE~QaZol*KTruS}6A|}>jhsD4oy>I;?+{v?J+9Tg^XFFc)f$D*QttOPyN{d*)Lbo5pcLJiE+@8?k?4zsvlez4bu*U9fimSF^KIzIJOXdr?^X)V~cvzw>C8N?um~*c})o;9#iv$%~+X-)%=3L1SUznfxKsOr0Lkv zQe4zq{~v2qYcuFi|`YX4K+tW?$5 zDsLY1b^IO;U09u@2;3xpa;3Zc<|cZ_YY(626JlTy;kwHz=ad_z`Q=ebyb6+#flrV) zSYPfB+oV2NQ1_2eIWeBl_$or43Fns(6XmJkAyzPB9_9BBBNq-`JK8N9u@9T2E^uq3 zV(uN&O34&(KC$4tV$Q4)AB`E(6xpP|fb*jGhV&(7W;irybi4YPO&dH)B3P)*<4iZE z-%yKZu-D?e2CM_%*4)qPuvJpLNWQEZg6@U+r$RhRA_2a1Kq+?p9JsfIl zVXL)83z&pO(E21K!0&BwHI36<{PPHn1PuRTx zWVI_Bz2x%NM^`EmL*@MyBQ(bcJ&^7m7}7Jc zZmjralH!TiwDG|SpdR5+@zAX9gX+YpgKCQ5pqgfiAAEXrn|e*F&~Qz|yFq>Y)Xw-z zg0M)BpiUd+rpkm>e;quk!l5@tehsVV`hNF*245BJ=cJ{5e3H0E2~1sA zrCWdbiTxyJegE41(Yg~+_bvWt&9gdxyxzZ#9t$iv#9Yt$CB>kfy5`dWd%fuYv?1U zz1Pq6f6x~@flQmzc3N%SkUmvA6!X;I)ci*X?3yb!{8qjB#djc++Lfgn{-)X;5& za0bA+c!Pb~K1mmxMD{{AX^+bo+#F<{3x}=@{;4+(wB+pIZ$U#?OM&zdcG0JheS;QvD@ z=6{R`q9yY7=YlTC=>E%Z2+Ws6>>7JjTBiw7mK(Vjv5sjg*uw@tMzjXS{5F5Oi44Um znqCrn67a-ce&O*MO*>VMjl%RS(v|>S|HPc-Vzz`sUX{LMw$ss}{;IS@ICOd7^}s0| z>4=WV*{>v;kV`vxCqUvd=B(Mb<|ZB6A&9j0A#m(-(C2XI`XNK)Nr85J2e-@J#O|WcDNF@8{U9H< zxXDA_NC{>a^(_{H>B16$se8(Q_t(*JKOTWDZs>mkw7%aB9R9lCnbF$W@(rm**PD*L zE!RmIgHNe*BJcL5g+osb%zCEQ^@=KZ-}>5AvS1ynD69eWrvA;SyaM|P zHNgqM_9q6OADDpHE}^SYO@p3$`8rBDDLy^__40MBMGfrX*Iz#VMqCM~-Yl^{48B9h zQJxT#Zx&tWPMktOd8OmflvY8v(7N!r=bf+Uy#6!qQP3DSuiImmIOx~57iu7X67dXl zt_97HLOvQ*8TjWwSFBQgrVl(B{k94`FqKZcQ;8UrpeYAWC1~(vSFJ4LZ-=ZQXG=>^ zYg7*U*OHH#&Nd8(-cf;>sQ+G7kj_V}Ow_ItZNqx|IhkswKMMc2Y(mTytdKeCqb9wS zy=pkL4LP%9k%mJL4oz~0O_X!H(trs27+i5UO9W{a(jufqNM)ol(psdoNcSS$i}WL; zAH~6j;sJ*TzAqV9KCX0J#w^$j5bf2eE?>6{*tUEP?fDqYbZmc9qQYXJFAx>78n}-c z&|_Wb3+`ryI-V)AUpo@&AFYKRJQ(@^X7uShpnnfPjR?^GRn&Go9NIsyshE{G34E;H zp?cC7$>ABb9A3jdN-X*zHaR`--eoEG^TD+m@FaE@IOr8s?G4O~8ucFgGG#rl%c)U| z>?_u;>|^j|k6Kc7#!tlbYwc4`Hnggl<*lkMA>HOxO=hpEH$#J)$mDHRZ<(XB(l0h5 zw_6=Q|D2y#DvBu%v?7j}L;N=NgU)ZcZ=P4Y@Af_Lfugu}#>1J0LT`+Um56%mVr~if z#Y!jEx>)`b_g(WWmB&D7qp~)cG8Eb|x@UPZ^$f_{1FQ6FswmGeIh9sUL~R(ag_OTN z;~~oLp|>FS;-rxRItwB&7xxA9-WfSvgcQIACRQv3x5VvPS`1x1Kb`&yk$-*U-w^pv zj{F-zGvihGS%#@*6la?(3Y(9r$&0QlIjZI_I*Q$L8qPLJUu2X`c_ix~b|26`lT$V6 zovPs;r)o^Eb142PID;W<$}CQ&rE(*sTqF~v=Al$BO6fPF)I@i3(av&;dy74HSEiPj zmGyJX{p%Q9bIeMZLFAx$aruOjo#h)WJ3XVYJwtys@F?|Eu@8l$$QdDVuM0$vEB4J8 zG7SAcT@T$zPk@J|I7W35-Bcc<7ie`iuGryvP+&dTi1R{Xipf^8tH!|`|HtVd+zEnn zK}g-Dt0#Q)V=dD&KA;VixFQ;Lus~%Ia}96P7ULW6M@b@?(48WN0KR#M4gcr+w5ET( zuey4#Mtp^@fhBXXstIOrbZaE#X3iEvMSXE9AFx$s`aH&RjICLX?a`lKh8V()9ngG624?<;B z<>0H?_jxE_l6oR>Y%Kh2;+jT6d)}@pjQY)JBth1r?Fp(QUDL}ZV!xiSuTu1-$O%4^ zyuqP4zRhzKF%z8cbND-?O1ltiSby0YuRF%YKof5zo$&RwEfEF+iO?TLqrqPVZTxe1 zd&HCQhc@sI)o$);uy{UD?Q^Jxy{h?6=+IuqSX1uLh5Vfu;ZKZZ@`t*l_D>fbJI`v9 zT=gEo_c!@NPoj*sdV|Y_|HU%=5?I!`*pn*JIzCNZB)94e?Z?lvh7Fz=U#I+$CnZu| za2Y-GWkz8b#yQ`U64`4vV2o*mb~v;KdJ!$+u|dsieh4qIv;opCP$;{Z!b@^zLH3y0 zrVCEgOi|)B`yJPJQZJ@y;YN(hjAL}ycsQ(uMQ2mxu+JjzkzaFUAOBLW^TheSluvp@ zc~M$?mi~n3Do^puzuhy%Gu98AwAd34%?ww_LgdsVIu^9%O!yM3%~POJut~YNpBH`? zqy1SRUHWgFghDydKT>P751y~)q0r}ur=an0LL*jfSnws=uyTrq1A43*Xf{1@@JV9mW`glKpZ>?xuzocIaU>Nk^mnnM1A{85b?qI!=bNRQf1a-#5;ILN}GLNUkzeV zQ{`9>EfE9y?Z!K+k9z3VIR^doyav>R=yCcT+vM;NORC2xRTajO>v&QrV`jv zsrO}7VUi~lSd6Qn(Fu&!$U@19iC+z|(~a;J)s?gw(Iz)12y3FUcGTpF#+i^$cFw-d z5l`&6bl@GB=Rlv7>jrW9gJE~!P$&<+wvZ%Bxnqe9te0xYsn;$&SLR=z!>2A(7`_HQ z0DZNE0$DyYqQ;@UYoNZF(QjzXci+`m5ybF>{}C&ak^M*bEKoZFC&xK=ws3$h`prMT z+59hW=xEVV&B*?J3z0tp1!AB#qOipuL_Fobg|Ofv60MF0jpBBe*_a(fc}$I*x6um= zE>>r49Spc5 zq6q2@Jtl2di&mP3$QZ435m8D`&?%g4V7;}gK2r83_~yQ=uE1LOrt+Xe7ol{=)eDuC zmCI5oURxh}!7(0>#baz-cz2eGS<{8*o-sJ1y(8o|K9;y<1>iG9Y^<)y^unc z4@tAr zx6+tAGvyo@i(q3mI6*xc;43}``)IQO4L%Q_kC`~P+*`+Et>bGVZlo=q@eGH&m?;g$ ziRzd?!l@48M(X84D#M}S_h_%jN#;sAXM0B&8`pLQ-qvTZhXBS%n@XD+h;d`hS629Z zz!Y5xe0bLD+{Tt9sV1_jx#^%JZhF?zjSGozJ+9;T62UQi-HwzhF?k7VN%o-M zkV?J1SQjt3CvR~GZAmJVfwOzkNOs7dm^u`i0S_N)^BNCM%hq`OJh}5%pnV^d*Fb{t zE~GntigN>2t*!Z02kU>o+$;qH%nTtfBj+6Mz$?x_A25M;X|1d(q&mvj+Yy)F6gw~W zj=0j(YOePnpk_p?hidAulg&QlxP06>x9`~YLf8dCx8JTO0=)>BESl;XL8mPAToLL+ z`H#5s-@wm>Og*J~w$wqpOtl$A`L^br;FNg8zUQ%ZRyh*Ye8Z>k4xI8u9gch2nNHub zTZ3(&k3y`aP;yDP<<9GTCuohowJiy$DgNfRcY2B0@zZ0AmZ$&vi4=nZXlMLZkNLHE`{ei11_xP4*VPVV}XO0$@-?_ z?*t!@&p~@@;;+U3L-A&RX1{mY%MGr6)3VmUJHedzcz?I%Zj2?{A@-bE3u}S(l@vW7Q7$5{m&Ec1S>H9dpE=?r@4jDBYnK#Q|b5aB`UwG38Nyk z?2zaf6iLY~b0AZNr{ff|VXw6Pi+6$##INtK-XANWK3BXsCa8;v&ldJ(E4sL>mU#1_ z3v3+X>W6+$&stJqSSH8O_L9!oo*X&76Z05Ts+eMu6n(t2jkc8B!i(@Ecj!-=b+7bt zx|sI2C7hE03ckJY?I0tl{##w-T3V9Fc@f3nj+h&^7t-2!%+(_$u$#m`;?}opLHyF6 zdxe;oUO{Wb>ZokGSt7Z1`Zs0`I98!RX#7y#q3D&0aH?J*|}}0K|cPvuB~%(Pg1O*eP_FvT|4Jy zos0#P%&tAXf*{h9SnA$t$?54?tr3|#3N-<4zm0Tan*fi@B-bIw!Ip3;xi(peiBI>> zmY~<(Q8fAe2IjfHK*qo+E(KlG-(Khpe5oyJVe-BX(6Qj_wiNO>n=%JH^A(IphV=ar z5n-8blKAeJV0e}-GI~~-mZ7CfC3@z`f|G#jv5ycz@LF#S%i}y!T9)6j({W>qu&-3H z3CE3fs>ZuI{h7HOR%80fv(WuC1;e*-{_7$&a)0<_Zk+%3>J-~dtEp3qTqd+k24G96 zGF@P9u*y^;w7qanfTo(Q+Y9N}nw>iTfpl5}&WJ$0(3k9FW^jLa5B;1joC%oTB!UrF zIxf;04x@fUmNY$katp0rgx}t;k<#zzI9lafPO&$@rW6x}>7%(;*?cm&pWH`hGr481 z`F?mc(mCS0rbi$=p`F(8Nsz=&Ge_s!W_~9a6F=qi=p7HJV}my4r2w;&;#SGr+LoAL z0ZTPl+gfbqhg{IT4b-+Is!8eF3;z=6hGmGk;lluJodqVoAF!H_1(@lt1!H4BZtw>_ z#cE-MaY0iI*3#@>BLd!{i|+td^7H17^GmJ+Uo*Fj;dkNOmwR>EE1lm4-c3;h6rL1d zF0{wjpKD`o`x>ivSv=ows$fAyD&yDs4_r2_tnkwnht(GIsdPf+4NIV<0WG+jWM?ae z7%if>i*Z-pJBP^t+$mVY+BQ0FoWBfl9ykNaE4&^H&pVulGQg*uZJ;HXZA5w7o2@Xh zuDKbYe%?z5y{=0J7Id#KriX>jjq_(K2{EW~FctGnlsCQLG1!M(iE2u&4chZRcysz& zOL7!LEd4$eYtoMBoK$FnwQYwS-b+WlL#a3eP8e#~)2of4Bf7o&Q)!O|V-#1~)BVWr z+m~u~b%>g~TI_wT({Uw`27ANS0PXRlAM3HAjd>@yD4zClE@=Ns?qowuPGM(^buO$X zoN~t$7k(35t{Yy|#02@c6FB#Q=^*AW1E6ZkkFkU1@87VvY5)&;zh_PB~T9ZDlZ1;n3#cV_y|x%u_HTOdCeM*dTr$ zI0G+;;{Mj+(tdt*M`TW?m?@q_cQ@ehR|34>T#_RoN}ovof&aS#sr}wk#t%J1H=Ebh za9?1~B`urU!^Yp%zj%Ki>Yx;WQa$*@VUNT9+cic-=xkU(7o#hl)?@H9H@q*sI5+$A zy}dlyJ@;)y!)jgg4l%p(T$80WU+tD|L3`vrZIIPk<>Zz{=CzTveU`S$rS@>~r`uAY zd)Ee;$a|~VWJbOB8C#~AdjJb-)h z;y?I}VKBjO?)hSs#%43q{dzF;LYPcBlmb3UTKve(kKE#kMC|Awj4@uD5iK8)1-(+-3ci1AYx(;qM1y!^R~h9^wl=$^pa z$QPOpGRO_re^VIur(V5=nJvsZ07}^FpW&O*^VMo5FV*#1=)13xZ1Ar9kgK~$p0ItR zi~Hln9MtfaNd0_Q!#DgB%uFwy>w+5Lw7MJTuk5a$f58w(&sc+}9QTYwwsfV@lck+F z^JD9&1=13UY%hj|`A=aIwCV3g1&x8Bvs?!Vnxkhp{jfPH9X(vAhvL=mYR%;p}5}mevG}IQRPw87@_rl8A zO;lS~1%1r2QGW8dla~V2hyDEldS=iafNR`IT9WEA{x(2zJ5T=hs&w}hQh(rY=e1?i zQccqsf5!Fcoy`vHY%RASs^OJhP0V2EzLCDlhDxDV!&_Z-j=pmKSW_?~KKVqcr0XVT zTIUC7q5tG(Sn)SOhNMuKAq9QV#k*d{o^T{U@p+)lER{$K>d^s5XQEEGtFQcbKyqjH8XDnYZDzi?>5+mU(8W}ssc4>6In<`C6I5M?fWIG}OGc_cJW zAs+r3*0o8>2sqZmkkyGY2d8y$U9oP~l3K-gTh}7KKXS@&LGvEnAm01%{z@0Ls+Mm8 z6CiJ-8%ZW&1m}4?oYDbvaR;F1yWpo5iI_DsSAa(f`Ue9hlry5d0Nq9)ygO*(7C9Ep z5t>({-^`n2$}&?p)P-+#UCd0a%Ea;0F8i5X#3Xv4|Bd(%#@siQ!yDLu^Bm*m-HBLPi;w;@H@WD49*^j2 zoQAMAuW64gHnApNS*6Yp_fW6&7TV`zz{9#bJtqWQq>w>tEP7 zsfvBRQ-wdKa!2^I+W%6#52r9yomQ2tnByBhQH8Q+a4r&qy7Sd*eK_+8HZ`K;ZX_79 zIbm)KHC26h*$OI;ginS@B0 zjt%l;J`1tJ8&02t%o#U6A(`-IFYH{C!t`sFJ00N7zbv{E`R~L3x*{czJ_UUBOb#bv z@Mg^x&E9ZG8_u29@Bb=5Yd(urO64PV7d^X(gM{?b2Ash#g*9PhAlYok3^LGv;B+(S zH*umkeNH&#g)qj|w#PB4lidY72c^2bCa zZ;!DhLB=ns;2rBwP&6c&GuKPC3VruT$Q1UWWp}dV6IatJ;qT&ha~Ky~)}OttGBZ$~ z>cGF{fh!BT&AioW@wGdJoMxrI2nPT&MeBErogU$Cs^LS{|7=FP9aR4|D5dsMSq%K;AE`YS_o=s@0$+y4W$t@S8B4hs zPgCG%?uZ)>hp-!C1)QUU!glaK!7;M<-g8px|A1?tlQ@N)Kojh{(LcI+M}X%WihWLr zy;F((UrOw4h`mm0@ojPH&=)s5dEfIl-#pt(IkfP5ex%gjNBn2pKz_Oz{)H0mjn2|P??e0w^E+f3!H`RU;d!H{St#je8^r1gHKqigJ!a19kj)f zL;ry3MjP*Q`+?cyil)^)D`HlDLbN^Art;}A(_I2+HzOxP!d z^(_U@7ia{&D$p@H)V%|xKG`_C^Sd1NEN~FuH)9M?9Z>lh`u;ueZh_iiCM|bG- zA-atRHq2FTgtF?+tl-krZdIDjz1W4b1mU80y4?wV3RTZ{-eREWM59%oQ8=N{>=atO zM0tewg(#0mg*q|dL_*gv!&PkGgnCm0QE;;@%B3p{NNLdDB)p*6ovo`>(^W;l%{j)J z?nix1hXbCYXoAi%_i}4Fu)}wOHgePbf^tGoG+3g+HI-)<)(T>se{^Pzm|p)fcmU1_ z?(Rd@X6R8JsEvheaG1NaHog9}rF8BBnSAGxYS64N5%s6wgKdJG2M{+2&4ds)L+>Pd zE>uK)fHQlCX?bjU1avN;ueqFqY{?$vMCgcN-I6b0TCPD~*i%lS#Jk*tG%i$>HnOoF z15uP`UwYYS!lhZO`3L^P*-5%)P0HS>%B}^4!)=3wihbc7X<jgH;#I z{d@KTZ)7*5yI5+rTi=K`1(IR;=aa}5*=9VwG~6`@@^B$JWqQIT%n`ShZJl;Z9&0!T zY{#(r$oiLY&O%{BmyU3;#5v#-ADmVMu74SHH$wX{ib-!6>ci?QtqE?(Xc@q9Y)qZW>_Zaqq9@e1*3c=VAllBhy2g^&Q|h$qm=);d@46# zy4t){Z}pAg9dT@vtg7plVgd@*E2z~_jo#Zi`@PWB+RnM}p{;~DO53!1DcW*lg1ub?3$e{_X?G?;C(K8mha>IN<%>XHpqA{7>Xx^V7ll z@<#LWWSokk7vZFZG~q000m4NjE>>l*LQ#a zqG?N!7+D{S(DO1 zWy8TeYzE%YfE2YSMyvjYxK#UkFM7jM{GKS^D9BR|K+6%9Q+R^U3oKNlOQg15=dw+Cyjqs^>7bS((Rf>qVHysI29|y^0J7)fwwB>IjRLdUmB>9UuQM zkjO4jU8$Kl12Ze?RDGa2gb-$&&C>rOv#sM=D200zNebTv6EwxSt^YiW($|0CH!a86 zRR0{x(py>=)gI{2^Y@-J;8SzJNsbA>rqIeN-x~j9`+@c_{xIf7S_xv8foBU`_0KQ{ zR;xe5x=WZ%L}AcK-E0F^$%fT!MdeGACb;J&QlQ{-&fin9>Yre!}lN@xGDW3 z6RT0#wZ`|azqocl%lp?itvzw|L+2aUH?3Bi+0{QfiU0cao`#0k-g*DJb?tb!|%i9vSv?0b3e^w@|kBsrrh`B>Luho|JwTmhI?FID2VD6cG=r3Uw`V> z`N811)kg%6X*uhs&aQx3Bk9DTH18uNH<;;I@=xvqX!ZR|W9t)_f3a|G`POL%l=X@b zUw2y%RI_t$R&#g%mscjl@Vrl7WMk^kvjxzUN5LBi(UVGQs0o&w;U2wZeEqvtBj{1A zs^S7Xdzg#UI=kUgRdcBJ+mW`bFhU^`869_1xVT*3+m7rTLAQ z`X@9`-CQD`Vy{o>pK%XIDWI#_OD9Mgcb>QpRQ5MY?P-8(PPBrxwyJ+*jdEAkT5H4V ztCkXtx2|?j3*Wu&T2*O&?YjPP!!Ks0Q>FQf`Q;0imb;>-A^hsP(si|i>p?ji=f<44 zI4CP0aewwYrd2Mjs$I8?>#n+1S-#6^I1=uuszoe=3QrCPIy$+)5Y$-}R>u<;2WRt( zV_YFj?!Cv!C+r7cgApE>i?@RlM>-jx@pagXP%9If&UWBiFtff1YX=KGqknq-Z;Vgg zp`eH&W&>|0v?zrh5^b(eoyovT8XACPjxD({8**=HkbI-QW`qQi)4mm{M!9I7o%Ip4 z#1fqLpj7k`?V0Y}Q{D0o+Y#Vt9O)@K41|u%{fVkE+~jIp<=KJi;4misZsj8mmblx| z;)q%K$jX+LK%#LxvTEe2aFebiQ~b)wnIcwZ+hfu82+1Ui2|V!=GpL=2YMV>6B!p^bTc5+m zlBc-ekacyM68-oGWnJ2c;s*=Q0CiR9xU9h*Hr$4|gg1i~$(DOqQ!;GEYDkHq-ZqE! ztF+go{VM8=%S2s_2%z-FUv+Q3#$}-o8);vq8~=;K7TCU6SQdwIku2_;2HqRZjW3~Z z3R}DrpJ2KLYZ(mhF&$w=427I$j94Zz6YLHF(JmF&vCzTYIgL(^h_1et7wW46#m&IT zVc_G2=Axjqw~vkO!p^4%a#ljeCp`7w!6FCl-f3`+C${3=s7m1W>_BaWO7=bC3d z^C~oxiIVzHg_7dG%$ry`;|$IqM!9*j+0B6y-Q-NOGv9(9280U}`XPp%kE1x1BY|0ePD}QoUK)RLk%96ucn5n!{)28eAgiA&mz+6oBLQ2k8nPT5s z0SlA?$S0-{5A(Zv>UYzFSG-Q#zu<)Y1(23v9Gvk_UM}U|Jh;o`%ujoo<g2>qi@7HPJ2IuG}nEexfRAq zeCjNm;;Vc^ROwUqr%daABOm??My=5dF7{D*lX16mr(A2?y>f#$A?0q5c5F7qGj6qJ zc=93N`#Iw7t~rQ!d!DY5Ycrb(qsV;J&5S#zHQC3*oK(Za3Gz)-X8M|cre#^j>k5D6 zV~mmYNO2yJ$Ex7Z#%TL6{2TehIq8kWcc8sLT4cjgyLqF*K73Z21lNBb%+!p2RJYc&hQx%FRK(kedk0VE$ps+AVbd(Hh%42V=9!AKK9# z2!8JUqxJ7+e|*s(t4?rPCFSGmIbh!0g+23k>-P{XjZ+2s#@Al+#`uDs_LV+Z zn}vn}?wkmL)FMV%C3HZ@KEW?Oq_F>VUa&`j&YcH3_l#|ay!npEZkvGYrb^NGBfAk# zbvxp&`)~Megzff%p;x*;(4Zi@QR=Taqd->!XRG84=<4m5v)38x+s~|h-3>gbR$6^` zYa_oQZ5t(LIMv~Mu&)GG|LgKP-1+(lRck$Tq@iz~1f3ESJ>LN=$7fyiHgvymRz-V6 zTEB4y72r&2l(8xkSi4DWw8wCwU;Pi<{sioi!mz*IWz}Jilz=@_Sp9;Sj}_daa&N+x z9}tQ*%}lSK9((m)q_H3Sqfi>OKiUr(?3{Oh?Gikr{ZV>oe{_d$mtdb9dXM%;C3ug% z%}s9dmel_K=G)U_JC)fF`<4bv2+z^G}1Z;&B5PxyD0 zsI7Gd-ltMm18=g!^^B{~MRjHrZ`Im#)Edyh^195*Nh`)z^c9;Y>d zsDS4)VN)2C7VTAh3eQ!U9|*-7c9&ScCLpb&qzUMjcRG*CnoOHHx5;K=+ldZYariH? zP=^yZhTLq#y1RbW`xJjY;?q>aOjHtlv?naMV6L6YkWl(GHI0#abDl3eQoLZ`fZO|?|+TsgPqkmwxP>amF2BwFdY#6z;i_LXdKY?cMG4`hr4-)p%6fpPJLbs_GrkVbE90YaJi{G>8rQH1xmsC!U=&#m`s| zzgpgqsWTZ8>=>!FnX@~Gt;XoxSNZ~IE?m`YEiJWnwUt)O{MHNA!u2Jq4=fs7{K>`W z9O1fUUX@(2?v%U+$QaLACyV+SobONFbk@@+wc)gvEXd&8O8RrpyWWKbMrcr->Q;*f zK|{O_e$Iz*JK!=K*4M4KN6auJ{JXps6uceSNbhvpA;)nDJ2mBMHED^07a<*>GLNW=_1 z0oic<1=!@-x8}zus^u8mYxQkUR?G2D)9RAdudV)mb;6p`HC`a9?0;g+lZ&1l^Hj-G zEAXcA#Gry|Ie~efT2WRlo1C+K;ksY@)@rNeq|9o0w6j`HbXdkz%VXNA44q#9L~6 zxz+MSxJkxpc`{;5L5!(}d$5A~Dha!m{j!Pqtc`L*6>JI;t!+B} z6$_dZn>R8G_yEPSR%Rx4$w|!7$W1*^@rqU5l8c`9Yyh~#EWGU@g!D*j z0}Y4>s3A+N9CrfN^y>^;(>n4^h%B1`s<-eZo@ zrS|5BGYbs&FkgK4unq&Hn(0Xo@J@bE_E=<3twtO!j)3GK^L^f1iIKY<(q8wpk|gkb z;x1qa9Bm56$?X@QZ8nQx=eTi2X#1C;^Tf9lf%BBwlibz<+30ZKJVUPb1R>+iZ(3+w zh+3b0X)~~*gvjl7BX_3pq|BT``&SgpIBz~*@GBdxG8f?L)tgsE;(41Nw#Y*JoHLNP z;&KdGy0r72hz>5Ca>GW=E4+FxqC>?|K4u{wAGA_BvoC!q%tL!av)xJebRGHvU4_0t zSLba9pwGlW9}E&BY>;Gwbwi(vrH^c_s%U6GH7K@4mLgFDgIZVHFBu3uah{yWSi5@Y zRNEnYw#y8z#bo61UDPzSg-+2khCf0^*lmK&$JR8fQ5saXEJ725q!mmko`txGeDlD}QpB z*yS;x&GA*~TiB2COOFR=uFCTN9n?WkI@Pa*)+7BKxTS>#T`1@(K^njp4|#}EXbXYY zwh=m>*``Xe_908JBZt}+=$HnWT}Xz`Q1Ug{Ic3R^DlsjwnJU}8dhmYeRJgY{yole( z!2&1r)GCRinvZ(0L&}Wwg>)9oksolA`AX91rFURY2Qx>s2u%QUY9ot{%j^M`M0BI! zct+|q=<2|_4bM#h*FGb%5&DFVtKN*%ZZ~v$%$+!e=8J;TUxPPvgy}p!7cv6OL_5G? zVw6o)QB%iK3*9fuahb65!gB|Kbe#P)EI~8hOvvHg-NOCu{6+qLvY0zw<|~|Hu6PC# zfJcHwv~mfWojO;K^eN6xNeaMMIn`Beht6TX-8PNpyQJ^IJ*NA8HsC5syC5%h!F~75 zIFMSfoxd4_+TH+N7CK-5vzM#jMMz?1j&o(C$k2)4vhJ$LNa=P*;~ZTES4=I&RAi*; z++$`8$s9AC`IZFBasHL(HrtYllkIVKz9Pds)x$TqawejMa0K5$*wNVpNad5HUfeKc0Wh_*z8tK2&Z z)n~px%SKU}iQ*Y=seOzXCjvo7{2Gp#zC;NkLUsxGFT7Oe7OXc^@30Svd_V8X0WV^) zUGLh5-5SY(P75#-@|KOfWfLDS2UeUZt^kWQL&bYs50zPN(b-vCFU=sTcXTxNSkn4B055mD>%xh@C;{jAA8{`udfd zef_EKTYdf1#we6}kee@i*7YTj0Cw9~xdy|A-2ithc+*3`mn0j*j%m~mD|~8Ph3;wZ zsTOPMwm}nyr7Unq`ZR+;wQ0D6+{;6n40~`Q^t9$T(M`b4*oxj}`}(5lF<8lbjQJXH z_IOvT>UZ~{Z-s1z4QPdo_zKj>8`N3`w|W=p${oXrr63Ll4d(omq7{08oQ(6 z6Z7Pq`Vh?0Uf{DiUf{Q^b&l(-^U_ zP&h{#W*x0-Z2$0@%ec2Ggz8U-_qK8qu6Xxbk2U?lK177H;vAgA_Y83DFB}AJlFsot zo(y#z+Q?-eLcKKfu#6Tr&F_LAvu@7guqMT&>YEDeG!j0BM8$fv+92^p-tIz~O^44d z9ddXH%qS-(S6dfd(>vILvF-?PcCXqdhGJWO#12&H%r1-E&Y7p4gVp><(>1+93=!aYjSh`hO+6@?@PWN=?G#5q@(J@XtiPX&nQqsFQddUqGz4ad9S zbKraXo0i(QBj$F*BzlbOh@+N}%6d>Gfz~5_J=sy+*s6*6HYmM<7&LP+U%^psGFg8= zQ0Y5QPjKG%0p=RKTT|zD!2*nl+sYl(>JcW@v6CA1vnC?HiFC*5Si_Sk7>uCz?YG_p-INU?n=h==_~NS1}4k9m%NZa1VU z!l(PCjX;Kn6#i3&;~H4@^#l7}Wiq<>#Kfl(?NLu%^O~OOQ0$A4eI3G65X1$Iyq!)+I+_&?e(thvf;$w z=V}Y(v-jDtHlBbz%7lrHoN=CQ*i&ZP$fsh&QfSOX*yh>dpOU@vVA(BXn}og}Dpw9l z6?#UtuS~9JdtJBFX9)xP2u>6gTRb?4yb(v&pe~MZ`K1Bfe(4pNC{9WG0kr1XB-)b` z%CIE8_%G0#%r!AW*f-{ySYhC|q0=cz+5iqa&dAfQo#&<`V@!S8JF5PYH_ds)i_?^N zte~wUQ-(K7QYmUh0C%_y+Bs~_i?G293tvWVyDa@3<+j+6J*^Ygi_M6*BEuiXus9>Ay|`aDU|jLQj<&7=tQ-~8YxJP{I1 zwV>3ifrj-I=zTwz@Dt7+B4i%-2$^iECj3pRC#q8iB*^Z}cax*-yhO=lO2KJap_IXATzIX=QCryH1n%7NtBKU<14a_t$<-p>> z&AF%zU#}Bf?}av&{;B)IboJ9O%R^qT!fj@o z-cHB`%WU`-BRrMp{4a4uIVumRJ9NSV>I z24dcdJ_L&sGi=lBS|6vKoS$!_w`T_EKQC~^y3PGohfXz4=@r-fn;~n&BHn>EXIMM0 zDu)Co_HVXw`hF&l>nQqu=EvTAMRGDG-)d{|Qc7`w1f`x{4-mKQ-cI{_<3vhVlD_bd zLrA`tje6AUJEFHofLAl%t}^=<+Pl7qe)!vqs^Q56jX*~F+5WX{gnd_Z+{1r}Nh)|{ z&J1Ai6xjF77f}AV`~q91==%`8=NRE)1L@+-uISfe_A0UV0PC0I%WYS@z7I*(TapF^ zEahZV4zt#(t^IRYgiTdEKfeglV~%OmmvrJd7dKIrk^@PQ_5C)*$`Xk;B-=zY6O91*dVM;v052LU&zYi4ambxJrpBhm( z$OGdg(VvJOB^*S%^=Y98ZvYJvkbcGtY(t9NZXMo}fr-|dAS zCv+*<(FxdDf{NR=^)QFnW|E}cJ)$B#opYPhBcVskZBG!nov;igr>76{)OE1gVP^wU zVIa{&T9M51T;tF-mUP+M4GswqOu+YmT&xnh0-;k}ce_k>?8(#KhD;P@XB({w*j?tY zhkei?^yTC^Zu;^SncFk6B0U4&&4^aMOHxS8C(7#hNTjI`uu+6NwEXY{7e|;IX~&cl zNn;JU01==>`#g@pkH;q4SLx`O$3%JW?Xg?ux=$KcsjI1njb z=tle;Do1+88P8%X8++PAG#TcqDj}fG;h?3>Z9nf7zzJX}0gqn%2U=i&sJCxzG*x7p z6Fj9AkHtY3kDqTI;Zcc(gnjtVV)>{`m18ib*&qj#9Oj{zGGd0}UGu1NI=of!(dH|P zUgBlQgI)CIK%ePHg_=8IFE5LY*$$ghxnhp7Tk}=y$bge_#ePAkA^KP+JUR>VGurIV%9TVBFy9kLjmc_vSgw#<+b`io zG+H=fY+4D5<|s?FTpfxOOOE;)HrR;=3JS{3G9GYGE<4p|xjG>G73+X=4cKK5Z2kT9 zyeGoa!*PP5_N9g?zhQ}^EmsH4d&Qcj$hm6U7Jw&q!JUQODama9)va(w?c-fpu&GEI zVWe-`={4cX?}atvPG{+L_$K%r-WxoXv+i-=%qYDaCCENH8EO8>O)3AUn|s@GRexVd zUeDcn96N<k37|&{R8*b1F}%g{=HA~Vy~fT1)@D>2a*lM{skI00V($; z|A6Qfhr$yHLRXi{{)NlXr~|(q6dLII>);>yTLoCwrJZ)9yw7fI{C=Yf`y@UUQbW_} zsaE0S3}xs?O?KkDDKu>WX9Okj=4kNyz$Z-x1`;gYgGbuseYSB`BTM-Rt%12I53(su zEIAHyG0US_5B825|Ine+KYmg8FP0M4%FHpX%(p^5FAHth!<8C|AhQxKOTsb1PTAo_BdTH2NbJjJcvI|M1FZ^+viXmqBm9614cHg_koJ{%o zruO@J#LLsYB8Xcsqs;PbvhEPe&elU(a;}T(R$V*UVdRWJWYc%6dh%d}c86v5rMRL5 z{YL@0Yh-t=qzeqYfam#|fVN|oHT-N`JI`x6f|*X=$jV(-%hk9_)jg#J3u0ccKOB&K zx_}|O;1XZJ0$S-!CAJ{2j$pRa7hd@$VrwfG7pQVAmo%2Y$Fk8QT;Es}UTOX~&{Dn) zo2_AI$u{ploNP4sg^&UZJwM!C)y2ln@NBlK&a8uus^3{1Q-XYO##cp_-sVQ!U!3=< z8iRkOa4ulKVKqxP^R zv0K|S^AfK&c56GiZq2p0d_UFXbcSnJzz-x-%1KxtTFHSfFc3LVb!)ChD7nye1SdIt zHO?B;(R$~>4wbH?Ae0xsFD#UoJQf((w?)Yd$DvMhmYv>Gxb&^? zK9JjQ{ak!QeDKUX_oJ@E*cp`I8P~0q5|NJ%%gB7x)k-!xRIg}zzS%-8p8(5SFI%|$ z8#Q(~R0rcDU<+82k1uz_4KTRcAwgahV#4gaC=mw`_@2x#wYl)}e>PuFv`fo~bk+zrZIqVM3`#7+b5!54!y zoV3u>PN(t&Ik%|hGbm&08jxojPGLZUaJEqTnaAkM$EY+28FpKU;TZFMc?@=pO~6qe z;FvZL62-GSp+}Ee$d4ajCXR`=nNl-CPAkOEDLjU9cOa$fi03=>L6uhRxpjZx1A3Pn z*4Tc20yD6Mrea@147ebP#V4;tXd?9^Yv$WOvW|Gh?Ec-xkF07BXVfRD11x*KeZ(_) zS9yLnIAl>wP%sqIZ6h*ZW}74_KLjN4M+;Z#1Yav>WnNfHpyoo5QZZWN^#iYfzq( zRXFVz+$ckWsz{ckMwY-8b$bgV1XcjYC4-_y3?4Bk+}p_gk8oWBg-5t`$HNf*HFzu> z`?y|HL~S8Ue`-|Y>B;`5s-kPi%Z;=Nle6lYuEsE}4-{uxBDI7Ah|@Jwb7tjtI)MIN zGc~I?d&U{rnaf{a8^vFLZr&c%cAG36^^ZlW4a$GLpEGtzub_9OJ>Dhl@~0N>wOT#k zv*GDB|7g$|X-m3*OPo~1e0oTTkAklYn4obz(39i~suICd2=n|5O>Ipx^=CG^F#jEE zZc~~VhW@_Qu`_$oBC7IuU?9^`8hb^SLPuUE&1R)sruuNxEU8xxOjJH|GkhLq7tH-spRj-e0mrV3mDTkjeRt8U;QmV;}M&xqb4gK78V`TOx&*vb+FB|3uwY&&D?c17^uQ$)kT%|m#sC>I}eRF z@TO4aHE_lw17PEEFyxby3$PDugg4;lp-0xjf8 zyQDwD>eh7+aZYoO1FhU^DV_;_8J%;g!8h%arsAYtQ24=bfO-0Ng$GR1-`&_@fG3Pt z^ARf*vD8YePodQ&N$%U?0r&V`np470v+GV~!R}&vkS}xE{~p8I3k-(-`l496h5@Gu z5d|`&9Yz&b!DR+hVC6M?ofRlMBApctz)6eTFen)*JthF5Nfdvnpa?HTKDr>s#*(Ki zxu^+hvB#eV)YPCfBPf_AiBu1d2ixtlI~|Mk2^V6ZW2)ji+e(306Lc!!6nCM58(Ie3 zjLZ*kwvO7Pr}qU-pu*|BPopV#G#-U+p_wU=`~` zl}V3%2k`FunhUes)EAnrt$68S**JyHMIM&p;0y4h;p^ZJfv<;efNy}Whd%_q4t_Lz z0e)QOjdUpGulsZ#l-k3f`$|3R#ERkAEvZn46!u;psMBngI7GQSsA%fE*9WU2*dFV45J7!~_TM+-Z|%#nKZKm_wq|=);VKSSV?Fh_ipEun=PIs-;A)g7 ztL!1||{)gxG@6GQ!tmJ~E zLk0C8@IQdPOY?Jry4WM@(^Z{qi=tq;Q9qT+--o$PVBPBE#31IOKf?N-dM1@wf=*d7 zB=)aC%A(X}IBto?+5;RN2Gnk2qOO5XB_{S5fxti~p~1@|W*A`s$k1@VeXlji{ms$? zC=X{!#%U4c+ODk=q8g`sFtpgcXdm$Ffm3f7>FI0)>RW28XZKR@YutQCGR^~o&}f;1 zl^f;B!5JRr9IV|YAS>YUgM%T~ziu|w%$dGtafuRik zJJNkVmW?V|_4tz$(jU)&|0{dRs>P3$Jh5!e*ivTYz%^ugCcqis2E!%7ncx<}t%h3z zXG6SkJ9R7*E(Woe;{H**nU3pw;Tt)|9>%rEIBZ%}>^Zn+;huq;3U?3OlWt&Det*%56>FBQC|SH@)vq2e zDO=9+91iQMvgN;iz`@E^t;~S?)f3B?R5+HDu356UZ1pM>eai9`%S#?#au0IM*hM3- zh5CKI-`61EYdqKDo_rndzk(m$A0CE#dM~2?Uf=Hz==WDISyj4X`J_q4!nt#2&z)q< zTefOR$>OJtc(`22M>y+`Vw}6=*JZ2METJ45^9%Ab^73aH5mr{R%(!?}*^^6F-HO_u zm{?M_Y{_Ednia-Uq`GE_agBY+KfSu-$+FTVlZ;7=Z@oV6iPF*~t5-kv#Ij{i8&~yz zmJ+(d>-}HGn3>N6I31iG&Hy(AE*dTl&ZwH7v3SXo8Ee)&J+FcVQT%`PQ`+$3aZJ~n z3EN?C?HNp$1Q$q$JqEa0c$NJKL(X;d-hOk#}s1ASm1`A86_6^wm{ z?;7BrHbR{(~xf%$h7bkzBJwM7|g=p+b%$o627xKo<+dl zmo%E`;h*>{oehBB_UpUZK=>?dDjNj9Z24nsdC78?yc``M1#P9^^^MC9;rI1e8QU8F z$%mi8xBRd-a~pj2+K!k<$^YreqA}zff3@#w9(=as>*I=F{g(}j?~a_O_{fXmv!y>- zC?2ah9P%w|Lq40{?+>x;-bKI0d!HTh?zHcoslGQoKd$}z@iF&Ks?Gd<%hQGTe7Lds zxAmv@PRV}r;J2o(=@X~E*;&v#==WK#{I>Q_x?>BH@>jgGI9c;KRXu*AEQ-e-4*4~w z6u%W%DneO9NOgD8Y)4lR|DEx5;(|MMKu5YA@!JV`iopAqC zO!w83OxO4{?Cinc4}G_n;U>e)f}0Jeu0+3mF7&?Z`H5ZXo5(nhQ}GWrk-$m0WB zn69H1IOcE^KH){Ci|W6o`;1$4b$8mtta0Nr`>PCd0m_-l=G{LlJL}%iFLYBhVL{Gw zcRyM|uQS?zsPK=DUpIPESe^0b;95=z`9J-sjDte!0%EH!<6QLr^cEuReMc$Jo#XSN zveMXGL`^1^dar=Gh{hFHF@3S5-?7RJb(u2c}-gd9713HxjlqoGN^Fx@b!C+b) z_TboC(s-a}H?nubr{_h8bK`!}jSKi~{ex&D!ihecBVg(2zosB1*vP1l-h5wqmO#%8 L)KjsjF!uid*tncw literal 0 HcmV?d00001 diff --git a/boards/ark/pi6x/firmware.prototype b/boards/ark/pi6x/firmware.prototype new file mode 100644 index 000000000000..6c21025a6bc2 --- /dev/null +++ b/boards/ark/pi6x/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 58, + "magic": "ARKPi6XFWv1", + "description": "Firmware for the ARKPi6X board", + "image": "", + "build_time": 0, + "summary": "ARKPi6X", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1835008, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/ark/pi6x/init/rc.board_defaults b/boards/ark/pi6x/init/rc.board_defaults new file mode 100644 index 000000000000..978dcf43d3cd --- /dev/null +++ b/boards/ark/pi6x/init/rc.board_defaults @@ -0,0 +1,33 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# transision from params file to flash-based params (2022-08) +if [ -f $PARAM_FILE ] +then + param load $PARAM_FILE + param save + # create a backup + mv $PARAM_FILE ${PARAM_FILE}.bak + reboot +fi + +param set-default SENS_EN_INA226 1 + +# TODO: Set params to start UXRCE DDS on Telem2 + +# TODO: Start Mavlink on USB by default + +# TODO: Tune the following parameters +param set-default SENS_EN_THERMAL 1 +param set-default SENS_IMU_TEMP 10.0 +#param set-default SENS_IMU_TEMP_FF 0.0 +#param set-default SENS_IMU_TEMP_I 0.025 +#param set-default SENS_IMU_TEMP_P 1.0 + +if ver hwtypecmp ARKPI6X000 +then + # TODO: Add the correct sensor ID + param set-default SENS_TEMP_ID 2490378 +fi diff --git a/boards/ark/pi6x/init/rc.board_sensors b/boards/ark/pi6x/init/rc.board_sensors new file mode 100644 index 000000000000..647e685c7f43 --- /dev/null +++ b/boards/ark/pi6x/init/rc.board_sensors @@ -0,0 +1,34 @@ +#!/bin/sh +# +# ARKPI6X specific board sensors init +#------------------------------------------------------------------------------ + +board_adc start + +if param compare SENS_EN_INA226 1 +then + # Start Digital power monitors + ina226 -I -b 3 -t 1 -k start +fi + +if ver hwtypecmp ARKPI6X000 +then + # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz + icm42688p -R 3 -s -b 1 -C 32051 start + + # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz + icm42688p -R 1 -s -b 2 -C 32051 start +fi + +# Internal magnetometer on I2C +# TODO: Write a driver for the MMC5983MA +mmc5983ma -I -b 4 start + +# Internal Baro on I2C +bmp388 -I -b 4 start + +# Internal optical flow +paw3902 -s -b 3 start -Y 90 + +# Internal distance sensor +afbrs50 start diff --git a/boards/ark/pi6x/nuttx-config/Kconfig b/boards/ark/pi6x/nuttx-config/Kconfig new file mode 100644 index 000000000000..bb33d3cfda4d --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/ark/pi6x/nuttx-config/bootloader/defconfig b/boards/ark/pi6x/nuttx-config/bootloader/defconfig new file mode 100644 index 000000000000..745251793bd0 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/bootloader/defconfig @@ -0,0 +1,95 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/pi6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="ark" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0039 +CONFIG_CDCACM_PRODUCTSTR="ARK BL Pi6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ARK" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART7=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART7_RXBUFSIZE=512 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=512 +CONFIG_UART7_TXDMA=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/pi6x/nuttx-config/include/board.h b/boards/ark/pi6x/nuttx-config/include/board.h new file mode 100644 index 000000000000..2b716936cebd --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/include/board.h @@ -0,0 +1,512 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6x/include/board.h + * + * Copyright (C) 2016-2024 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * 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 NuttX 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 __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The ARKV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS No remap /* PC8 */ +#define GPIO_UART5_CTS (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9|GPIO_PULLDOWN) /* PC9 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is Not Used + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/ark/pi6x/nuttx-config/include/board_dma_map.h b/boards/ark/pi6x/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..62e278597243 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/include/board_dma_map.h @@ -0,0 +1,81 @@ +/**************************************************************************** + * + * 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 + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/ark/pi6x/nuttx-config/nsh/defconfig b/boards/ark/pi6x/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..947fee32b15f --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/nsh/defconfig @@ -0,0 +1,274 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/pi6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="ark" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0039 +CONFIG_CDCACM_PRODUCTSTR="ARK Pi6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ARK" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=3000 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld b/boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..b0515c91c7f8 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2024 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The ARKV6X uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The ARKV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/pi6x/nuttx-config/scripts/script.ld b/boards/ark/pi6x/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..8e6dca3e4941 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2024 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The ARKV6X uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The ARKV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */ + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/pi6x/src/CMakeLists.txt b/boards/ark/pi6x/src/CMakeLists.txt new file mode 100644 index 000000000000..78b8222f19d8 --- /dev/null +++ b/boards/ark/pi6x/src/CMakeLists.txt @@ -0,0 +1,77 @@ +############################################################################ +# +# Copyright (c) 2016 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + mtd.cpp + sdio.c + spi.cpp + spix_sync.c + spix_sync.h + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/ark/pi6x/src/board_config.h b/boards/ark/pi6x/src/board_config.h new file mode 100644 index 000000000000..5e123db35124 --- /dev/null +++ b/boards/ark/pi6x/src/board_config.h @@ -0,0 +1,402 @@ +/**************************************************************************** + * + * Copyright (c) 2016-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. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * ARK Pi6X internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_NBAT_V 1d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 1d // 2 Digital Current + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define PX4_I2C_OBDEV_SE050 0x48 + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15) + +#define ADC_CHANNELS \ + ((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL)) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ +#define BOARD_HAS_HW_SPLIT_VERSIONING + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 +#define HW_INFO_INIT_PREFIX "ARKPI6X" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 +// Base/FMUM +#define ARKPI6X_0 HW_FMUM_ID(0x0) // ARKPI6X, Sensor Set Rev 0 +#define ARKPI6X_1 HW_FMUM_ID(0x1) // ARKPI6X, Sensor Set Rev 1 + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PE6 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +#define GPIO_FMU_CH1 /* PI0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN0) +#define GPIO_FMU_CH2 /* PH12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN12) +#define GPIO_FMU_CH3 /* PH11 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN11) +#define GPIO_FMU_CH4 /* PH10 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN10) +#define GPIO_FMU_CH5 /* PD13 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTD|GPIO_PIN13) +#define GPIO_FMU_CH6 /* PD14 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTD|GPIO_PIN14) +#define GPIO_FMU_CH7 /* PH6 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN6) +#define GPIO_FMU_CH8 /* PH9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN9) + +#define GPIO_FMU_CAP /* PE11 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN11) +#define GPIO_SPIX_SYNC /* PE9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN9) + +#define BROADCOM_AFBR_S50_S2PI_SPI_BUS 6 +#define BROADCOM_AFBR_S50_S2PI_CS /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10) +#define BROADCOM_AFBR_S50_S2PI_IRQ /* PD11 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN11|GPIO_EXTI) +#define BROADCOM_AFBR_S50_S2PI_CLK /* PB3 */ GPIO_SPI6_SCK_3 +#define BROADCOM_AFBR_S50_S2PI_MOSI /* PG14 */ GPIO_SPI6_MOSI_1 +#define BROADCOM_AFBR_S50_S2PI_MISO /* PA6 */ GPIO_SPI6_MISO_2 + +/* Power supply control and monitoring GPIOs */ + +#define BOARD_NUMBER_BRICKS 0 +#define BOARD_NUMBER_DIGITAL_BRICKS 1 + +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* Spare GPIO */ + +#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +#define FLASH_BASED_PARAMS + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +/* RC Serial port */ + +#define RC_SERIAL_PORT "/dev/ttyS4" + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) + +/* ARKPI6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_PD15, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nARMED_INIT, \ + GPIO_FMU_CH1, \ + GPIO_FMU_CH2, \ + GPIO_FMU_CH3, \ + GPIO_FMU_CH4, \ + GPIO_FMU_CH5, \ + GPIO_FMU_CH6, \ + GPIO_FMU_CH7, \ + GPIO_FMU_CH8, \ + GPIO_FMU_CAP, \ + GPIO_SPIX_SYNC \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 3 +#define BOARD_SPIX_SYNC_FREQ 32000 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/ark/pi6x/src/bootloader_main.c b/boards/ark/pi6x/src/bootloader_main.c new file mode 100644 index 000000000000..7a3ef5e01932 --- /dev/null +++ b/boards/ark/pi6x/src/bootloader_main.c @@ -0,0 +1,85 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure pins */ + const uint32_t list[] = PX4_GPIO_INIT_LIST; + + for (size_t gpio = 0; gpio < arraySize(list); gpio++) { + if (list[gpio] != 0) { + px4_arch_configgpio(list[gpio]); + } + } + + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/ark/pi6x/src/can.c b/boards/ark/pi6x/src/can.c new file mode 100644 index 000000000000..cdebe7a3ad61 --- /dev/null +++ b/boards/ark/pi6x/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/ark/pi6x/src/hw_config.h b/boards/ark/pi6x/src/hw_config.h new file mode 100644 index 000000000000..52c70ec748da --- /dev/null +++ b/boards/ark/pi6x/src/hw_config.h @@ -0,0 +1,129 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS5,921600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 58 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/ark/pi6x/src/i2c.cpp b/boards/ark/pi6x/src/i2c.cpp new file mode 100644 index 000000000000..86c060404934 --- /dev/null +++ b/boards/ark/pi6x/src/i2c.cpp @@ -0,0 +1,40 @@ +/**************************************************************************** + * + * Copyright (C) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusInternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/ark/pi6x/src/init.c b/boards/ark/pi6x/src/init.c new file mode 100644 index 000000000000..90bb4fc128be --- /dev/null +++ b/boards/ark/pi6x/src/init.c @@ -0,0 +1,293 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * ARKFMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" +#include "spix_sync.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_HIPOWER_EN(false); + board_control_spi_sensors_power(false, 0xffff); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_HIPOWER_EN(true); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Power on Interfaces */ + VDD_5V_HIPOWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {15, 128 * 1024, 0x081E0000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + led_on(LED_AMBER); + } + +#endif // FLASH_BASED_PARAMS + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +#if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +#endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +#endif /* CONFIG_MMCSD */ + + /* Configure the SPIX_SYNC output */ + spix_sync_servo_init(BOARD_SPIX_SYNC_FREQ); + spix_sync_servo_set(0, 150); + + return OK; +} diff --git a/boards/ark/pi6x/src/led.c b/boards/ark/pi6x/src/led.c new file mode 100644 index 000000000000..b629ade32c36 --- /dev/null +++ b/boards/ark/pi6x/src/led.c @@ -0,0 +1,234 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * ARKFMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/ark/pi6x/src/mtd.cpp b/boards/ark/pi6x/src/mtd.cpp new file mode 100644 index 000000000000..bd74d551ee4c --- /dev/null +++ b/boards/ark/pi6x/src/mtd.cpp @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include + +#include +#include + +static const px4_mft_entry_s mft_mft = { + .type = MFT, + .pmft = (void *) system_query_manifest, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mft_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/ark/pi6x/src/sdio.c b/boards/ark/pi6x/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/ark/pi6x/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/ark/pi6x/src/spi.cpp b/boards/ark/pi6x/src/spi.cpp new file mode 100644 index 000000000000..bae9af7622a3 --- /dev/null +++ b/boards/ark/pi6x/src/spi.cpp @@ -0,0 +1,83 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { + initSPIFmumID(ARKPI6X_0, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_FLOW_DEVTYPE_PAW3902, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + // initSPIBus(SPI::Bus::SPI5, { + // initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + // }), + initSPIBus(SPI::Bus::SPI6, { + initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}) + }), + }), + initSPIFmumID(ARKPI6X_1, { // Placeholder + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_FLOW_DEVTYPE_PAW3902, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + // initSPIBus(SPI::Bus::SPI5, { + // initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + // }), + initSPIBus(SPI::Bus::SPI6, { + initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}) + }), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); diff --git a/boards/ark/pi6x/src/spix_sync.c b/boards/ark/pi6x/src/spix_sync.c new file mode 100644 index 000000000000..056e38e75f74 --- /dev/null +++ b/boards/ark/pi6x/src/spix_sync.c @@ -0,0 +1,309 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name Airmind nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** +* @file spix_sync.c +* +* +*/ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +#include +#include +#include + +#include + +#include "spix_sync.h" + +#define REG(_tmr, _reg) (*(volatile uint32_t *)(spix_sync_timers[_tmr].base + _reg)) + +#define rCR1(_tmr) REG(_tmr, STM32_GTIM_CR1_OFFSET) +#define rCR2(_tmr) REG(_tmr, STM32_GTIM_CR2_OFFSET) +#define rSMCR(_tmr) REG(_tmr, STM32_GTIM_SMCR_OFFSET) +#define rDIER(_tmr) REG(_tmr, STM32_GTIM_DIER_OFFSET) +#define rSR(_tmr) REG(_tmr, STM32_GTIM_SR_OFFSET) +#define rEGR(_tmr) REG(_tmr, STM32_GTIM_EGR_OFFSET) +#define rCCMR1(_tmr) REG(_tmr, STM32_GTIM_CCMR1_OFFSET) +#define rCCMR2(_tmr) REG(_tmr, STM32_GTIM_CCMR2_OFFSET) +#define rCCER(_tmr) REG(_tmr, STM32_GTIM_CCER_OFFSET) +#define rCNT(_tmr) REG(_tmr, STM32_GTIM_CNT_OFFSET) +#define rPSC(_tmr) REG(_tmr, STM32_GTIM_PSC_OFFSET) +#define rARR(_tmr) REG(_tmr, STM32_GTIM_ARR_OFFSET) +#define rCCR1(_tmr) REG(_tmr, STM32_GTIM_CCR1_OFFSET) +#define rCCR2(_tmr) REG(_tmr, STM32_GTIM_CCR2_OFFSET) +#define rCCR3(_tmr) REG(_tmr, STM32_GTIM_CCR3_OFFSET) +#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET) +#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET) +#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET) +#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET) + +#define BOARD_SPIX_SYNC_PWM_FREQ 1024000 + +unsigned +spix_sync_timer_get_period(unsigned timer) +{ + return (rARR(timer)); +} + +static void spix_sync_timer_init_timer(unsigned timer, unsigned rate) +{ + if (spix_sync_timers[timer].base) { + + irqstate_t flags = px4_enter_critical_section(); + + /* enable the timer clock before we try to talk to it */ + + modifyreg32(spix_sync_timers[timer].clock_register, 0, spix_sync_timers[timer].clock_bit); + + /* disable and configure the timer */ + rCR1(timer) = 0; + rCR2(timer) = 0; + rSMCR(timer) = 0; + rDIER(timer) = 0; + rCCER(timer) = 0; + rCCMR1(timer) = 0; + rCCMR2(timer) = 0; + rCCR1(timer) = 0; + rCCR2(timer) = 0; + rCCR3(timer) = 0; + rCCR4(timer) = 0; + rCCER(timer) = 0; + rDCR(timer) = 0; + + if ((spix_sync_timers[timer].base == STM32_TIM1_BASE) || (spix_sync_timers[timer].base == STM32_TIM8_BASE)) { + + /* master output enable = on */ + + rBDTR(timer) = ATIM_BDTR_MOE; + } + + /* If the timer clock source provided as clock_freq is the STM32_APBx_TIMx_CLKIN + * then configure the timer to free-run at 1MHz. + * Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly. + */ + + rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_SPIX_SYNC_PWM_FREQ) - 1; + + /* configure the timer to update at the desired rate */ + + rARR(timer) = (BOARD_SPIX_SYNC_PWM_FREQ / rate) - 1; + + /* generate an update event; reloads the counter and all registers */ + rEGR(timer) = GTIM_EGR_UG; + + px4_leave_critical_section(flags); + } + +} + +void spix_sync_channel_init(unsigned channel) +{ + /* Only initialize used channels */ + + if (spix_sync_channels[channel].timer_channel) { + + unsigned timer = spix_sync_channels[channel].timer_index; + + /* configure the GPIO first */ + px4_arch_configgpio(spix_sync_channels[channel].gpio_out); + + uint16_t polarity = spix_sync_channels[channel].masks; + + /* configure the channel */ + switch (spix_sync_channels[channel].timer_channel) { + case 1: + rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC1M_SHIFT) | GTIM_CCMR1_OC1PE; + rCCER(timer) |= polarity | GTIM_CCER_CC1E; + break; + + case 2: + rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC2M_SHIFT) | GTIM_CCMR1_OC2PE; + rCCER(timer) |= polarity | GTIM_CCER_CC2E; + break; + + case 3: + rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC3M_SHIFT) | GTIM_CCMR2_OC3PE; + rCCER(timer) |= polarity | GTIM_CCER_CC3E; + break; + + case 4: + rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC4M_SHIFT) | GTIM_CCMR2_OC4PE; + rCCER(timer) |= polarity | GTIM_CCER_CC4E; + break; + } + } +} + +int +spix_sync_servo_set(unsigned channel, uint8_t cvalue) +{ + if (channel >= arraySize(spix_sync_channels)) { + return -1; + } + + unsigned timer = spix_sync_channels[channel].timer_index; + + /* test timer for validity */ + if ((spix_sync_timers[timer].base == 0) || + (spix_sync_channels[channel].gpio_out == 0)) { + return -1; + } + + unsigned period = spix_sync_timer_get_period(timer); + + unsigned value = (unsigned)cvalue * period / 255; + + /* configure the channel */ + if (value > 0) { + value--; + } + + + switch (spix_sync_channels[channel].timer_channel) { + case 1: + rCCR1(timer) = value; + break; + + case 2: + rCCR2(timer) = value; + break; + + case 3: + rCCR3(timer) = value; + break; + + case 4: + rCCR4(timer) = value; + break; + + default: + return -1; + } + + return 0; +} + +unsigned spix_sync_servo_get(unsigned channel) +{ + if (channel >= 3) { + return 0; + } + + unsigned timer = spix_sync_channels[channel].timer_index; + uint16_t value = 0; + + /* test timer for validity */ + if ((spix_sync_timers[timer].base == 0) || + (spix_sync_channels[channel].timer_channel == 0)) { + return 0; + } + + /* configure the channel */ + switch (spix_sync_channels[channel].timer_channel) { + case 1: + value = rCCR1(timer); + break; + + case 2: + value = rCCR2(timer); + break; + + case 3: + value = rCCR3(timer); + break; + + case 4: + value = rCCR4(timer); + break; + } + + unsigned period = spix_sync_timer_get_period(timer); + return ((value + 1) * 255 / period); +} + +int spix_sync_servo_init(unsigned rate) +{ + /* do basic timer initialisation first */ + for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) { + spix_sync_timer_init_timer(i, rate); + } + + /* now init channels */ + for (unsigned i = 0; i < arraySize(spix_sync_channels); i++) { + spix_sync_channel_init(i); + } + + spix_sync_servo_arm(true); + return OK; +} + +void +spix_sync_servo_deinit(void) +{ + /* disable the timers */ + spix_sync_servo_arm(false); +} +void +spix_sync_servo_arm(bool armed) +{ + /* iterate timers and arm/disarm appropriately */ + for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) { + if (spix_sync_timers[i].base != 0) { + if (armed) { + /* force an update to preload all registers */ + rEGR(i) = GTIM_EGR_UG; + + /* arm requires the timer be enabled */ + rCR1(i) |= GTIM_CR1_CEN | GTIM_CR1_ARPE; + + } else { + rCR1(i) = 0; + } + } + } +} diff --git a/boards/ark/pi6x/src/spix_sync.h b/boards/ark/pi6x/src/spix_sync.h new file mode 100644 index 000000000000..2e37c8908613 --- /dev/null +++ b/boards/ark/pi6x/src/spix_sync.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +__BEGIN_DECLS +void spix_sync_channel_init(unsigned channel); +int spix_sync_servo_set(unsigned channel, uint8_t value); +unsigned spix_sync_servo_get(unsigned channel); +int spix_sync_servo_init(unsigned rate); +void spix_sync_servo_deinit(void); +void spix_sync_servo_arm(bool armed); +unsigned spix_sync_timer_get_period(unsigned timer); +__END_DECLS diff --git a/boards/ark/pi6x/src/timer_config.cpp b/boards/ark/pi6x/src/timer_config.cpp new file mode 100644 index 000000000000..bee77b999337 --- /dev/null +++ b/boards/ark/pi6x/src/timer_config.cpp @@ -0,0 +1,88 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + //initIOTimer(Timer::Timer1), + //initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + //initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + //initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); + + +constexpr io_timers_t spix_sync_timers[MAX_SPIX_SYNC_TIMERS] = { + initIOTimer(Timer::Timer1), +}; + +constexpr timer_io_channels_t spix_sync_channels[MAX_SPIX_SYNC_TIMERS] = { + initIOTimerChannel(spix_sync_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), +}; diff --git a/boards/ark/pi6x/src/usb.c b/boards/ark/pi6x/src/usb.c new file mode 100644 index 000000000000..1c64e94ba104 --- /dev/null +++ b/boards/ark/pi6x/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "arm_internal.h" +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the ARKFMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp index 4df96fa5a996..5310701eebda 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp @@ -72,7 +72,7 @@ static constexpr wq_config_t INS1{"wq:INS1", 6000, -15}; static constexpr wq_config_t INS2{"wq:INS2", 6000, -16}; static constexpr wq_config_t INS3{"wq:INS3", 6000, -17}; -static constexpr wq_config_t hp_default{"wq:hp_default", 2392, -18}; +static constexpr wq_config_t hp_default{"wq:hp_default", 2800, -18}; static constexpr wq_config_t uavcan{"wq:uavcan", 3624, -19}; diff --git a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c index 894834f078fa..859d861b2094 100644 --- a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c +++ b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c @@ -71,6 +71,14 @@ const mcu_rev_t silicon_revs[] = { {MCU_REV_Z, 'Z'}, /* Revision Z */ }; +/* + * If APP_RESERVATION_SIZE is greater than 0 and + * FLASH_BASED_PARAMS is defined, throw a compile error + */ +#if defined(FLASH_BASED_PARAMS) && (APP_RESERVATION_SIZE <= 0) +# error "APP_RESERVATION_SIZE must be greater than 0 if FLASH_BASED_PARAMS is defined" +#endif + #define APP_SIZE_MAX (BOARD_FLASH_SIZE - (BOOTLOADER_RESERVATION_SIZE + APP_RESERVATION_SIZE)) diff --git a/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c b/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c index 015249f859f5..367c5417df60 100644 --- a/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c +++ b/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c @@ -362,9 +362,9 @@ status_t S2PI_TransferFrame(s2pi_slave_t spi_slave, uint8_t const *txData, uint8 } /* Check the spi slave.*/ - if (spi_slave != S2PI_S2) { - return ERROR_S2PI_INVALID_SLAVE; - } + // if (spi_slave != S2PI_S2) { + // return ERROR_S2PI_INVALID_SLAVE; + // } /* Check the driver status, lock if idle. */ IRQ_LOCK(); From 1b1479a92b61ca700b69f34da531674a4fcf4d8c Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Sun, 3 Mar 2024 19:22:51 -0400 Subject: [PATCH 106/652] airframes: Droneblocks DEXI 5 --- .../init.d/airframes/4601_droneblocks_dexi_5 | 78 +++++++++++++++++++ .../init.d/airframes/CMakeLists.txt | 1 + boards/ark/pi6x/init/rc.board_defaults | 17 ++++ 3 files changed, 96 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 new file mode 100644 index 000000000000..c1484d0b417c --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 @@ -0,0 +1,78 @@ +#!/bin/sh +# +# @name Droneblocks DEXI 5 +# +# @type Quadrotor x +# @class Copter +# +# @maintainer Dennis Baldwin +# @maintainer Alex klimaj +# +# @board px4_fmu-v2 exclude +# @board px4_fmu-v3 exclude +# @board px4_fmu-v4 exclude +# @board px4_fmu-v4pro exclude +# @board px4_fmu-v5 exclude +# @board px4_fmu-v5x exclude +# @board px4_fmu-v6x exclude +# @board bitcraze_crazyflie exclude +# @board diatone_mamba-f405-mk2 exclude +# @board ark_fmu-v6x exclude +# + +. ${R}etc/init.d/rc.mc_defaults + +param set-default BAT1_CAPACITY 4000 +param set-default BAT1_N_CELLS 6 +param set-default BAT1_V_EMPTY 3.3 +param set-default BAT1_V_LOAD_DROP 0.5 +param set-default BAT_AVRG_CURRENT 13 + +# Square quadrotor X PX4 numbering +param set-default CA_ROTOR_COUNT 4 +param set-default CA_ROTOR0_PX 0.0762 +param set-default CA_ROTOR0_PY 0.09525 +param set-default CA_ROTOR0_KM 0.05 +param set-default CA_ROTOR1_PX -0.0762 +param set-default CA_ROTOR1_PY -0.09525 +param set-default CA_ROTOR1_KM 0.05 +param set-default CA_ROTOR2_PX 0.0762 +param set-default CA_ROTOR2_PY -0.09525 +param set-default CA_ROTOR2_KM -0.05 +param set-default CA_ROTOR3_PX -0.0762 +param set-default CA_ROTOR3_PY 0.09525 +param set-default CA_ROTOR3_KM -0.05 + +param set-default EKF2_MIN_RNG 0.01 +param set-default EKF2_OF_POS_X 0.043 +param set-default EKF2_OF_POS_Y 0.011 +param set-default EKF2_OF_QMIN_GND 1 +param set-default EKF2_RNG_POS_X 0.043 +param set-default EKF2_RNG_POS_Y 0.0 + +param set-default IMU_GYRO_DNF_EN 2 + +param set-default MC_PITCHRATE_D 0.0013 +param set-default MC_PITCHRATE_I 0.185 +param set-default MC_PITCHRATE_P 0.105 +param set-default MC_PITCH_P 7.5 +param set-default MC_ROLLRATE_D 0.0010 +param set-default MC_ROLLRATE_I 0.165 +param set-default MC_ROLLRATE_P 0.095 +param set-default MC_ROLL_P 7.5 +param set-default MC_YAWRATE_I 0.35 +param set-default MC_YAWRATE_P 0.13 + +param set-default MPC_THR_HOVER 0.22 +param set-default MPC_THR_MAX 0.5 +param set-default MPC_THR_MIN 0.025 +param set-default MPC_VEL_MANUAL 5.0 +param set-default MPC_XY_VEL_MAX 8.0 + +param set-default RTL_RETURN_ALT 15 + +param set-default SENS_FLOW_MINHGT 0.0 + +param set-default SER_TEL2_BAUD 3000000 + +param set-default UXRCE_DDS_CFG 102 diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index 66e29e32b4dd..89498206c3e9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -69,6 +69,7 @@ if(CONFIG_MODULES_MC_RATE_CONTROL) 4071_ifo 4073_ifo-s 4500_clover4 + 4601_droneblocks_dexi_5 4901_crazyflie21 # [5000, 5999] Quadrotor + diff --git a/boards/ark/pi6x/init/rc.board_defaults b/boards/ark/pi6x/init/rc.board_defaults index 978dcf43d3cd..03134c887801 100644 --- a/boards/ark/pi6x/init/rc.board_defaults +++ b/boards/ark/pi6x/init/rc.board_defaults @@ -31,3 +31,20 @@ then # TODO: Add the correct sensor ID param set-default SENS_TEMP_ID 2490378 fi + +param set-default EKF2_BARO_DELAY 13 +param set-default EKF2_BARO_NOISE 0.9 +param set-default EKF2_HGT_REF 2 +param set-default EKF2_MAG_DELAY 100 +param set-default EKF2_MAG_NOISE 0.06 +param set-default EKF2_MULTI_IMU 2 +param set-default EKF2_OF_CTRL 1 +param set-default EKF2_OF_DELAY 48 +param set-default EKF2_OF_N_MIN 0.05 +param set-default EKF2_RNG_A_HMAX 25 +param set-default EKF2_RNG_DELAY 48 +param set-default EKF2_RNG_NOISE 0.03 +param set-default EKF2_RNG_QLTY_T 0.1 +param set-default EKF2_RNG_SFE 0.03 + +param set-default SENS_FLOW_RATE 150 From 78bbb66568e6a47291dc4d96ed177318704075fb Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 18 Dec 2023 13:03:52 -0500 Subject: [PATCH 107/652] delete SYS_MC_EST_GROUP - introduce per module parameters (EKF2_EN, LPE_EN, ATT_EN) - add basic checks to prevent EKF2 + LPE running simultaneously --- ROMFS/px4fmu_common/init.d-posix/rcS | 23 +++++-- .../init.d/airframes/4901_crazyflie21 | 2 +- ROMFS/px4fmu_common/init.d/rc.airship_apps | 43 ------------ ROMFS/px4fmu_common/init.d/rc.balloon_apps | 36 ---------- .../px4fmu_common/init.d/rc.balloon_defaults | 4 +- ROMFS/px4fmu_common/init.d/rc.fw_apps | 5 -- ROMFS/px4fmu_common/init.d/rc.mc_apps | 43 ------------ ROMFS/px4fmu_common/init.d/rc.rover_apps | 5 -- .../init.d/rc.rover_differential_apps | 3 - ROMFS/px4fmu_common/init.d/rc.uuv_apps | 10 --- ROMFS/px4fmu_common/init.d/rc.vehicle_setup | 1 - ROMFS/px4fmu_common/init.d/rc.vtol_apps | 10 --- ROMFS/px4fmu_common/init.d/rcS | 17 +++++ .../mamba-f405-mk2/init/rc.board_defaults | 5 -- boards/flywoo/gn-f405/init/rc.board_defaults | 5 -- boards/omnibus/f4sd/init/rc.board_defaults | 5 -- .../spracing/h7extreme/init/rc.board_defaults | 5 -- src/drivers/ins/vectornav/VectorNav.cpp | 4 -- src/lib/parameters/param_translation.cpp | 69 +++++++++++++++++++ src/lib/systemlib/system_params.c | 14 ---- .../attitude_estimator_q_main.cpp | 8 +++ .../attitude_estimator_q_params.c | 10 +++ .../checks/estimatorCheck.cpp | 5 +- .../checks/estimatorCheck.hpp | 1 - src/modules/ekf2/EKF2.cpp | 1 - src/modules/ekf2/ekf2_params.c | 8 +++ .../BlockLocalPositionEstimator.cpp | 8 +++ src/modules/local_position_estimator/params.c | 8 ++- test/mavsdk_tests/configs/sitl.json | 5 +- 29 files changed, 154 insertions(+), 209 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index 0084a6701e6d..0fd28a0f13ca 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -182,10 +182,6 @@ param set-default SYS_FAILURE_EN 1 # does not go below 50% by default, but failure injection can trigger failsafes. param set-default COM_LOW_BAT_ACT 2 -# Allow to override SYS_MC_EST_GROUP via env -if [ -n "$SYS_MC_EST_GROUP" ]; then - param set SYS_MC_EST_GROUP $SYS_MC_EST_GROUP -fi # Adapt timeout parameters if simulation runs faster or slower than realtime. if [ -n "$PX4_SIM_SPEED_FACTOR" ]; then @@ -256,6 +252,23 @@ manual_control start sensors start commander start +# +# state estimator selection +if param compare -s EKF2_EN 1 +then + ekf2 start & +fi + +if param compare -s LPE_EN 1 +then + local_position_estimator start +fi + +if param compare -s ATT_EN 1 +then + attitude_estimator_q start +fi + if ! pwm_out_sim start -m sim then tune_control play error @@ -330,7 +343,7 @@ fi [ -e "$autostart_file".post ] && . "$autostart_file".post # Run script to start logging -if param compare SYS_MC_EST_GROUP 2 +if param compare -s EKF2_EN 1 then set LOGGER_ARGS "-p ekf2_timestamps" else diff --git a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 index 37dfc34def96..d16230d3583c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -17,7 +17,7 @@ # . ${R}etc/init.d/rc.mc_defaults -param set-default SYS_MC_EST_GROUP 2 + param set-default SYS_HAS_MAG 0 param set-default EKF2_OF_CTRL 1 param set-default EKF2_GPS_CTRL 0 diff --git a/ROMFS/px4fmu_common/init.d/rc.airship_apps b/ROMFS/px4fmu_common/init.d/rc.airship_apps index 837a3a21613d..090c16b2231d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.airship_apps +++ b/ROMFS/px4fmu_common/init.d/rc.airship_apps @@ -5,49 +5,6 @@ # NOTE: Script variables are declared/initialized/unset in the rcS script. # -############################################################################### -# Begin Estimator Group Selection # -############################################################################### - -# -# LPE -# -if param compare SYS_MC_EST_GROUP 1 -then - # - # Try to start LPE. If it fails, start EKF2 as a default. - # Unfortunately we do not build it on px4_fmu-v2 due to a limited flash. - # - if attitude_estimator_q start - then - echo "WARN [init] Estimator LPE unsupported, EKF2 recommended." - local_position_estimator start - else - echo "ERROR [init] Estimator LPE not available. Using EKF2" - param set SYS_MC_EST_GROUP 2 - param save - reboot - fi -else - # - # Q estimator (attitude estimation only) - # - if param compare SYS_MC_EST_GROUP 3 - then - attitude_estimator_q start - else - # - # EKF2 - # - param set SYS_MC_EST_GROUP 2 - ekf2 start & - fi -fi - -############################################################################### -# End Estimator Group Selection # -############################################################################### - # # Start Control Allocator # diff --git a/ROMFS/px4fmu_common/init.d/rc.balloon_apps b/ROMFS/px4fmu_common/init.d/rc.balloon_apps index 2adb216ec145..7f42a3b27ead 100644 --- a/ROMFS/px4fmu_common/init.d/rc.balloon_apps +++ b/ROMFS/px4fmu_common/init.d/rc.balloon_apps @@ -4,39 +4,3 @@ # # NOTE: Script variables are declared/initialized/unset in the rcS script. # - -# -# Start the attitude and position estimator. -# - -if param compare SYS_MC_EST_GROUP 1 -then - # - # Try to start LPE. If it fails, start EKF2 as a default. - # Unfortunately we do not build it on px4_fmu-v2 due to a limited flash. - # - if attitude_estimator_q start - then - echo "WARN [init] Estimator LPE unsupported, EKF2 recommended." - local_position_estimator start - else - echo "ERROR [init] Estimator LPE not available. Using EKF2" - param set SYS_MC_EST_GROUP 2 - param save - reboot - fi -else - # - # Q estimator (attitude estimation only) - # - if param compare SYS_MC_EST_GROUP 3 - then - attitude_estimator_q start - else - # - # EKF2 - # - param set SYS_MC_EST_GROUP 2 - ekf2 start & - fi -fi diff --git a/ROMFS/px4fmu_common/init.d/rc.balloon_defaults b/ROMFS/px4fmu_common/init.d/rc.balloon_defaults index 6f7d925e0c42..70161f3fa3d5 100644 --- a/ROMFS/px4fmu_common/init.d/rc.balloon_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.balloon_defaults @@ -13,4 +13,6 @@ param set-default MAV_TYPE 8 # # Default parameters for balloon UAVs. # -param set-default SYS_MC_EST_GROUP 1 +param set-default LPE_EN 1 +param set-default ATT_EN 1 +param set-default EKF2_EN 0 diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps index f3c559298e8c..81af5e1acd7a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_apps +++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps @@ -5,11 +5,6 @@ # NOTE: Script variables are declared/initialized/unset in the rcS script. # -# -# Start the attitude and position estimator. -# -ekf2 start & - # # Start Control Allocator # diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps index 8158ab8b03cf..d5d9989c8666 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_apps +++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps @@ -5,49 +5,6 @@ # NOTE: Script variables are declared/initialized/unset in the rcS script. # -############################################################################### -# Begin Estimator Group Selection # -############################################################################### - -# -# LPE -# -if param compare SYS_MC_EST_GROUP 1 -then - # - # Try to start LPE. If it fails, start EKF2 as a default. - # Unfortunately we do not build it on px4_fmu-v2 due to a limited flash. - # - if attitude_estimator_q start - then - echo "WARN [init] Estimator LPE unsupported, EKF2 recommended." - local_position_estimator start - else - echo "ERROR [init] Estimator LPE not available. Using EKF2" - param set SYS_MC_EST_GROUP 2 - param save - reboot - fi -else - # - # Q estimator (attitude estimation only) - # - if param compare SYS_MC_EST_GROUP 3 - then - attitude_estimator_q start - else - # - # EKF2 - # - param set SYS_MC_EST_GROUP 2 - ekf2 start & - fi -fi - -############################################################################### -# End Estimator Group Selection # -############################################################################### - # # Start Control Allocator # diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_apps b/ROMFS/px4fmu_common/init.d/rc.rover_apps index 1db046ace4a1..2decfbb5ed15 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_apps @@ -5,11 +5,6 @@ # NOTE: Script variables are declared/initialized/unset in the rcS script. # -# -# Start the attitude and position estimator. -# -ekf2 start & - # # Start Control Allocator # diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps index 848527a9e975..275664af7e26 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps @@ -1,9 +1,6 @@ #!/bin/sh # Standard apps for a differential drive rover. -# Start the attitude and position estimator. -ekf2 start & - # Start rover differential drive controller. differential_drive start diff --git a/ROMFS/px4fmu_common/init.d/rc.uuv_apps b/ROMFS/px4fmu_common/init.d/rc.uuv_apps index d2eb13208c25..f604b644525c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uuv_apps +++ b/ROMFS/px4fmu_common/init.d/rc.uuv_apps @@ -5,16 +5,6 @@ # NOTE: Script variables are declared/initialized/unset in the rcS script. # -############################################################################### -# Begin Estimator Group Selection # -############################################################################### - -ekf2 start & - -############################################################################### -# End Estimator Group Selection # -############################################################################### - # # Start Control Allocator # diff --git a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup index 1b7ddee5a569..42b9c7e876d7 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup +++ b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup @@ -76,5 +76,4 @@ fi if [ $VEHICLE_TYPE = none ] then echo "No autostart ID found" - ekf2 start & fi diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_apps b/ROMFS/px4fmu_common/init.d/rc.vtol_apps index fdc16af83dc5..c28adef56ae9 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_apps +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_apps @@ -5,16 +5,6 @@ # NOTE: Script variables are declared/initialized/unset in the rcS script. # -############################################################################### -# Begin Estimator group selection # -############################################################################### - -ekf2 start & - -############################################################################### -# End Estimator group selection # -############################################################################### - # # Start Control Allocator # diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 466fed1f624d..b9d46ce27dc7 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -391,6 +391,23 @@ else pwm_out start fi + # + # state estimator selection + if param compare -s EKF2_EN 1 + then + ekf2 start & + fi + + if param compare -s LPE_EN 1 + then + local_position_estimator start + fi + + if param compare -s ATT_EN 1 + then + attitude_estimator_q start + fi + # # Configure vehicle type specific parameters. # Note: rc.vehicle_setup is the entry point for all vehicle type specific setup. diff --git a/boards/diatone/mamba-f405-mk2/init/rc.board_defaults b/boards/diatone/mamba-f405-mk2/init/rc.board_defaults index 61c5953c4147..f5e37010631a 100644 --- a/boards/diatone/mamba-f405-mk2/init/rc.board_defaults +++ b/boards/diatone/mamba-f405-mk2/init/rc.board_defaults @@ -9,9 +9,4 @@ param set-default CBRK_SUPPLY_CHK 894281 # Disable safety switch by default param set-default CBRK_IO_SAFETY 22027 -# use the Q attitude estimator, it works w/o mag or GPS. -param set-default SYS_MC_EST_GROUP 3 -param set-default ATT_W_ACC 0.4 -param set-default ATT_W_GYRO_BIAS 0 - param set-default SYS_HAS_MAG 0 diff --git a/boards/flywoo/gn-f405/init/rc.board_defaults b/boards/flywoo/gn-f405/init/rc.board_defaults index c1fc72c526f1..51fd2a6fbcfd 100644 --- a/boards/flywoo/gn-f405/init/rc.board_defaults +++ b/boards/flywoo/gn-f405/init/rc.board_defaults @@ -12,14 +12,9 @@ param set-default CBRK_SUPPLY_CHK 894281 # Disable safety switch by default param set-default CBRK_IO_SAFETY 22027 -# EKF2 can be enabled when baro is avaialble and EKF2_MAG_TYPE is set to 5 -param set-default SYS_MC_EST_GROUP 2 param set-default EKF2_MAG_TYPE 5 param set-default SENS_BOARD_ROT 6 -param set-default ATT_W_ACC 0.4 -param set-default ATT_W_GYRO_BIAS 0 - param set-default SYS_HAS_MAG 0 # GPS is on Uart6 diff --git a/boards/omnibus/f4sd/init/rc.board_defaults b/boards/omnibus/f4sd/init/rc.board_defaults index 9e6affd3454b..2678eae827cb 100644 --- a/boards/omnibus/f4sd/init/rc.board_defaults +++ b/boards/omnibus/f4sd/init/rc.board_defaults @@ -12,9 +12,4 @@ param set-default CBRK_SUPPLY_CHK 894281 # Disable safety switch by default param set-default CBRK_IO_SAFETY 22027 -# use the Q attitude estimator, it works w/o mag or GPS. -param set-default SYS_MC_EST_GROUP 3 -param set-default ATT_W_ACC 0.4 -param set-default ATT_W_GYRO_BIAS 0 - param set-default SYS_HAS_MAG 0 diff --git a/boards/spracing/h7extreme/init/rc.board_defaults b/boards/spracing/h7extreme/init/rc.board_defaults index d2b9948883d9..92a8d971ab7b 100644 --- a/boards/spracing/h7extreme/init/rc.board_defaults +++ b/boards/spracing/h7extreme/init/rc.board_defaults @@ -12,9 +12,4 @@ param set-default CBRK_SUPPLY_CHK 894281 # Select the Generic 250 Racer by default param set-default SYS_AUTOSTART 4050 -# use the Q attitude estimator, it works w/o mag or GPS. -param set-default SYS_MC_EST_GROUP 3 -param set-default ATT_W_ACC 0.4 -param set-default ATT_W_GYRO_BIAS 0 - param set-default SYS_HAS_MAG 0 diff --git a/src/drivers/ins/vectornav/VectorNav.cpp b/src/drivers/ins/vectornav/VectorNav.cpp index 0278f63abdcb..369e56298ead 100644 --- a/src/drivers/ins/vectornav/VectorNav.cpp +++ b/src/drivers/ins/vectornav/VectorNav.cpp @@ -62,10 +62,6 @@ VectorNav::VectorNav(const char *port) : v = 0; param_set(param_find("EKF2_EN"), &v); - // SYS_MC_EST_GROUP 0 (disabled) - v = 0; - param_set(param_find("SYS_MC_EST_GROUP"), &v); - // SENS_IMU_MODE (VN handles sensor selection) v = 0; param_set(param_find("SENS_IMU_MODE"), &v); diff --git a/src/lib/parameters/param_translation.cpp b/src/lib/parameters/param_translation.cpp index 93cbddcdec42..490ad02f22c3 100644 --- a/src/lib/parameters/param_translation.cpp +++ b/src/lib/parameters/param_translation.cpp @@ -73,5 +73,74 @@ param_modify_on_import_ret param_modify_on_import(bson_node_t node) } } + // 2024-04-15 SYS_MC_EST_GROUP removed + if ((node->type == bson_type_t::BSON_INT32) && (strcmp("SYS_MC_EST_GROUP", node->name) == 0)) { + + int32_t value = node->i32; + + // value 1 local_position_estimator, attitude_estimator_q (unsupported) + if (value == 1) { + // enable local_position_estimator + int32_t lpe_en_val = 1; + int lpe_en_ret = param_set(param_find("LPE_EN"), &lpe_en_val); + + // enable attitude_estimator_q + int32_t att_en_val = 1; + int att_en_ret = param_set(param_find("ATT_EN"), &att_en_val); + + // disable ekf2 (only if enabling lpe and att_w was successful) + if (lpe_en_ret == PX4_OK && att_en_ret == PX4_OK) { + int32_t ekf2_en_val = 0; + param_set(param_find("EKF2_EN"), &ekf2_en_val); + + } else { + int32_t ekf2_en_val = 1; + param_set(param_find("EKF2_EN"), &ekf2_en_val); + } + + return param_modify_on_import_ret::PARAM_MODIFIED; + } + + // value 2 ekf2 (recommended) + if (value == 2) { + // disable local_position_estimator + int32_t lpe_en_val = 0; + param_set(param_find("LPE_EN"), &lpe_en_val); + + // disable attitude_estimator_q + int32_t att_en_val = 0; + param_set(param_find("ATT_EN"), &att_en_val); + + // enable ekf2 + int32_t ekf2_en_val = 1; + param_set(param_find("EKF2_EN"), &ekf2_en_val); + + return param_modify_on_import_ret::PARAM_MODIFIED; + } + + // value 3 Q attitude estimator (no position) + if (value == 3) { + // disable local_position_estimator + int32_t lpe_en_val = 0; + param_set(param_find("LPE_EN"), &lpe_en_val); + + // enable attitude_estimator_q + int32_t att_en_val = 1; + int att_en_ret = param_set(param_find("ATT_EN"), &att_en_val); + + // disable ekf2 (only if enabling att_w was successful) + if (att_en_ret == PX4_OK) { + int32_t ekf2_en_val = 0; + param_set(param_find("EKF2_EN"), &ekf2_en_val); + + } else { + int32_t ekf2_en_val = 1; + param_set(param_find("EKF2_EN"), &ekf2_en_val); + } + + return param_modify_on_import_ret::PARAM_MODIFIED; + } + } + return param_modify_on_import_ret::PARAM_NOT_MODIFIED; } diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c index 1417cd37b46e..23c0234380c9 100644 --- a/src/lib/systemlib/system_params.c +++ b/src/lib/systemlib/system_params.c @@ -83,20 +83,6 @@ PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0); */ PARAM_DEFINE_INT32(SYS_HITL, 0); -/** - * Set multicopter estimator group - * - * Set the group of estimators used for multicopters and VTOLs - * - * @value 1 local_position_estimator, attitude_estimator_q (unsupported) - * @value 2 ekf2 (recommended) - * @value 3 Q attitude estimator (no position) - * - * @reboot_required true - * @group System - */ -PARAM_DEFINE_INT32(SYS_MC_EST_GROUP, 2); - /** * Enable auto start of rate gyro thermal calibration at the next power up. * diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index b4da68f72275..7c47cfca30d6 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -180,6 +180,14 @@ AttitudeEstimatorQ::AttitudeEstimatorQ() : bool AttitudeEstimatorQ::init() { + uORB::SubscriptionData vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + vehicle_attitude_sub.update(); + + if (vehicle_attitude_sub.advertised() && (hrt_elapsed_time(&vehicle_attitude_sub.get().timestamp) < 1_s)) { + PX4_ERR("init failed, vehicle_attitude already advertised"); + return false; + } + if (!_sensors_sub.registerCallback()) { PX4_ERR("callback registration failed"); return false; diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c index 90a9342bb502..b9a3dc752d72 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c @@ -39,6 +39,16 @@ * @author Anton Babushkin */ +/** + * standalone attitude estimator enable (unsupported) + * + * Enable standalone quaternion based attitude estimator. + * + * @group Attitude Q estimator + * @boolean + */ +PARAM_DEFINE_INT32(ATT_EN, 0); + /** * Complimentary filter accelerometer weight * diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 1cdd097b12aa..dc5b4566839f 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -99,7 +99,10 @@ void EstimatorChecks::checkAndReport(const Context &context, Report &reporter) } } - if (missing_data && _param_sys_mc_est_group.get() == 2) { + int32_t param_ekf2_en = 0; + param_get(param_find_no_notification("EKF2_EN"), ¶m_ekf2_en); + + if (missing_data && (param_ekf2_en == 1)) { /* EVENT */ reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate, diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp index f5b807352492..7f41a9c86dbb 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp @@ -106,7 +106,6 @@ class EstimatorChecks : public HealthAndArmingCheckBase bool _nav_failure_imminent_warned{false}; DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, - (ParamInt) _param_sys_mc_est_group, (ParamInt) _param_sens_imu_mode, (ParamInt) _param_com_arm_mag_str, (ParamFloat) _param_com_arm_ekf_hgt, diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 9aec7b213c6a..e98ddd9a0bc0 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -237,7 +237,6 @@ EKF2::~EKF2() bool EKF2::multi_init(int imu, int mag) { // advertise all topics to ensure consistent uORB instance numbering - _ekf2_timestamps_pub.advertise(); _estimator_event_flags_pub.advertise(); _estimator_innovation_test_ratios_pub.advertise(); _estimator_innovation_variances_pub.advertise(); diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index b43f30440dfb..26386a45cc75 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -39,6 +39,14 @@ * */ +/** + * EKF2 enable + * + * @group EKF2 + * @boolean + */ +PARAM_DEFINE_INT32(EKF2_EN, 1); + /** * EKF prediction period * diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 5538965f0ed1..8517ff03b0eb 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -137,6 +137,14 @@ BlockLocalPositionEstimator::BlockLocalPositionEstimator() : bool BlockLocalPositionEstimator::init() { + uORB::SubscriptionData vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + vehicle_local_position_sub.update(); + + if (vehicle_local_position_sub.advertised() && (hrt_elapsed_time(&vehicle_local_position_sub.get().timestamp) < 1_s)) { + PX4_ERR("init failed, vehicle_local_position already advertised"); + return false; + } + if (!_sensors_sub.registerCallback()) { PX4_ERR("callback registration failed"); return false; diff --git a/src/modules/local_position_estimator/params.c b/src/modules/local_position_estimator/params.c index da199ca24675..636f4289b04d 100644 --- a/src/modules/local_position_estimator/params.c +++ b/src/modules/local_position_estimator/params.c @@ -1,6 +1,12 @@ #include -// 16 is max name length +/** + * Local position estimator enable (unsupported) + * + * @group Local Position Estimator + * @boolean + */ +PARAM_DEFINE_INT32(LPE_EN, 0); /** * Optical flow z offset from center diff --git a/test/mavsdk_tests/configs/sitl.json b/test/mavsdk_tests/configs/sitl.json index f2bf6e74b102..c2af766f2e95 100644 --- a/test/mavsdk_tests/configs/sitl.json +++ b/test/mavsdk_tests/configs/sitl.json @@ -14,10 +14,7 @@ "model": "iris", "vehicle": "iris", "test_filter": "[offboard_attitude]", - "timeout_min": 10, - "env": { - "SYS_MC_EST_GROUP": 3 - } + "timeout_min": 10 }, { "model": "standard_vtol", From 0f665f2772b93ffb2a543c1788998fb272771fca Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Thu, 11 Apr 2024 18:25:09 -0700 Subject: [PATCH 108/652] Added high rate esc_status logging to the high rate logging category along with actuator_outputs_debug. Both of these really help diagnosing odd flight behavior / crashes on VOXL2. Also changed the logger start commands in the VOXL2 standard and HITL startup scripts. --- boards/modalai/voxl2/target/voxl-px4-hitl-start | 10 +++------- boards/modalai/voxl2/target/voxl-px4-start | 15 ++++++++------- src/modules/logger/logged_topics.cpp | 2 ++ 3 files changed, 13 insertions(+), 14 deletions(-) diff --git a/boards/modalai/voxl2/target/voxl-px4-hitl-start b/boards/modalai/voxl2/target/voxl-px4-hitl-start index 45ef0b2ddf53..9dcc4bb4f03f 100755 --- a/boards/modalai/voxl2/target/voxl-px4-hitl-start +++ b/boards/modalai/voxl2/target/voxl-px4-hitl-start @@ -43,13 +43,6 @@ else param load fi -# Start logging and use timestamps for log files when possible. -# Add the "-e" option to start logging immediately. Default is -# to log only when armed. Caution must be used with the "-e" option -# because if power is removed without stopping the logger gracefully then -# the log file may be corrupted. -logger start -e -t -b 200 - /bin/sleep 1 # Start all of the processing modules on DSP @@ -97,6 +90,9 @@ mavlink stream -u 14556 -s GLOBAL_POSITION_INT -r 30 # start the slow normal mode for voxl-mavlink-server to forward to GCS mavlink start -x -u 14558 -o 14559 -r 100000 -n lo +# Start logging and use timestamps for log files when possible. +logger start -t -b 256 + /bin/sleep 1 mavlink boot_complete diff --git a/boards/modalai/voxl2/target/voxl-px4-start b/boards/modalai/voxl2/target/voxl-px4-start index ad9804451b33..2c2821bfe458 100755 --- a/boards/modalai/voxl2/target/voxl-px4-start +++ b/boards/modalai/voxl2/target/voxl-px4-start @@ -62,13 +62,6 @@ param select /data/px4/param/parameters # Load in all of the parameters that have been saved in the file param load -# Start logging and use timestamps for log files when possible. -# Add the "-e" option to start logging immediately. Default is -# to log only when armed. Caution must be used with the "-e" option -# because if power is removed without stopping the logger gracefully then -# the log file may be corrupted. -logger start -t - # IMU (accelerometer / gyroscope) if [ "$PLATFORM" == "M0104" ]; then /bin/echo "Starting IMU driver with rotation 12" @@ -235,6 +228,14 @@ mavlink stream -u 14556 -s SCALED_PRESSURE -r 10 # start the slow normal mode for voxl-mavlink-server to forward to GCS mavlink start -x -u 14558 -o 14559 -r 100000 -n lo +# Start logging and use timestamps for log files when possible. +# Add the "-e" option to start logging immediately. Default is +# to log only when armed. Caution must be used with the "-e" option +# because if power is removed without stopping the logger gracefully then +# the log file may be corrupted. Rather than using "-e" option it's better +# to use the SDLOG_MODE to do that. +logger start -t -b 256 + mavlink boot_complete # Optional MSP OSD driver for DJI goggles diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 1b0326234bcd..022f0b9068e1 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -316,7 +316,9 @@ void LoggedTopics::add_high_rate_topics() add_topic("vehicle_attitude_setpoint"); add_topic("vehicle_rates_setpoint"); + add_topic("esc_status", 5); add_topic("actuator_motors"); + add_topic("actuator_outputs_debug"); add_topic("actuator_servos"); add_topic_multi("vehicle_thrust_setpoint", 0, 2); add_topic_multi("vehicle_torque_setpoint", 0, 2); From d908b68c78231e101783e510f45e3c9a6f0a71b8 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Mon, 15 Apr 2024 13:09:19 -0700 Subject: [PATCH 109/652] lib/rc/dsm: update proto init to have reset incorporated as well (#22995) * update voxl2-slpi spektrum_rc driver --- boards/modalai/voxl2-slpi/src/CMakeLists.txt | 2 +- .../voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp | 8 +++++--- src/lib/rc/dsm.cpp | 3 +++ 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/boards/modalai/voxl2-slpi/src/CMakeLists.txt b/boards/modalai/voxl2-slpi/src/CMakeLists.txt index 4675d2e77a56..21a1e6090e3e 100644 --- a/boards/modalai/voxl2-slpi/src/CMakeLists.txt +++ b/boards/modalai/voxl2-slpi/src/CMakeLists.txt @@ -46,7 +46,7 @@ add_library(drivers_board # Add custom drivers for SLPI add_subdirectory(${PX4_BOARD_DIR}/src/drivers/rc_controller) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/mavlink_rc_in) -# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/spektrum_rc) +add_subdirectory(${PX4_BOARD_DIR}/src/drivers/spektrum_rc) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl) add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_sbus) diff --git a/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp b/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp index 0cf350edeb78..18067b1756eb 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp +++ b/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp @@ -110,16 +110,18 @@ void task_main(int argc, char *argv[]) } } - int uart_fd = dsm_init(device_path); + int uart_fd = qurt_uart_open(device_path, 115200); if (uart_fd < 0) { - PX4_ERR("dsm init failed"); + PX4_ERR("uart open failed"); return; } else if (verbose) { - PX4_INFO("Spektrum RC: dsm_init succeeded"); + PX4_INFO("Spektrum RC: uart open succeeded"); } + dsm_proto_init(); + orb_advert_t rc_pub = nullptr; // Use a buffer size of the double of the minimum, just to be safe. diff --git a/src/lib/rc/dsm.cpp b/src/lib/rc/dsm.cpp index d1b78a99bf69..257307a62078 100644 --- a/src/lib/rc/dsm.cpp +++ b/src/lib/rc/dsm.cpp @@ -481,6 +481,9 @@ void dsm_proto_init() channel_buffer[i].last_seen = 0; channel_buffer[i].value = 0; } + + /* reset the format detector */ + dsm_guess_format(true); } /** From 94d496605a316d3dc0be795c710eaa6860349960 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Mon, 15 Apr 2024 13:10:22 -0700 Subject: [PATCH 110/652] Voxl new board specific module (voxl_save_cal_params) to save calibration parameters (#22993) * Added Voxl board specific module to save calibration parameters in QGC format --- boards/modalai/voxl2/scripts/install-voxl.sh | 1 + boards/modalai/voxl2/src/CMakeLists.txt | 3 + .../voxl_save_cal_params/CMakeLists.txt | 43 ++++ .../VoxlSaveCalParams.cpp | 234 ++++++++++++++++++ .../VoxlSaveCalParams.hpp | 73 ++++++ boards/modalai/voxl2/target/voxl-px4-start | 4 +- 6 files changed, 357 insertions(+), 1 deletion(-) create mode 100644 boards/modalai/voxl2/src/modules/voxl_save_cal_params/CMakeLists.txt create mode 100644 boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp create mode 100644 boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.hpp diff --git a/boards/modalai/voxl2/scripts/install-voxl.sh b/boards/modalai/voxl2/scripts/install-voxl.sh index 6bf21f1e564c..4a88a7a56f80 100755 --- a/boards/modalai/voxl2/scripts/install-voxl.sh +++ b/boards/modalai/voxl2/scripts/install-voxl.sh @@ -128,6 +128,7 @@ adb shell "cd /usr/bin; /bin/ln -f -s px4 px4-uart_esc_driver" adb shell "cd /usr/bin; /bin/ln -f -s px4 px4-flight_mode_manager" adb shell "cd /usr/bin; /bin/ln -f -s px4 px4-imu_server" adb shell "cd /usr/bin; /bin/ln -f -s px4 px4-apps_sbus" +adb shell "cd /usr/bin; /bin/ln -f -s px4 px4-voxl_save_cal_params" # Make sure any required directories exist adb shell "/bin/mkdir -p /data/px4/param" diff --git a/boards/modalai/voxl2/src/CMakeLists.txt b/boards/modalai/voxl2/src/CMakeLists.txt index 97cc043a1483..f783825128f1 100644 --- a/boards/modalai/voxl2/src/CMakeLists.txt +++ b/boards/modalai/voxl2/src/CMakeLists.txt @@ -44,3 +44,6 @@ add_library(drivers_board # Add custom drivers add_subdirectory(${PX4_BOARD_DIR}/src/drivers/apps_sbus) + +# Add custom modules +add_subdirectory(${PX4_BOARD_DIR}/src/modules/voxl_save_cal_params) diff --git a/boards/modalai/voxl2/src/modules/voxl_save_cal_params/CMakeLists.txt b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/CMakeLists.txt new file mode 100644 index 000000000000..f645fd3c53b2 --- /dev/null +++ b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/CMakeLists.txt @@ -0,0 +1,43 @@ +############################################################################ +# +# Copyright (c) 2024 ModalAI, Inc. 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_module( + MODULE modules__voxl_save_cal_params + MAIN voxl_save_cal_params + COMPILE_FLAGS + SRCS + VoxlSaveCalParams.cpp + VoxlSaveCalParams.hpp + DEPENDS + px4_work_queue + ) diff --git a/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp new file mode 100644 index 000000000000..5c8717db267e --- /dev/null +++ b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp @@ -0,0 +1,234 @@ +/**************************************************************************** + * + * Copyright (c) 2024 ModalAI, Inc. 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 "VoxlSaveCalParams.hpp" + +#include +#include +#include +#include +#include + +using namespace std; + +static bool debug = false; + +VoxlSaveCalParams::VoxlSaveCalParams() : + ModuleParams(nullptr), + WorkItem(MODULE_NAME, px4::wq_configurations::lp_default) +{ +} + +bool +VoxlSaveCalParams::init() +{ + if (!_parameter_primary_set_value_request_sub.registerCallback()) { + PX4_ERR("callback registration failed"); + return false; + } + + return true; +} + +void +VoxlSaveCalParams::save_calibration_parameter_to_file(const char *name, param_type_t type, + param_value_u value) +{ + // If the parameter being set is a calibration parameter then save it out to + // a separate calibration file so that they can be preserved and reloaded + // after system updates + string cal_file_name = param_get_default_file(); + string cal_file_append; + string param_name(name); + string cal_strings[] = {"CAL_GYRO", "CAL_MAG", "CAL_BARO", "CAL_ACC"}; + + for (auto i : cal_strings) { + // Check to see if the parameter is one of the desired calibration parameters + if (param_name.substr(0, i.size()) == i) { + // We want the filename to be the standard parameters file name with + // the calibration type appended to it. + cal_file_append = i.substr(3, i.size()); + // Make sure it is lowercase + transform(cal_file_append.begin(), cal_file_append.end(), cal_file_append.begin(), ::tolower); + // And add a cal file extension + cal_file_append += ".cal"; + break; + } + } + + // Check for level horizon calibration parameters + if (cal_file_append.empty() && + (param_name == "SENS_BOARD_X_OFF" || param_name == "SENS_BOARD_Y_OFF")) { + cal_file_append = "_level.cal"; + } + + // Check for RC calibration parameters + if (cal_file_append.empty() && name[0] == 'R' && name[1] == 'C' && isdigit(name[2])) { + cal_file_append = "_rc.cal"; + } + + if (! cal_file_append.empty()) { + cal_file_name += cal_file_append; + + stringstream param_data_stream; + + switch (type) { + case PARAM_TYPE_INT32: + param_data_stream << value.i; + param_data_stream << "\t" << 6; + break; + + case PARAM_TYPE_FLOAT: + param_data_stream << value.f; + param_data_stream << "\t" << 9; + break; + + default: + PX4_ERR("Calibration parameter must be either int or float"); + break; + } + + string param_data; + param_data += "1\t1\t"; + param_data += param_name; + param_data += "\t"; + param_data += param_data_stream.str(); + + if (debug) { PX4_INFO("Writing %s to file %s", param_data.c_str(), cal_file_name.c_str()); } + + // open a file in write (append) mode. + ofstream cal_file; + cal_file.open(cal_file_name, ios_base::app); + + if (cal_file) { + cal_file << param_data << endl; + cal_file.close(); + + } else { + PX4_ERR("Couldn't open %s for writing calibration value", cal_file_name.c_str()); + } + } +} + +void +VoxlSaveCalParams::Run() +{ + if (should_exit()) { + _parameter_primary_set_value_request_sub.unregisterCallback(); + exit_and_cleanup(); + return; + } + + parameter_set_value_request_s req; + + if (_parameter_primary_set_value_request_sub.copy(&req)) { + // PX4_INFO("Got set value request in autosave module"); + + // debug_counters.set_value_received++; + + param_t param = req.parameter_index; + param_value_u value; + value.i = 0; + value.f = 0.0f; + + switch (param_type(param)) { + case PARAM_TYPE_INT32: + param_set_no_remote_update(param, (const void *) &req.int_value, true); + value.i = req.int_value; + break; + + case PARAM_TYPE_FLOAT: + param_set_no_remote_update(param, (const void *) &req.float_value, true); + value.f = req.float_value; + break; + + default: + PX4_ERR("Parameter must be either int or float"); + break; + } + + save_calibration_parameter_to_file(param_name(param), param_type(param), value); + } +} + +int VoxlSaveCalParams::task_spawn(int argc, char *argv[]) +{ + VoxlSaveCalParams *instance = new VoxlSaveCalParams(); + + if (instance) { + _object.store(instance); + _task_id = task_id_is_work_queue; + + if (instance->init()) { + return PX4_OK; + } + + } else { + PX4_ERR("alloc failed"); + } + + delete instance; + _object.store(nullptr); + _task_id = -1; + + return PX4_ERROR; +} + +int VoxlSaveCalParams::custom_command(int argc, char *argv[]) +{ + return print_usage("unknown command"); +} + +int VoxlSaveCalParams::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +This implements autosaving of calibration parameters on VOXL2 platform. + +)DESCR_STR"); + + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int voxl_save_cal_params_main(int argc, char *argv[]) +{ + return VoxlSaveCalParams::main(argc, argv); +} diff --git a/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.hpp b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.hpp new file mode 100644 index 000000000000..791bbf5073f8 --- /dev/null +++ b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.hpp @@ -0,0 +1,73 @@ +/**************************************************************************** + * + * Copyright (c) 2024 ModalAI, Inc. 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 +#include +#include +#include +#include +#include + +using namespace time_literals; + +class VoxlSaveCalParams : public ModuleBase, public ModuleParams, + public px4::WorkItem +{ +public: + VoxlSaveCalParams(); + ~VoxlSaveCalParams() = default; + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + bool init(); + +private: + void Run() override; + + void save_calibration_parameter_to_file(const char *name, param_type_t type, param_value_u value); + + uORB::SubscriptionCallbackWorkItem _parameter_primary_set_value_request_sub{this, ORB_ID(parameter_primary_set_value_request)}; +}; diff --git a/boards/modalai/voxl2/target/voxl-px4-start b/boards/modalai/voxl2/target/voxl-px4-start index 2c2821bfe458..014d046c8be9 100755 --- a/boards/modalai/voxl2/target/voxl-px4-start +++ b/boards/modalai/voxl2/target/voxl-px4-start @@ -204,11 +204,13 @@ dataman start navigator start # This bridge allows raw data packets to be sent over UART to the ESC -voxl2_io_bridge start +# voxl2_io_bridge start # Start uxrce_dds_client for ros2 offboard messages from agent over localhost uxrce_dds_client start -t udp -h 127.0.0.1 -p 8888 +voxl_save_cal_params start + # On M0052 there is only one IMU. So, PX4 needs to # publish IMU samples externally for VIO to use. if [ $PLATFORM = "M0052" ]; then From 05cd850ae3c8b08a5eba9e5b1bf3f659cab31154 Mon Sep 17 00:00:00 2001 From: JaeyoungLim Date: Mon, 15 Apr 2024 12:11:56 +0200 Subject: [PATCH 111/652] Document vehicle attitude message --- msg/VehicleAttitude.msg | 1 + 1 file changed, 1 insertion(+) diff --git a/msg/VehicleAttitude.msg b/msg/VehicleAttitude.msg index 46e1fc0bcb4e..99e6f25c2e42 100644 --- a/msg/VehicleAttitude.msg +++ b/msg/VehicleAttitude.msg @@ -1,4 +1,5 @@ # This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use +# The quaternion uses the Hamilton convention, and the order is q(w, x, y, z) uint64 timestamp # time since system start (microseconds) From 2fe4fec491afd7a6be18e3decdb0610a6d65cc06 Mon Sep 17 00:00:00 2001 From: Kalyan Sriram Date: Fri, 5 Apr 2024 09:56:58 +0200 Subject: [PATCH 112/652] Add python script to translate C param to new yaml file --- Tools/migrate_c_params.py | 497 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 497 insertions(+) create mode 100755 Tools/migrate_c_params.py diff --git a/Tools/migrate_c_params.py b/Tools/migrate_c_params.py new file mode 100755 index 000000000000..a51e75c39ba3 --- /dev/null +++ b/Tools/migrate_c_params.py @@ -0,0 +1,497 @@ +#!/usr/bin/python3 + +""" +Migrate c parameter definitions to yaml module definitions. + +This script is used to transition legacy c parameter definitions to +yaml module definitions. It parses each specified legacy c file +and produces a corresponding yaml definition in the same directory. +For modules with multiple parameter c files and/or existing module.yaml files, +the resulting list of yaml files must be merged separately, either manually +or with a tool like yq4: + + yq eval-all '. as $item ireduce ({}; . *+ $item)' *.yaml + +The legacy files and temporary yaml files can then be manually deleted +and the CMakeLists.txt updated after proofreading. +""" + +import argparse +import ast +import sys +import re +import math +import logging +import os +from dataclasses import dataclass, field +from typing import Any + +import yaml + + +global default_var +default_var = {} + + +# define sorting order of the fields +PRIORITIES = { + "board": 9, + "short_desc": 8, + "long_desc": 7, + "min": 5, + "max": 4, + "unit": 3, + "decimal": 2, + # all others == 0 (sorted alphabetically) +} + + +@dataclass +class Parameter: + """ + Single parameter + """ + + name: str + type: str + fields: dict[str, str] = field(init=False, default_factory=dict) + default: str = "" + category: str = "" + enum: dict[str, str] = field(init=False, default_factory=dict) + bitmask: dict[int, str] = field(init=False, default_factory=dict) + volatile: bool = False + boolean: bool = False + + def __lt__(self, other): + return self.name < other.name + + @property + def field_keys(self) -> list[str]: + """ + Return list of existing field codes in convenient order + """ + keys = self.fields.keys() + keys = sorted(keys) + keys = sorted(keys, key=lambda x: PRIORITIES.get(x, 0), reverse=True) + return keys + + +@dataclass +class ParameterGroup: + """ + Single parameter group + """ + + name: str + parameters: list[Parameter] = field(init=False, default_factory=list) + no_code_generation: bool = False + + +class SourceParser: + """ + Parses provided data and stores all found parameters internally. + """ + + re_split_lines = re.compile(r'[\r\n]+') + re_comment_start = re.compile(r'^\/\*\*') + re_comment_content = re.compile(r'^\*\s*(.*)') + re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)') + re_comment_end = re.compile(r'(.*?)\s*\*\/') + re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;') + re_px4_parameter_definition = re.compile(r'PX4_PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*\)\s*;') + re_px4_param_default_definition = re.compile(r'#define\s*PARAM_([A-Z_][A-Z0-9_]*)\s*([^ ,\)]+)\s*') + re_cut_type_specifier = re.compile(r'[a-z]+$') + re_is_a_number = re.compile(r'^-?[0-9\.]') + re_remove_dots = re.compile(r'\.+$') + re_remove_carriage_return = re.compile('\n+') + + valid_tags = set(["group", "board", "min", "max", "unit", "decimal", + "increment", "reboot_required", "value", "boolean", + "bit", "category", "volatile"]) + + # Order of parameter groups + priority = { + # All other groups = 0 (sort alphabetically) + "Miscellaneous": -10 + } + + def __init__(self): + self.param_groups = {} + + def parse(self, contents): + """ + Incrementally parse program contents and append all found parameters + to the list. + """ + # This code is essentially a comment-parsing grammar. "state" + # represents parser state. It contains human-readable state + # names. + state = None + for line in self.re_split_lines.split(contents): + line = line.strip() + # Ignore empty lines + if line == "": + continue + if self.re_comment_start.match(line): + state = "wait-short" + short_desc = None + long_desc = None + tags = {} + def_values = {} + def_bitmask = {} + elif state is not None and state != "comment-processed": + m = self.re_comment_end.search(line) + if m: + line = m.group(1) + last_comment_line = True + else: + last_comment_line = False + m = self.re_comment_content.match(line) + if m: + comment_content = m.group(1) + if comment_content == "": + # When short comment ends with empty comment line, + # start waiting for the next part - long comment. + if state == "wait-short-end": + state = "wait-long" + else: + m = self.re_comment_tag.match(comment_content) + if m: + tag, desc = m.group(1, 2) + if (tag == "value"): + # Take the meta info string and split + # the code and description + metainfo = desc.split(" ", 1) + def_values[metainfo[0]] = metainfo[1] + elif (tag == "bit"): + # Take the meta info string and split + # the code and description + metainfo = desc.split(" ", 1) + def_bitmask[metainfo[0]] = metainfo[1] + else: + tags[tag] = desc + current_tag = tag + state = "wait-tag-end" + elif state == "wait-short": + # Store first line of the short description + short_desc = comment_content + state = "wait-short-end" + elif state == "wait-short-end": + # Append comment line to the short description + short_desc += "\n" + comment_content + elif state == "wait-long": + # Store first line of the long description + long_desc = comment_content + state = "wait-long-end" + elif state == "wait-long-end": + # Append comment line to the long description + long_desc += "\n" + comment_content + elif state == "wait-tag-end": + # Append comment line to the tag text + tags[current_tag] += "\n" + comment_content + else: + raise AssertionError( + "Invalid parser state: %s" % state) + elif not last_comment_line: + # Invalid comment line (inside comment, but not + # startin with "*" or "*/". Reset parsed content. + state = None + if last_comment_line: + state = "comment-processed" + else: + tp = None + name = None + defval = "" + # Non-empty line outside the comment + m = self.re_px4_param_default_definition.match(line) + # Default value handling + if m: + name_m, defval_m = m.group(1, 2) + default_var[name_m] = defval_m + m = self.re_parameter_definition.match(line) + if m: + tp, name, defval = m.group(1, 2, 3) + else: + m = self.re_px4_parameter_definition.match(line) + if m: + tp, name = m.group(1, 2) + if (name+'_DEFAULT') in default_var: + defval = default_var[name+'_DEFAULT'] + if tp is not None: + # Remove trailing type specifier from numbers: 0.1f => 0.1 + if defval != "" and self.re_is_a_number.match(defval): + defval = self.re_cut_type_specifier.sub('', defval) + param = Parameter(name=name, type=tp, default=defval) + param.fields["short_desc"] = name + # If comment was found before the parameter declaration, + # inject its data into the newly created parameter. + group = "Miscellaneous" + if state == "comment-processed": + if short_desc is not None: + if '\n' in short_desc: + raise Exception('short description must be a single line (parameter: {:})'.format(name)) + if len(short_desc) > 150: + raise Exception('short description too long (150 max, is {:}, parameter: {:})'.format(len(short_desc), name)) + param.fields["short_desc"] = self.re_remove_dots.sub('', short_desc) + if long_desc is not None: + long_desc = self.re_remove_carriage_return.sub(' ', long_desc) + param.fields["long_desc"] = long_desc + for tag in tags: + if tag == "group": + group = tags[tag] + elif tag == "volatile": + param.volatile = True + elif tag == "category": + param.category = tags[tag] + elif tag == "boolean": + param.boolean = True + elif tag not in self.valid_tags: + sys.stderr.write("Skipping invalid documentation tag: '%s'\n" % tag) + return False + else: + param.fields[tag] = tags[tag] + for def_value in def_values: + param.enum[def_value] = def_values[def_value] + for def_bit in def_bitmask: + param.bitmask[def_bit] = def_bitmask[def_bit] + # Store the parameter + if group not in self.param_groups: + self.param_groups[group] = ParameterGroup(group) + self.param_groups[group].parameters.append(param) + state = None + return True + + def validate(self): + """ + Validates the parameter meta data. + """ + seenParamNames = [] + #allowedUnits should match set defined in /Firmware/validation/module_schema.yaml + allowedUnits = set ([ + '%', 'Hz', '1/s', 'mAh', + 'rad', '%/rad', 'rad/s', 'rad/s^2', '%/rad/s', 'rad s^2/m', 'rad s/m', + 'bit/s', 'B/s', + 'deg', 'deg*1e7', 'deg/s', + 'celcius', 'gauss', 'gauss/s', 'gauss^2', + 'hPa', 'kg', 'kg/m^2', 'kg m^2', + 'mm', 'm', 'm/s', 'm^2', 'm/s^2', 'm/s^3', 'm/s^2/sqrt(Hz)', 'm/s/rad', + 'Ohm', 'V', 'A', + 'us', 'ms', 's', + 'S', 'A/%', '(m/s^2)^2', 'm/m', 'tan(rad)^2', '(m/s)^2', 'm/rad', + 'm/s^3/sqrt(Hz)', 'm/s/sqrt(Hz)', 's/(1000*PWM)', '%m/s', 'min', 'us/C', '1/s/sqrt(Hz)', + 'N/(m/s)', 'Nm/rad', 'Nm/(rad/s)', 'Nm', 'N', + 'normalized_thrust/s', 'normalized_thrust', 'norm', 'SD','', 'RPM']) + + for group in self.parameter_groups: + for param in sorted(group.parameters): + name = param.name + if len(name) > 16: + sys.stderr.write("Parameter Name {0} is too long (Limit is 16)\n".format(name)) + return False + board = param.fields.get("board", "") + # Check for duplicates + name_plus_board = name + "+" + board + for seenParamName in seenParamNames: + if seenParamName == name_plus_board: + sys.stderr.write("Duplicate parameter definition: {0}\n".format(name_plus_board)) + return False + seenParamNames.append(name_plus_board) + # Validate values + default = param.default + min = param.fields.get("min", "") + max = param.fields.get("max", "") + units = param.fields.get("unit", "") + if units not in allowedUnits: + sys.stderr.write("Invalid unit in {0}: {1}\n".format(name, units)) + return False + #sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max)) + if default != "" and not self.is_number(default): + sys.stderr.write("Default value not number: {0} {1}\n".format(name, default)) + return False + # if default != "" and "." not in default: + # sys.stderr.write("Default value does not contain dot (e.g. 10 needs to be written as 10.0): {0} {1}\n".format(name, default)) + # return False + if min != "": + if not self.is_number(default): + sys.stderr.write("Min value not number: {0} {1}\n".format(name, min)) + return False + if default != "" and float(default) < float(min): + sys.stderr.write("Default value is smaller than min: {0} default:{1} min:{2}\n".format(name, default, min)) + return False + if max != "": + if not self.is_number(max): + sys.stderr.write("Max value not number: {0} {1}\n".format(name, max)) + return False + if default != "" and float(default) > float(max): + sys.stderr.write("Default value is larger than max: {0} default:{1} max:{2}\n".format(name, default, max)) + return False + for code in sorted(param.enum, key=float): + if not self.is_number(code): + sys.stderr.write("Min value not number: {0} {1}\n".format(name, code)) + return False + if param.enum.get(code, "") == "": + sys.stderr.write("Description for enum value is empty: {0} {1}\n".format(name, code)) + return False + for index in sorted(param.bitmask.keys(), key=float): + if not self.is_number(index): + sys.stderr.write("bit value not number: {0} {1}\n".format(name, index)) + return False + if not int(min) <= math.pow(2, int(index)) <= int(max): + sys.stderr.write("Bitmask bit must be between {0} and {1}: {2} {3}\n".format(min, max, name, math.pow(2, int(index)))) + return False + if param.bitmask.get(index, "") == "": + sys.stderr.write("Description for bitmask bit is empty: {0} {1}\n".format(name, index)) + return False + return True + + def is_number(self, num): + try: + float(num) + return True + except ValueError: + return False + + @property + def parameter_groups(self) -> list[ParameterGroup]: + """ + Returns the parsed list of parameters. Every parameter is a Parameter + object. Note that returned object is not a copy. Modifications affect + state of the parser. + """ + groups = self.param_groups.values() + groups = sorted(groups, key=lambda x: x.name) + groups = sorted(groups, key=lambda x: self.priority.get(x.name, 0), + reverse=True) + + return groups + + +def parse(filename: str) -> list[ParameterGroup]: + with open(filename) as f: + cdata = f.read() + + parser = SourceParser() + if not parser.parse(cdata): + logging.error(f"Error parsing c parameter file {filename}") + sys.exit(1) + if not parser.validate(): + logging.error(f"Error while validating c parameter file {filename}") + sys.exit(1) + + return parser.parameter_groups + + +def cast(val: str) -> Any: + if val == "true": + return True + elif val == "false": + return False + try: + return ast.literal_eval(val) + except ValueError: + return val + + +def generate_yaml(filename: str, groups: list[ParameterGroup]) -> str: + data = dict() + + module_name = os.path.dirname(os.path.realpath(filename)).split(os.sep)[-1] + + data["module_name"] = module_name + data["parameters"] = list() + + for group in groups: + g = dict() + g["group"] = group.name + g["definitions"] = dict() + + for parameter in group.parameters: + p = dict() + + p["default"] = cast(parameter.default) + if parameter.category != "": + p["category"] = parameter.category.title() + p["volatile"] = bool(parameter.volatile) + # the enum check has to happen first + # since some parameters are both boolean and enum at the same time + # (even with more than 0 and 1 as options for some reason) so let's assume + # they are enums not booleans + if len(parameter.enum) > 0: + p["type"] = "enum" + p["values"] = dict() + for key, val in parameter.enum.items(): + try: + p["values"][int(key)] = val + except ValueError: + p["values"][float(key)] = val + p["type"] = "float" + elif parameter.boolean: + p["type"] = "boolean" + elif len(parameter.bitmask) > 0: + p["type"] = "bitmask" + p["bit"] = dict() + for key, val in parameter.bitmask.items(): + p["bit"][int(key)] = val.strip() + elif parameter.type == "FLOAT": + p["type"] = "float" + else: + p["type"] = "int32" + + p["description"] = dict() + p["description"]["short"] = parameter.fields["short_desc"] + del parameter.fields["short_desc"] + if "long_desc" in parameter.fields: + p["description"]["long"] = parameter.fields["long_desc"] + del parameter.fields["long_desc"] + + for key, val in parameter.fields.items(): + try: + p[key] = cast(val) + except SyntaxError: + p[key] = val + + g["definitions"][parameter.name] = p + + data["parameters"].append(g) + + return yaml.dump(data) + + +def main(): + parser = argparse.ArgumentParser(description="Migrate legacy c parameter definitions to yaml") + parser.add_argument('input_file', nargs='+', help='input file(s)') + parser.add_argument('--update-cmake', action=argparse.BooleanOptionalAction) + args = parser.parse_args() + + input_files = args.input_file + update_cmake = args.update_cmake + + logging.basicConfig(level=logging.INFO) + + for filename in input_files: + logging.info(f"Migrating c parameter file {filename}") + + parameter_groups = parse(filename) + output = generate_yaml(filename, parameter_groups) + + dirname, fname = os.path.split(os.path.realpath(filename)) + fname = fname.split(".")[0] + with open(os.path.join(dirname, f"module.{fname}.yaml"), "w") as f: + f.write(output) + if update_cmake: + with open(os.path.join(dirname, "CMakeLists.txt"), "r+") as f: + content = f.read() + if "MODULE_CONFIG" not in content: + try: + index = content.index("DEPENDS") + except ValueError: + index = content.index("px4_add_module") + index += content[index:].index(")") + content = content[:index] + "MODULE_CONFIG\n\t\tmodule.yaml\n\t" + content[index:] + f.seek(0) + f.write(content) + f.truncate() + + +if __name__ == "__main__": + main() From 42a16bd91da376b319eff744ccdbd59b8ad0fa42 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 5 Apr 2024 11:06:29 +0200 Subject: [PATCH 113/652] order yaml fileds --- Tools/migrate_c_params.py | 71 +++++++-------------------------------- 1 file changed, 12 insertions(+), 59 deletions(-) diff --git a/Tools/migrate_c_params.py b/Tools/migrate_c_params.py index a51e75c39ba3..042bdfb543f9 100755 --- a/Tools/migrate_c_params.py +++ b/Tools/migrate_c_params.py @@ -28,24 +28,9 @@ import yaml - global default_var default_var = {} - -# define sorting order of the fields -PRIORITIES = { - "board": 9, - "short_desc": 8, - "long_desc": 7, - "min": 5, - "max": 4, - "unit": 3, - "decimal": 2, - # all others == 0 (sorted alphabetically) -} - - @dataclass class Parameter: """ @@ -65,17 +50,6 @@ class Parameter: def __lt__(self, other): return self.name < other.name - @property - def field_keys(self) -> list[str]: - """ - Return list of existing field codes in convenient order - """ - keys = self.fields.keys() - keys = sorted(keys) - keys = sorted(keys, key=lambda x: PRIORITIES.get(x, 0), reverse=True) - return keys - - @dataclass class ParameterGroup: """ @@ -266,21 +240,6 @@ def validate(self): Validates the parameter meta data. """ seenParamNames = [] - #allowedUnits should match set defined in /Firmware/validation/module_schema.yaml - allowedUnits = set ([ - '%', 'Hz', '1/s', 'mAh', - 'rad', '%/rad', 'rad/s', 'rad/s^2', '%/rad/s', 'rad s^2/m', 'rad s/m', - 'bit/s', 'B/s', - 'deg', 'deg*1e7', 'deg/s', - 'celcius', 'gauss', 'gauss/s', 'gauss^2', - 'hPa', 'kg', 'kg/m^2', 'kg m^2', - 'mm', 'm', 'm/s', 'm^2', 'm/s^2', 'm/s^3', 'm/s^2/sqrt(Hz)', 'm/s/rad', - 'Ohm', 'V', 'A', - 'us', 'ms', 's', - 'S', 'A/%', '(m/s^2)^2', 'm/m', 'tan(rad)^2', '(m/s)^2', 'm/rad', - 'm/s^3/sqrt(Hz)', 'm/s/sqrt(Hz)', 's/(1000*PWM)', '%m/s', 'min', 'us/C', '1/s/sqrt(Hz)', - 'N/(m/s)', 'Nm/rad', 'Nm/(rad/s)', 'Nm', 'N', - 'normalized_thrust/s', 'normalized_thrust', 'norm', 'SD','', 'RPM']) for group in self.parameter_groups: for param in sorted(group.parameters): @@ -301,16 +260,9 @@ def validate(self): min = param.fields.get("min", "") max = param.fields.get("max", "") units = param.fields.get("unit", "") - if units not in allowedUnits: - sys.stderr.write("Invalid unit in {0}: {1}\n".format(name, units)) - return False - #sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max)) if default != "" and not self.is_number(default): sys.stderr.write("Default value not number: {0} {1}\n".format(name, default)) return False - # if default != "" and "." not in default: - # sys.stderr.write("Default value does not contain dot (e.g. 10 needs to be written as 10.0): {0} {1}\n".format(name, default)) - # return False if min != "": if not self.is_number(default): sys.stderr.write("Min value not number: {0} {1}\n".format(name, min)) @@ -408,10 +360,15 @@ def generate_yaml(filename: str, groups: list[ParameterGroup]) -> str: for parameter in group.parameters: p = dict() - p["default"] = cast(parameter.default) + p["description"] = dict() + p["description"]["short"] = parameter.fields["short_desc"] + del parameter.fields["short_desc"] + if "long_desc" in parameter.fields: + p["description"]["long"] = parameter.fields["long_desc"] + del parameter.fields["long_desc"] + if parameter.category != "": p["category"] = parameter.category.title() - p["volatile"] = bool(parameter.volatile) # the enum check has to happen first # since some parameters are both boolean and enum at the same time # (even with more than 0 and 1 as options for some reason) so let's assume @@ -436,13 +393,10 @@ def generate_yaml(filename: str, groups: list[ParameterGroup]) -> str: p["type"] = "float" else: p["type"] = "int32" + p["default"] = cast(parameter.default) - p["description"] = dict() - p["description"]["short"] = parameter.fields["short_desc"] - del parameter.fields["short_desc"] - if "long_desc" in parameter.fields: - p["description"]["long"] = parameter.fields["long_desc"] - del parameter.fields["long_desc"] + if parameter.volatile: + p["volatile"] = bool(parameter.volatile) for key, val in parameter.fields.items(): try: @@ -451,10 +405,9 @@ def generate_yaml(filename: str, groups: list[ParameterGroup]) -> str: p[key] = val g["definitions"][parameter.name] = p - data["parameters"].append(g) - return yaml.dump(data) + return yaml.dump(data, sort_keys=False) def main(): @@ -476,7 +429,7 @@ def main(): dirname, fname = os.path.split(os.path.realpath(filename)) fname = fname.split(".")[0] - with open(os.path.join(dirname, f"module.{fname}.yaml"), "w") as f: + with open(os.path.join(dirname, f"module_{fname}.yaml"), "w") as f: f.write(output) if update_cmake: with open(os.path.join(dirname, "CMakeLists.txt"), "r+") as f: From 7a973eddce84c1e50e41cdb8c277f878bf84f8c7 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 5 Apr 2024 11:32:18 +0200 Subject: [PATCH 114/652] ekf2: migrate param to yaml --- src/modules/ekf2/CMakeLists.txt | 6 + src/modules/ekf2/ekf2_params.c | 1580 ----------------------- src/modules/ekf2/ekf2_params_multi.c | 58 - src/modules/ekf2/ekf2_params_selector.c | 81 -- src/modules/ekf2/ekf2_params_volatile.c | 43 - src/modules/ekf2/module.yaml | 1340 +++++++++++++++++++ src/modules/ekf2/params_multi.yaml | 24 + src/modules/ekf2/params_selector.yaml | 47 + src/modules/ekf2/params_volatile.yaml | 13 + 9 files changed, 1430 insertions(+), 1762 deletions(-) delete mode 100644 src/modules/ekf2/ekf2_params.c delete mode 100644 src/modules/ekf2/ekf2_params_multi.c delete mode 100644 src/modules/ekf2/ekf2_params_selector.c delete mode 100644 src/modules/ekf2/ekf2_params_volatile.c create mode 100644 src/modules/ekf2/module.yaml create mode 100644 src/modules/ekf2/params_multi.yaml create mode 100644 src/modules/ekf2/params_selector.yaml create mode 100644 src/modules/ekf2/params_volatile.yaml diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 8ddca66d92cd..2914f5a6b86a 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -241,6 +241,12 @@ px4_add_module( ${EKF_GENERATED_FILES} + MODULE_CONFIG + module.yaml + params_multi.yaml + params_volatile.yaml + params_selector.yaml + DEPENDS geo hysteresis diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c deleted file mode 100644 index 26386a45cc75..000000000000 --- a/src/modules/ekf2/ekf2_params.c +++ /dev/null @@ -1,1580 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015-2023 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file ekf2_params.c - * Parameter definition for ekf2. - * - * @author Roman Bast - * - */ - -/** - * EKF2 enable - * - * @group EKF2 - * @boolean - */ -PARAM_DEFINE_INT32(EKF2_EN, 1); - -/** - * EKF prediction period - * - * EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. - * Actual filter update will be an integer multiple of IMU update. - * - * @group EKF2 - * @min 1000 - * @max 20000 - * @unit us - */ -PARAM_DEFINE_INT32(EKF2_PREDICT_US, 10000); - -/** - * IMU control - * - * @group EKF2 - * @min 0 - * @max 7 - * @bit 0 Gyro Bias - * @bit 1 Accel Bias - * @bit 2 Gravity vector fusion - */ -PARAM_DEFINE_INT32(EKF2_IMU_CTRL, 7); - -/** - * Magnetometer measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_DELAY, 0); - -/** - * Barometer measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BARO_DELAY, 0); - -/** - * GPS measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_DELAY, 110); - -/** - * Optical flow measurement delay relative to IMU measurements - * - * Assumes measurement is timestamped at trailing edge of integration period - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_DELAY, 20); - -/** - * Range finder measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_DELAY, 5); - -/** - * Airspeed measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ASP_DELAY, 100); - -/** - * Vision Position Estimator delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_DELAY, 0); - -/** - * Auxiliary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_AVEL_DELAY, 5); - -/** - * Integer bitmask controlling GPS checks. - * - * Set bits to 1 to enable checks. Checks enabled by the following bit positions - * 0 : Minimum required sat count set by EKF2_REQ_NSATS - * 1 : Maximum allowed PDOP set by EKF2_REQ_PDOP - * 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH - * 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV - * 4 : Maximum allowed speed error set by EKF2_REQ_SACC - * 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. - * 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. - * 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. - * 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT - * - * @group EKF2 - * @min 0 - * @max 511 - * @bit 0 Min sat count (EKF2_REQ_NSATS) - * @bit 1 Max PDOP (EKF2_REQ_PDOP) - * @bit 2 Max horizontal position error (EKF2_REQ_EPH) - * @bit 3 Max vertical position error (EKF2_REQ_EPV) - * @bit 4 Max speed error (EKF2_REQ_SACC) - * @bit 5 Max horizontal position rate (EKF2_REQ_HDRIFT) - * @bit 6 Max vertical position rate (EKF2_REQ_VDRIFT) - * @bit 7 Max horizontal speed (EKF2_REQ_HDRIFT) - * @bit 8 Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) - */ -PARAM_DEFINE_INT32(EKF2_GPS_CHECK, 245); - -/** - * Required EPH to use GPS. - * - * @group EKF2 - * @min 2 - * @max 100 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_EPH, 3.0f); - -/** - * Required EPV to use GPS. - * - * @group EKF2 - * @min 2 - * @max 100 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_EPV, 5.0f); - -/** - * Required speed accuracy to use GPS. - * - * @group EKF2 - * @min 0.5 - * @max 5.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_SACC, 0.5f); - -/** - * Required satellite count to use GPS. - * - * @group EKF2 - * @min 4 - * @max 12 - */ -PARAM_DEFINE_INT32(EKF2_REQ_NSATS, 6); - -/** - * Maximum PDOP to use GPS. - * - * @group EKF2 - * @min 1.5 - * @max 5.0 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_PDOP, 2.5f); - -/** - * Maximum horizontal drift speed to use GPS. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_HDRIFT, 0.1f); - -/** - * Maximum vertical drift speed to use GPS. - * - * @group EKF2 - * @min 0.1 - * @max 1.5 - * @decimal 2 - * @unit m/s - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_VDRIFT, 0.2f); - -/** - * Rate gyro noise for covariance prediction. - * - * @group EKF2 - * @min 0.0001 - * @max 0.1 - * @unit rad/s - * @decimal 4 - */ -PARAM_DEFINE_FLOAT(EKF2_GYR_NOISE, 1.5e-2f); - -/** - * Accelerometer noise for covariance prediction. - * - * @group EKF2 - * @min 0.01 - * @max 1.0 - * @unit m/s^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ACC_NOISE, 3.5e-1f); - -/** - * Process noise for IMU rate gyro bias prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.01 - * @unit rad/s^2 - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_GYR_B_NOISE, 1.0e-3f); - -/** - * Process noise for IMU accelerometer bias prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.01 - * @unit m/s^3 - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_ACC_B_NOISE, 3.0e-3f); - -/** - * Process noise for body magnetic field prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.1 - * @unit gauss/s - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 1.0e-4f); - -/** - * Process noise for earth magnetic field prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.1 - * @unit gauss/s - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_E_NOISE, 1.0e-3f); - -/** - * Process noise spectral density for wind velocity prediction. - * - * When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. - * - * @group EKF2 - * @min 0.0 - * @max 1.0 - * @unit m/s^2/sqrt(Hz) - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_WIND_NSD, 5.0e-2f); - -/** - * Measurement noise for GNSS velocity. - * - * @group EKF2 - * @min 0.01 - * @max 5.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_V_NOISE, 0.3f); - -/** - * Measurement noise for GNSS position. - * - * @group EKF2 - * @min 0.01 - * @max 10.0 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_P_NOISE, 0.5f); - -/** - * Measurement noise for non-aiding position hold. - * - * @group EKF2 - * @min 0.5 - * @max 50.0 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_NOAID_NOISE, 10.0f); - -/** - * Measurement noise for barometric altitude. - * - * @group EKF2 - * @min 0.01 - * @max 15.0 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_BARO_NOISE, 3.5f); - -/** - * Measurement noise for magnetic heading fusion. - * - * @group EKF2 - * @min 0.01 - * @max 1.0 - * @unit rad - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_HEAD_NOISE, 0.3f); - -/** - * Measurement noise for magnetometer 3-axis fusion. - * - * @group EKF2 - * @min 0.001 - * @max 1.0 - * @unit gauss - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_NOISE, 5.0e-2f); - -/** - * Measurement noise for airspeed fusion. - * - * @group EKF2 - * @min 0.5 - * @max 5.0 - * @unit m/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_EAS_NOISE, 1.4f); - -/** - * Gate size for synthetic sideslip fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BETA_GATE, 5.0f); - -/** - * Noise for synthetic sideslip fusion. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_BETA_NOISE, 0.3f); - -/** - * Gate size for heading fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_HDG_GATE, 2.6f); - -/** - * Gate size for magnetometer XYZ component fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_GATE, 3.0f); - -/** - * Integer bitmask controlling handling of magnetic declination. - * - * Set bits in the following positions to enable functions. - * 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. - * 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. - * - * @group EKF2 - * @min 0 - * @max 3 - * @bit 0 use geo_lookup declination - * @bit 1 save EKF2_MAG_DECL on disarm - * @reboot_required true - */ -PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 3); - -/** - * Type of magnetometer fusion - * - * Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. - * The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. - * If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. - * If set to 'Magnetic heading' magnetic heading fusion is used at all times. - * If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). - * @group EKF2 - * @value 0 Automatic - * @value 1 Magnetic heading - * @value 5 None - * @reboot_required true - */ -PARAM_DEFINE_INT32(EKF2_MAG_TYPE, 0); - -/** - * Horizontal acceleration threshold used for heading observability check - * - * The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active. - * - * @group EKF2 - * @min 0.0 - * @max 5.0 - * @unit m/s^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_ACCLIM, 0.5f); - -/** - * Gate size for barometric and GPS height fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BARO_GATE, 5.0f); - -/** - * Baro deadzone range for height fusion - * - * Sets the value of deadzone applied to negative baro innovations. - * Deadzone is enabled when EKF2_GND_EFF_DZ > 0. - * - * @group EKF2 - * @min 0.0 - * @max 10.0 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GND_EFF_DZ, 4.0f); - -/** - * Height above ground level for ground effect zone - * - * Sets the maximum distance to the ground level where negative baro innovations are expected. - * - * @group EKF2 - * @min 0.0 - * @max 5.0 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GND_MAX_HGT, 0.5f); - -/** - * Gate size for GNSS position fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_P_GATE, 5.0f); - -/** - * Gate size for GNSS velocity fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 5.0f); - -/** - * Gate size for TAS fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_TAS_GATE, 5.0f); - -/** - * Determines the reference source of height data used by the EKF. - * - * When multiple height sources are enabled at the same time, the height estimate will - * always converge towards the reference height source selected by this parameter. - * - * The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. - * - * @group EKF2 - * @value 0 Barometric pressure - * @value 1 GPS - * @value 2 Range sensor - * @value 3 Vision - * @reboot_required true - */ -PARAM_DEFINE_INT32(EKF2_HGT_REF, 1); - -/** - * Barometric sensor height aiding - * - * If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other - * height sources (if activated). - * - * @group EKF2 - * @boolean - */ -PARAM_DEFINE_INT32(EKF2_BARO_CTRL, 1); - -/** - * External vision (EV) sensor aiding - * - * Set bits in the following positions to enable: - * 0 : Horizontal position fusion - * 1 : Vertical position fusion - * 2 : 3D velocity fusion - * 3 : Yaw - * - * @group EKF2 - * @min 0 - * @max 15 - * @bit 0 Horizontal position - * @bit 1 Vertical position - * @bit 2 3D velocity - * @bit 3 Yaw - */ -PARAM_DEFINE_INT32(EKF2_EV_CTRL, 15); - -/** - * GNSS sensor aiding - * - * Set bits in the following positions to enable: - * 0 : Longitude and latitude fusion - * 1 : Altitude fusion - * 2 : 3D velocity fusion - * 3 : Dual antenna heading fusion - * - * @group EKF2 - * @min 0 - * @max 15 - * @bit 0 Lon/lat - * @bit 1 Altitude - * @bit 2 3D velocity - * @bit 3 Dual antenna heading - */ -PARAM_DEFINE_INT32(EKF2_GPS_CTRL, 7); - -/** - * Range sensor height aiding - * - * WARNING: Range finder measurements are less reliable and can experience unexpected errors. - * For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, - * unless baro errors are severe enough to cause problems with landing and takeoff. - * - * To en-/disable range finder for terrain height estimation, use EKF2_TERR_MASK instead. - * - * If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other - * height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in "conditional" mode. - * - * Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) - * operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state - * estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does - * not occur until above EKF2_RNG_A_HMAX. - * - * @group EKF2 - * @value 0 Disable range fusion - * @value 1 Enabled (conditional mode) - * @value 2 Enabled - */ -PARAM_DEFINE_INT32(EKF2_RNG_CTRL, 1); - -/** - * Integer bitmask controlling fusion sources of the terrain estimator - * - * Set bits in the following positions to enable: - * 0 : Set to true to use range finder data if available - * 1 : Set to true to use optical flow data if available - * - * @group EKF2 - * @min 0 - * @max 3 - * @bit 0 use range finder - * @bit 1 use optical flow - */ -PARAM_DEFINE_INT32(EKF2_TERR_MASK, 3); - -/** - * Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid. - * - * @group EKF2 - * @group EKF2 - * @min 500000 - * @max 10000000 - * @unit us - */ -PARAM_DEFINE_INT32(EKF2_NOAID_TOUT, 5000000); - -/** - * Measurement noise for range finder fusion - * - * @group EKF2 - * @min 0.01 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_NOISE, 0.1f); - -/** - * Range finder range dependent noise scaler. - * - * Specifies the increase in range finder noise with range. - * - * @group EKF2 - * @min 0.0 - * @max 0.2 - * @unit m/m - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_SFE, 0.05f); - -/** - * Gate size for range finder fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_GATE, 5.0f); - -/** - * Expected range finder reading when on ground. - * - * If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. - * - * @group EKF2 - * @min 0.01 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MIN_RNG, 0.1f); - -/** - * External vision (EV) noise mode - * - * If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. - * If set to 1 the observation noise is set from the parameters directly, - * - * @value 0 EV reported variance (parameter lower bound) - * @value 1 EV noise parameters - * @group EKF2 - */ -PARAM_DEFINE_INT32(EKF2_EV_NOISE_MD, 0); - -/** - * External vision (EV) minimum quality (optional) - * - * External vision will only be started and fused if the quality metric is above this threshold. - * The quality metric is a completely optional field provided by some VIO systems. - * - * @group EKF2 - * @min 0 - * @max 100 - * @decimal 1 - */ -PARAM_DEFINE_INT32(EKF2_EV_QMIN, 0); - -/** - * Measurement noise for vision position observations used to lower bound or replace the uncertainty included in the message - * - * @group EKF2 - * @min 0.01 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_EVP_NOISE, 0.1f); - -/** - * Measurement noise for vision velocity observations used to lower bound or replace the uncertainty included in the message - * - * @group EKF2 - * @min 0.01 - * @unit m/s - * @decimal 2 -*/ -PARAM_DEFINE_FLOAT(EKF2_EVV_NOISE, 0.1f); - -/** - * Measurement noise for vision angle observations used to lower bound or replace the uncertainty included in the message - * - * @group EKF2 - * @min 0.05 - * @unit rad - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_EVA_NOISE, 0.1f); - -/** - * Accelerometer measurement noise for gravity based observations. - * - * @group EKF2 - * @min 0.1 - * @max 10.0 - * @unit g0 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_GRAV_NOISE, 1.0f); - -/** - * Optical flow aiding - * - * Enable optical flow fusion. - * - * @group EKF2 - * @boolean - */ -PARAM_DEFINE_INT32(EKF2_OF_CTRL, 0); - -/** - * Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum - * - * @group EKF2 - * @min 0.05 - * @unit rad/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_N_MIN, 0.15f); - -/** - * Measurement noise for the optical flow sensor. - * - * (when it's reported quality metric is at the minimum set by EKF2_OF_QMIN). - * The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN - * - * @group EKF2 - * @min 0.05 - * @unit rad/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_N_MAX, 0.5f); - -/** - * Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN. - * - * @group EKF2 - * @min 0 - * @max 255 - */ -PARAM_DEFINE_INT32(EKF2_OF_QMIN, 1); - -/** - * Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND. - * - * @group EKF2 - * @min 0 - * @max 255 - */ -PARAM_DEFINE_INT32(EKF2_OF_QMIN_GND, 0); - -/** - * Gate size for optical flow fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_GATE, 3.0f); - -/** - * Terrain altitude process noise - accounts for instability in vehicle height estimate - * - * @group EKF2 - * @min 0.5 - * @unit m/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_TERR_NOISE, 5.0f); - -/** - * Magnitude of terrain gradient - * - * @group EKF2 - * @min 0.0 - * @unit m/m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_TERR_GRAD, 0.5f); - -/** - * X position of IMU in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_IMU_POS_X, 0.0f); - -/** - * Y position of IMU in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_IMU_POS_Y, 0.0f); - -/** - * Z position of IMU in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_IMU_POS_Z, 0.0f); - -/** - * X position of GPS antenna in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_POS_X, 0.0f); - -/** - * Y position of GPS antenna in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_POS_Y, 0.0f); - -/** - * Z position of GPS antenna in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_POS_Z, 0.0f); - -/** - * X position of range finder origin in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_POS_X, 0.0f); - -/** - * Y position of range finder origin in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_POS_Y, 0.0f); - -/** - * Z position of range finder origin in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_POS_Z, 0.0f); - -/** - * X position of optical flow focal point in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_POS_X, 0.0f); - -/** - * Y position of optical flow focal point in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_POS_Y, 0.0f); - -/** - * Z position of optical flow focal point in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_POS_Z, 0.0f); - -/** -* X position of VI sensor focal point in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_POS_X, 0.0f); - -/** - * Y position of VI sensor focal point in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_POS_Y, 0.0f); - -/** - * Z position of VI sensor focal point in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_POS_Z, 0.0f); - -/** -* Airspeed fusion threshold. -* -* Airspeed data is fused for wind estimation if above this threshold. -* Set to 0 to disable airspeed fusion. -* For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. -* Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode). -* -* @group EKF2 -* @min 0.0 -* @unit m/s -* @decimal 1 -*/ -PARAM_DEFINE_FLOAT(EKF2_ARSP_THR, 0.0f); - -/** -* Enable synthetic sideslip fusion. -* -* For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. -* Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode). -* Note: side slip fusion is currently not supported for tailsitters. -* -* @group EKF2 -* @boolean -*/ -PARAM_DEFINE_INT32(EKF2_FUSE_BETA, 0); - -/** - - * Time constant of the velocity output prediction and smoothing filter - * - * @group EKF2 - * @max 1.0 - * @unit s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_TAU_VEL, 0.25f); - -/** - * Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_TAU_POS, 0.25f); - -/** - * 1-sigma IMU gyro switch-on bias - * - * @group EKF2 - * @min 0.0 - * @max 0.2 - * @unit rad/s - * @reboot_required true - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_GBIAS_INIT, 0.1f); - -/** - * 1-sigma IMU accelerometer switch-on bias - * - * @group EKF2 - * @min 0.0 - * @max 0.5 - * @unit m/s^2 - * @reboot_required true - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ABIAS_INIT, 0.2f); - -/** - * 1-sigma tilt angle uncertainty after gravity vector alignment - * - * @group EKF2 - * @min 0.0 - * @max 0.5 - * @unit rad - * @reboot_required true - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_ANGERR_INIT, 0.1f); - -/** - * Range sensor pitch offset. - * - * @group EKF2 - * @min -0.75 - * @max 0.75 - * @unit rad - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_PITCH, 0.0f); - -/** - * Maximum horizontal velocity allowed for conditional range aid mode. - * - * If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements - * to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). - * - * @group EKF2 - * @min 0.1 - * @max 2 - * @unit m/s - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_A_VMAX, 1.0f); - -/** - * Maximum absolute altitude (height above ground level) allowed for conditional range aid mode. - * - * If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements - * to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). - * - * @group EKF2 - * @min 1.0 - * @max 10.0 - * @unit m - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_A_HMAX, 5.0f); - -/** - * Gate size used for innovation consistency checks for range aid fusion - * - * A lower value means HAGL needs to be more stable in order to use range finder for height estimation - * in range aid mode - * - * @group EKF2 - * @unit SD - * @min 0.1 - * @max 5.0 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_A_IGATE, 1.0f); - -/** - * Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s) - * - * - * @group EKF2 - * @unit s - * @min 0.1 - * @max 5 -*/ -PARAM_DEFINE_FLOAT(EKF2_RNG_QLTY_T, 1.0f); - -/** - * Gate size used for range finder kinematic consistency check - * - * To be used, the time derivative of the distance sensor measurements projected on the vertical axis - * needs to be statistically consistent with the estimated vertical velocity of the drone. - * - * Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). - * - * Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate. - * - * @group EKF2 - * @unit SD - * @min 0.1 - * @max 5.0 -*/ -PARAM_DEFINE_FLOAT(EKF2_RNG_K_GATE, 1.0f); - -/** - * Gate size for vision velocity estimate fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 -*/ -PARAM_DEFINE_FLOAT(EKF2_EVV_GATE, 3.0f); - -/** - * Gate size for vision position fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 -*/ -PARAM_DEFINE_FLOAT(EKF2_EVP_GATE, 5.0f); - -/** - * Multirotor wind estimation selection - * - * Activate wind speed estimation using specific-force measurements and - * a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. - * - * Only use on vehicles that have their thrust aligned with the Z axis and - * no thrust in the XY plane. - * - * @group EKF2 - * @boolean - */ -PARAM_DEFINE_INT32(EKF2_DRAG_CTRL, 0); - -/** - * Specific drag force observation noise variance used by the multi-rotor specific drag force model. - * - * Increasing this makes the multi-rotor wind estimates adjust more slowly. - * - * @group EKF2 - * @min 0.5 - * @max 10.0 - * @unit (m/s^2)^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_DRAG_NOISE, 2.5f); - -/** - * X-axis ballistic coefficient used for multi-rotor wind estimation. - * - * This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. - * Set this parameter to zero to turn off the bluff body drag model for this axis. - * - * @group EKF2 - * @min 0.0 - * @max 200.0 - * @unit kg/m^2 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 100.0f); - -/** - * Y-axis ballistic coefficient used for multi-rotor wind estimation. - * - * This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. - * Set this parameter to zero to turn off the bluff body drag model for this axis. - * - * @group EKF2 - * @min 0.0 - * @max 200.0 - * @unit kg/m^2 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BCOEF_Y, 100.0f); - -/** - * Propeller momentum drag coefficient used for multi-rotor wind estimation. - * - * This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. - * Set this parameter to zero to turn off the momentum drag model for both axis. - * - * @group EKF2 - * @min 0 - * @max 1.0 - * @unit 1/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MCOEF, 0.15f); - - -/** - * Upper limit on airspeed along individual axes used to correct baro for position error effects - * - * @group EKF2 - * @min 5.0 - * @max 50.0 - * @unit m/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ASPD_MAX, 20.0f); - -/** - * Static pressure position error coefficient for the positive X axis - * - * This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. - * If the baro height estimate rises during forward flight, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_XP, 0.0f); - -/** - * Static pressure position error coefficient for the negative X axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. - * If the baro height estimate rises during backwards flight, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_XN, 0.0f); - -/** - * Pressure position error coefficient for the positive Y axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. - * If the baro height estimate rises during sideways flight to the right, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_YP, 0.0f); - -/** - * Pressure position error coefficient for the negative Y axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. - * If the baro height estimate rises during sideways flight to the left, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_YN, 0.0f); - -/** - * Static pressure position error coefficient for the Z axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_Z, 0.0f); - -/** - * Accelerometer bias learning limit. - * - * The ekf accel bias states will be limited to within a range equivalent to +- of this value. - * - * @group EKF2 - * @min 0.0 - * @max 0.8 - * @unit m/s^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_LIM, 0.4f); - -/** - * Maximum IMU accel magnitude that allows IMU bias learning. - * - * If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. - * This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates. - * - * @group EKF2 - * @min 20.0 - * @max 200.0 - * @unit m/s^2 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_ACCLIM, 25.0f); - -/** - * Maximum IMU gyro angular rate magnitude that allows IMU bias learning. - * - * If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. - * This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates. - * - * @group EKF2 - * @min 2.0 - * @max 20.0 - * @unit rad/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_GYRLIM, 3.0f); - -/** - * Time constant used by acceleration and angular rate magnitude checks used to inhibit accel bias learning. - * - * The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. - * This parameter controls the time constant of the decay. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_TAU, 0.5f); - -/** - * Gyro bias learning limit. - * - * The ekf gyro bias states will be limited to within a range equivalent to +- of this value. - * - * @group EKF2 - * @min 0.0 - * @max 0.4 - * @unit rad/s - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_GYR_B_LIM, 0.15f); - -/** - * Required GPS health time on startup - * - * Minimum continuous period without GPS failure required to mark a healthy GPS status. - * It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle. - * - * @group EKF2 - * @min 0.1 - * @decimal 1 - * @unit s - * @reboot_required true - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_GPS_H, 10.0f); - -/** - * Magnetic field strength test selection - * - * Bitmask to set which check is used to decide whether the magnetometer data is valid. - * - * If GNSS data is received, the magnetic field is compared to a World - * Magnetic Model (WMM), otherwise an average value is used. - * This check is useful to reject occasional hard iron disturbance. - * - * Set bits to 1 to enable checks. Checks enabled by the following bit positions - * 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR - * 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC - * 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM - * - * @group EKF2 - * @min 0 - * @max 7 - * @bit 0 Strength (EKF2_MAG_CHK_STR) - * @bit 1 Inclination (EKF2_MAG_CHK_INC) - * @bit 2 Wait for WMM - */ -PARAM_DEFINE_INT32(EKF2_MAG_CHECK, 1); - -/** - * Magnetic field strength check tolerance - * - * Maximum allowed deviation from the expected magnetic field strength to pass the check. - * - * @group EKF2 - * @min 0.0 - * @max 1.0 - * @unit gauss - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_CHK_STR, 0.2f); - -/** - * Magnetic field inclination check tolerance - * - * Maximum allowed deviation from the expected magnetic field inclination to pass the check. - * - * @group EKF2 - * @min 0.0 - * @max 90.0 - * @unit deg - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_CHK_INC, 20.f); - -/** - * Enable synthetic magnetometer Z component measurement. - * - * Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. - * For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated - * using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter - * will only have an effect if the global position of the drone is known. - * For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value. - * - * @group EKF2 - * @boolean -*/ -PARAM_DEFINE_INT32(EKF2_SYNT_MAG_Z, 0); - -/** - * Default value of true airspeed used in EKF-GSF AHRS calculation. - * - * If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. - * - * @group EKF2 - * @min 0.0 - * @unit m/s - * @max 100.0 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GSF_TAS, 15.0f); - -/** - * Aux global position (AGP) sensor aiding - * - * Set bits in the following positions to enable: - * 0 : Horizontal position fusion - * 1 : Vertical position fusion - * - * @group EKF2 - * @min 0 - * @max 3 - * @bit 0 Horizontal position - * @bit 1 Vertical position - */ -PARAM_DEFINE_INT32(EKF2_AGP_CTRL, 1); - -/** - * Aux global position estimator delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_AGP_DELAY, 0); - -/** - * Measurement noise for aux global position observations used to lower bound or replace the uncertainty included in the message - * - * @group EKF2 - * @min 0.01 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_AGP_NOISE, 0.9f); - -/** - * Gate size for aux global position fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 -*/ -PARAM_DEFINE_FLOAT(EKF2_AGP_GATE, 3.0f); diff --git a/src/modules/ekf2/ekf2_params_multi.c b/src/modules/ekf2/ekf2_params_multi.c deleted file mode 100644 index cd06198dc161..000000000000 --- a/src/modules/ekf2/ekf2_params_multi.c +++ /dev/null @@ -1,58 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 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. - * - ****************************************************************************/ - -/** - * Multi-EKF IMUs - * - * Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. - * Requires SENS_IMU_MODE 0. - * - * @group EKF2 - * @reboot_required true - * @min 0 - * @max 4 - */ -PARAM_DEFINE_INT32(EKF2_MULTI_IMU, 0); - -/** - * Multi-EKF Magnetometers. - * - * Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. - * Requires SENS_MAG_MODE 0. - * - * @group EKF2 - * @reboot_required true - * @min 0 - * @max 4 - */ -PARAM_DEFINE_INT32(EKF2_MULTI_MAG, 0); diff --git a/src/modules/ekf2/ekf2_params_selector.c b/src/modules/ekf2/ekf2_params_selector.c deleted file mode 100644 index 43a630fe8fb3..000000000000 --- a/src/modules/ekf2/ekf2_params_selector.c +++ /dev/null @@ -1,81 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 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. - * - ****************************************************************************/ - -/** - * Selector error reduce threshold - * - * EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced. - * - * @group EKF2 - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_ERR_RED, 0.2f); - -/** - * Selector angular rate threshold - * - * EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error. - * - * @group EKF2 - * @unit deg/s - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_RAT, 7.0f); - -/** - * Selector angular threshold. - * - * EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty. - * - * @group EKF2 - * @unit deg - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_ANG, 15.0f); - -/** - * Selector acceleration threshold - * - * EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error. - * - * @group EKF2 - * @unit m/s^2 - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_ACC, 1.0f); - -/** - * Selector angular threshold. - * - * EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty. - * - * @group EKF2 - * @unit m/s - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_VEL, 2.0f); diff --git a/src/modules/ekf2/ekf2_params_volatile.c b/src/modules/ekf2/ekf2_params_volatile.c deleted file mode 100644 index 5b947a5cf818..000000000000 --- a/src/modules/ekf2/ekf2_params_volatile.c +++ /dev/null @@ -1,43 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 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. - * - ****************************************************************************/ - -/** - * Magnetic declination - * - * @group EKF2 - * @volatile - * @category system - * @unit deg - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_DECL, 0); diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml new file mode 100644 index 000000000000..030e26779fb4 --- /dev/null +++ b/src/modules/ekf2/module.yaml @@ -0,0 +1,1340 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_EN: + description: + short: EKF2 enable + type: boolean + default: 1 + EKF2_PREDICT_US: + description: + short: EKF prediction period + long: EKF prediction period in microseconds. This should ideally be an integer + multiple of the IMU time delta. Actual filter update will be an integer + multiple of IMU update. + type: int32 + default: 10000 + min: 1000 + max: 20000 + unit: us + EKF2_IMU_CTRL: + description: + short: IMU control + type: bitmask + bit: + 0: Gyro Bias + 1: Accel Bias + 2: Gravity vector fusion + default: 7 + min: 0 + max: 7 + EKF2_MAG_DELAY: + description: + short: Magnetometer measurement delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_BARO_DELAY: + description: + short: Barometer measurement delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_GPS_DELAY: + description: + short: GPS measurement delay relative to IMU measurements + type: float + default: 110 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_OF_DELAY: + description: + short: Optical flow measurement delay relative to IMU measurements + long: Assumes measurement is timestamped at trailing edge of integration period + type: float + default: 20 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_RNG_DELAY: + description: + short: Range finder measurement delay relative to IMU measurements + type: float + default: 5 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_ASP_DELAY: + description: + short: Airspeed measurement delay relative to IMU measurements + type: float + default: 100 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_EV_DELAY: + description: + short: Vision Position Estimator delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_AVEL_DELAY: + description: + short: Auxiliary Velocity Estimate (e.g from a landing target) delay relative + to IMU measurements + type: float + default: 5 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_GPS_CHECK: + description: + short: Integer bitmask controlling GPS checks + long: 'Set bits to 1 to enable checks. Checks enabled by the following bit + positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Maximum + allowed PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position + error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set + by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : + Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check + will only run when the vehicle is on ground and stationary. 6 : Maximum + allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only + run when the vehicle is on ground and stationary. 7 : Maximum allowed horizontal + speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle + is on ground and stationary. 8 : Maximum allowed vertical velocity discrepancy + set by EKF2_REQ_VDRIFT' + type: bitmask + bit: + 0: Min sat count (EKF2_REQ_NSATS) + 1: Max PDOP (EKF2_REQ_PDOP) + 2: Max horizontal position error (EKF2_REQ_EPH) + 3: Max vertical position error (EKF2_REQ_EPV) + 4: Max speed error (EKF2_REQ_SACC) + 5: Max horizontal position rate (EKF2_REQ_HDRIFT) + 6: Max vertical position rate (EKF2_REQ_VDRIFT) + 7: Max horizontal speed (EKF2_REQ_HDRIFT) + 8: Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) + default: 245 + min: 0 + max: 511 + EKF2_REQ_EPH: + description: + short: Required EPH to use GPS + type: float + default: 3.0 + min: 2 + max: 100 + unit: m + decimal: 1 + EKF2_REQ_EPV: + description: + short: Required EPV to use GPS + type: float + default: 5.0 + min: 2 + max: 100 + unit: m + decimal: 1 + EKF2_REQ_SACC: + description: + short: Required speed accuracy to use GPS + type: float + default: 0.5 + min: 0.5 + max: 5.0 + unit: m/s + decimal: 2 + EKF2_REQ_NSATS: + description: + short: Required satellite count to use GPS + type: int32 + default: 6 + min: 4 + max: 12 + EKF2_REQ_PDOP: + description: + short: Maximum PDOP to use GPS + type: float + default: 2.5 + min: 1.5 + max: 5.0 + decimal: 1 + EKF2_REQ_HDRIFT: + description: + short: Maximum horizontal drift speed to use GPS + type: float + default: 0.1 + min: 0.1 + max: 1.0 + unit: m/s + decimal: 2 + EKF2_REQ_VDRIFT: + description: + short: Maximum vertical drift speed to use GPS + type: float + default: 0.2 + min: 0.1 + max: 1.5 + decimal: 2 + unit: m/s + EKF2_GYR_NOISE: + description: + short: Rate gyro noise for covariance prediction + type: float + default: 0.015 + min: 0.0001 + max: 0.1 + unit: rad/s + decimal: 4 + EKF2_ACC_NOISE: + description: + short: Accelerometer noise for covariance prediction + type: float + default: 0.35 + min: 0.01 + max: 1.0 + unit: m/s^2 + decimal: 2 + EKF2_GYR_B_NOISE: + description: + short: Process noise for IMU rate gyro bias prediction + type: float + default: 0.001 + min: 0.0 + max: 0.01 + unit: rad/s^2 + decimal: 6 + EKF2_ACC_B_NOISE: + description: + short: Process noise for IMU accelerometer bias prediction + type: float + default: 0.003 + min: 0.0 + max: 0.01 + unit: m/s^3 + decimal: 6 + EKF2_MAG_B_NOISE: + description: + short: Process noise for body magnetic field prediction + type: float + default: 0.0001 + min: 0.0 + max: 0.1 + unit: gauss/s + decimal: 6 + EKF2_MAG_E_NOISE: + description: + short: Process noise for earth magnetic field prediction + type: float + default: 0.001 + min: 0.0 + max: 0.1 + unit: gauss/s + decimal: 6 + EKF2_WIND_NSD: + description: + short: Process noise spectral density for wind velocity prediction + long: When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases + by this amount every second. + type: float + default: 0.05 + min: 0.0 + max: 1.0 + unit: m/s^2/sqrt(Hz) + decimal: 3 + EKF2_GPS_V_NOISE: + description: + short: Measurement noise for GNSS velocity + type: float + default: 0.3 + min: 0.01 + max: 5.0 + unit: m/s + decimal: 2 + EKF2_GPS_P_NOISE: + description: + short: Measurement noise for GNSS position + type: float + default: 0.5 + min: 0.01 + max: 10.0 + unit: m + decimal: 2 + EKF2_NOAID_NOISE: + description: + short: Measurement noise for non-aiding position hold + type: float + default: 10.0 + min: 0.5 + max: 50.0 + unit: m + decimal: 1 + EKF2_BARO_NOISE: + description: + short: Measurement noise for barometric altitude + type: float + default: 3.5 + min: 0.01 + max: 15.0 + unit: m + decimal: 2 + EKF2_HEAD_NOISE: + description: + short: Measurement noise for magnetic heading fusion + type: float + default: 0.3 + min: 0.01 + max: 1.0 + unit: rad + decimal: 2 + EKF2_MAG_NOISE: + description: + short: Measurement noise for magnetometer 3-axis fusion + type: float + default: 0.05 + min: 0.001 + max: 1.0 + unit: gauss + decimal: 3 + EKF2_EAS_NOISE: + description: + short: Measurement noise for airspeed fusion + type: float + default: 1.4 + min: 0.5 + max: 5.0 + unit: m/s + decimal: 1 + EKF2_BETA_GATE: + description: + short: Gate size for synthetic sideslip fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_BETA_NOISE: + description: + short: Noise for synthetic sideslip fusion + type: float + default: 0.3 + min: 0.1 + max: 1.0 + unit: m/s + decimal: 2 + EKF2_HDG_GATE: + description: + short: Gate size for heading fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 2.6 + min: 1.0 + unit: SD + decimal: 1 + EKF2_MAG_GATE: + description: + short: Gate size for magnetometer XYZ component fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_DECL_TYPE: + description: + short: Integer bitmask controlling handling of magnetic declination + long: 'Set bits in the following positions to enable functions. 0 : Set to + true to use the declination from the geo_lookup library when the GPS position + becomes available, set to false to always use the EKF2_MAG_DECL value. 1 + : Set to true to save the EKF2_MAG_DECL parameter to the value returned + by the EKF when the vehicle disarms.' + type: bitmask + bit: + 0: use geo_lookup declination + 1: save EKF2_MAG_DECL on disarm + default: 3 + min: 0 + max: 3 + reboot_required: true + EKF2_MAG_TYPE: + description: + short: Type of magnetometer fusion + long: Integer controlling the type of magnetometer fusion used - magnetic + heading or 3-component vector. The fusion of magnetometer data as a three + component vector enables vehicle body fixed hard iron errors to be learned, + but requires a stable earth field. If set to 'Automatic' magnetic heading + fusion is used when on-ground and 3-axis magnetic field fusion in-flight + with fallback to magnetic heading fusion if there is insufficient motion + to make yaw or magnetic field states observable. If set to 'Magnetic heading' + magnetic heading fusion is used at all times. If set to 'None' the magnetometer + will not be used under any circumstance. If no external source of yaw is + available, it is possible to use post-takeoff horizontal movement combined + with GPS velocity measurements to align the yaw angle with the timer required + (depending on the amount of movement and GPS data quality). + type: enum + values: + 0: Automatic + 1: Magnetic heading + 5: None + default: 0 + reboot_required: true + EKF2_MAG_ACCLIM: + description: + short: Horizontal acceleration threshold used for heading observability check + long: The heading is assumed to be observable when the body acceleration is + greater than this parameter when a global position/velocity aiding source + is active. + type: float + default: 0.5 + min: 0.0 + max: 5.0 + unit: m/s^2 + decimal: 2 + EKF2_BARO_GATE: + description: + short: Gate size for barometric and GPS height fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_GND_EFF_DZ: + description: + short: Baro deadzone range for height fusion + long: Sets the value of deadzone applied to negative baro innovations. Deadzone + is enabled when EKF2_GND_EFF_DZ > 0. + type: float + default: 4.0 + min: 0.0 + max: 10.0 + unit: m + decimal: 1 + EKF2_GND_MAX_HGT: + description: + short: Height above ground level for ground effect zone + long: Sets the maximum distance to the ground level where negative baro innovations + are expected. + type: float + default: 0.5 + min: 0.0 + max: 5.0 + unit: m + decimal: 1 + EKF2_GPS_P_GATE: + description: + short: Gate size for GNSS position fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_GPS_V_GATE: + description: + short: Gate size for GNSS velocity fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_TAS_GATE: + description: + short: Gate size for TAS fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_HGT_REF: + description: + short: Determines the reference source of height data used by the EKF + long: When multiple height sources are enabled at the same time, the height + estimate will always converge towards the reference height source selected + by this parameter. The range sensor and vision options should only be used + when for operation over a flat surface as the local NED origin will move + up and down with ground level. + type: enum + values: + 0: Barometric pressure + 1: GPS + 2: Range sensor + 3: Vision + default: 1 + reboot_required: true + EKF2_BARO_CTRL: + description: + short: Barometric sensor height aiding + long: If this parameter is enabled then the estimator will make use of the + barometric height measurements to estimate its height in addition to other + height sources (if activated). + type: boolean + default: 1 + EKF2_EV_CTRL: + description: + short: External vision (EV) sensor aiding + long: 'Set bits in the following positions to enable: 0 : Horizontal position + fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw' + type: bitmask + bit: + 0: Horizontal position + 1: Vertical position + 2: 3D velocity + 3: Yaw + default: 15 + min: 0 + max: 15 + EKF2_GPS_CTRL: + description: + short: GNSS sensor aiding + long: 'Set bits in the following positions to enable: 0 : Longitude and latitude + fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading + fusion' + type: bitmask + bit: + 0: Lon/lat + 1: Altitude + 2: 3D velocity + 3: Dual antenna heading + default: 7 + min: 0 + max: 15 + EKF2_RNG_CTRL: + description: + short: Range sensor height aiding + long: 'WARNING: Range finder measurements are less reliable and can experience + unexpected errors. For these reasons, if accurate control of height relative + to ground is required, it is recommended to use the MPC_ALT_MODE parameter + instead, unless baro errors are severe enough to cause problems with landing + and takeoff. To en-/disable range finder for terrain height estimation, + use EKF2_TERR_MASK instead. If this parameter is enabled then the estimator + will make use of the range finder measurements to estimate its height in + addition to other height sources (if activated). Range sensor aiding can + be enabled (i.e.: always use) or set in "conditional" mode. Conditional + mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) + and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, + where baro interference from rotor wash is excessive and can corrupt EKF + state estimates. It is intended to be used where a vertical takeoff and + landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.' + type: enum + values: + 0: Disable range fusion + 1: Enabled (conditional mode) + 2: Enabled + default: 1 + EKF2_TERR_MASK: + description: + short: Integer bitmask controlling fusion sources of the terrain estimator + long: 'Set bits in the following positions to enable: 0 : Set to true to use + range finder data if available 1 : Set to true to use optical flow data + if available' + type: bitmask + bit: + 0: use range finder + 1: use optical flow + default: 3 + min: 0 + max: 3 + EKF2_NOAID_TOUT: + description: + short: Maximum lapsed time from last fusion of measurements that constrain + velocity drift before the EKF will report the horizontal nav solution as + invalid + type: int32 + default: 5000000 + min: 500000 + max: 10000000 + unit: us + EKF2_RNG_NOISE: + description: + short: Measurement noise for range finder fusion + type: float + default: 0.1 + min: 0.01 + unit: m + decimal: 2 + EKF2_RNG_SFE: + description: + short: Range finder range dependent noise scaler + long: Specifies the increase in range finder noise with range. + type: float + default: 0.05 + min: 0.0 + max: 0.2 + unit: m/m + EKF2_RNG_GATE: + description: + short: Gate size for range finder fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_MIN_RNG: + description: + short: Expected range finder reading when on ground + long: If the vehicle is on ground, is not moving as determined by the motion + test and the range finder is returning invalid or no data, then an assumed + range value of EKF2_MIN_RNG will be used by the terrain estimator so that + a terrain height estimate is available at the start of flight in situations + where the range finder may be inside its minimum measurements distance when + on ground. + type: float + default: 0.1 + min: 0.01 + unit: m + decimal: 2 + EKF2_EV_NOISE_MD: + description: + short: External vision (EV) noise mode + long: If set to 0 (default) the measurement noise is taken from the vision + message and the EV noise parameters are used as a lower bound. If set to + 1 the observation noise is set from the parameters directly, + type: enum + values: + 0: EV reported variance (parameter lower bound) + 1: EV noise parameters + default: 0 + EKF2_EV_QMIN: + description: + short: External vision (EV) minimum quality (optional) + long: External vision will only be started and fused if the quality metric + is above this threshold. The quality metric is a completely optional field + provided by some VIO systems. + type: int32 + default: 0 + min: 0 + max: 100 + decimal: 1 + EKF2_EVP_NOISE: + description: + short: Measurement noise for vision position observations used to lower bound + or replace the uncertainty included in the message + type: float + default: 0.1 + min: 0.01 + unit: m + decimal: 2 + EKF2_EVV_NOISE: + description: + short: Measurement noise for vision velocity observations used to lower bound + or replace the uncertainty included in the message + type: float + default: 0.1 + min: 0.01 + unit: m/s + decimal: 2 + EKF2_EVA_NOISE: + description: + short: Measurement noise for vision angle observations used to lower bound + or replace the uncertainty included in the message + type: float + default: 0.1 + min: 0.05 + unit: rad + decimal: 2 + EKF2_GRAV_NOISE: + description: + short: Accelerometer measurement noise for gravity based observations + type: float + default: 1.0 + min: 0.1 + max: 10.0 + unit: g0 + decimal: 2 + EKF2_OF_CTRL: + description: + short: Optical flow aiding + long: Enable optical flow fusion. + type: boolean + default: 0 + EKF2_OF_N_MIN: + description: + short: Measurement noise for the optical flow sensor when it's reported quality + metric is at the maximum + type: float + default: 0.15 + min: 0.05 + unit: rad/s + decimal: 2 + EKF2_OF_N_MAX: + description: + short: Measurement noise for the optical flow sensor + long: '(when it''s reported quality metric is at the minimum set by EKF2_OF_QMIN). + The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN' + type: float + default: 0.5 + min: 0.05 + unit: rad/s + decimal: 2 + EKF2_OF_QMIN: + description: + short: Optical Flow data will only be used in air if the sensor reports a + quality metric >= EKF2_OF_QMIN + type: int32 + default: 1 + min: 0 + max: 255 + EKF2_OF_QMIN_GND: + description: + short: Optical Flow data will only be used on the ground if the sensor reports + a quality metric >= EKF2_OF_QMIN_GND + type: int32 + default: 0 + min: 0 + max: 255 + EKF2_OF_GATE: + description: + short: Gate size for optical flow fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_TERR_NOISE: + description: + short: Terrain altitude process noise - accounts for instability in vehicle + height estimate + type: float + default: 5.0 + min: 0.5 + unit: m/s + decimal: 1 + EKF2_TERR_GRAD: + description: + short: Magnitude of terrain gradient + type: float + default: 0.5 + min: 0.0 + unit: m/m + decimal: 2 + EKF2_IMU_POS_X: + description: + short: X position of IMU in body frame (forward axis with origin relative + to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_IMU_POS_Y: + description: + short: Y position of IMU in body frame (right axis with origin relative to + vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_IMU_POS_Z: + description: + short: Z position of IMU in body frame (down axis with origin relative to + vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_GPS_POS_X: + description: + short: X position of GPS antenna in body frame (forward axis with origin relative + to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_GPS_POS_Y: + description: + short: Y position of GPS antenna in body frame (right axis with origin relative + to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_GPS_POS_Z: + description: + short: Z position of GPS antenna in body frame (down axis with origin relative + to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_RNG_POS_X: + description: + short: X position of range finder origin in body frame (forward axis with + origin relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_RNG_POS_Y: + description: + short: Y position of range finder origin in body frame (right axis with origin + relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_RNG_POS_Z: + description: + short: Z position of range finder origin in body frame (down axis with origin + relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_OF_POS_X: + description: + short: X position of optical flow focal point in body frame (forward axis + with origin relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_OF_POS_Y: + description: + short: Y position of optical flow focal point in body frame (right axis with + origin relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_OF_POS_Z: + description: + short: Z position of optical flow focal point in body frame (down axis with + origin relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_EV_POS_X: + description: + short: X position of VI sensor focal point in body frame (forward axis with + origin relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_EV_POS_Y: + description: + short: Y position of VI sensor focal point in body frame (right axis with + origin relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_EV_POS_Z: + description: + short: Z position of VI sensor focal point in body frame (down axis with origin + relative to vehicle centre of gravity) + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_ARSP_THR: + description: + short: Airspeed fusion threshold + long: Airspeed data is fused for wind estimation if above this threshold. + Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip + (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies + to fixed-wing vehicles (or VTOLs in fixed-wing mode). + type: float + default: 0.0 + min: 0.0 + unit: m/s + decimal: 1 + EKF2_FUSE_BETA: + description: + short: Enable synthetic sideslip fusion + long: 'For reliable wind estimation both sideslip and airspeed fusion (see + EKF2_ARSP_THR) should be enabled. Only applies to fixed-wing vehicles (or + VTOLs in fixed-wing mode). Note: side slip fusion is currently not supported + for tailsitters.' + type: boolean + default: 0 + EKF2_TAU_VEL: + description: + short: Time constant of the velocity output prediction and smoothing filter + type: float + default: 0.25 + max: 1.0 + unit: s + decimal: 2 + EKF2_TAU_POS: + description: + short: Time constant of the position output prediction and smoothing filter. + Controls how tightly the output track the EKF states + type: float + default: 0.25 + min: 0.1 + max: 1.0 + unit: s + decimal: 2 + EKF2_GBIAS_INIT: + description: + short: 1-sigma IMU gyro switch-on bias + type: float + default: 0.1 + min: 0.0 + max: 0.2 + unit: rad/s + reboot_required: true + decimal: 2 + EKF2_ABIAS_INIT: + description: + short: 1-sigma IMU accelerometer switch-on bias + type: float + default: 0.2 + min: 0.0 + max: 0.5 + unit: m/s^2 + reboot_required: true + decimal: 2 + EKF2_ANGERR_INIT: + description: + short: 1-sigma tilt angle uncertainty after gravity vector alignment + type: float + default: 0.1 + min: 0.0 + max: 0.5 + unit: rad + reboot_required: true + decimal: 3 + EKF2_RNG_PITCH: + description: + short: Range sensor pitch offset + type: float + default: 0.0 + min: -0.75 + max: 0.75 + unit: rad + decimal: 3 + EKF2_RNG_A_VMAX: + description: + short: Maximum horizontal velocity allowed for conditional range aid mode + long: If the vehicle horizontal speed exceeds this value then the estimator + will not fuse range measurements to estimate its height. This only applies + when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). + type: float + default: 1.0 + min: 0.1 + max: 2 + unit: m/s + EKF2_RNG_A_HMAX: + description: + short: Maximum absolute altitude (height above ground level) allowed for conditional + range aid mode + long: If the vehicle absolute altitude exceeds this value then the estimator + will not fuse range measurements to estimate its height. This only applies + when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). + type: float + default: 5.0 + min: 1.0 + max: 10.0 + unit: m + EKF2_RNG_A_IGATE: + description: + short: Gate size used for innovation consistency checks for range aid fusion + long: A lower value means HAGL needs to be more stable in order to use range + finder for height estimation in range aid mode + type: float + default: 1.0 + unit: SD + min: 0.1 + max: 5.0 + EKF2_RNG_QLTY_T: + description: + short: Minimum duration during which the reported range finder signal quality + needs to be non-zero in order to be declared valid (s) + type: float + default: 1.0 + unit: s + min: 0.1 + max: 5 + EKF2_RNG_K_GATE: + description: + short: Gate size used for range finder kinematic consistency check + long: 'To be used, the time derivative of the distance sensor measurements + projected on the vertical axis needs to be statistically consistent with + the estimated vertical velocity of the drone. Decrease this value to make + the filter more robust against range finder faulty data (stuck, reflections, + ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) + before tuning this gate.' + type: float + default: 1.0 + unit: SD + min: 0.1 + max: 5.0 + EKF2_EVV_GATE: + description: + short: Gate size for vision velocity estimate fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_EVP_GATE: + description: + short: Gate size for vision position fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_DRAG_CTRL: + description: + short: Multirotor wind estimation selection + long: Activate wind speed estimation using specific-force measurements and + a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles + that have their thrust aligned with the Z axis and no thrust in the XY plane. + type: boolean + default: 0 + EKF2_DRAG_NOISE: + description: + short: Specific drag force observation noise variance used by the multi-rotor + specific drag force model + long: Increasing this makes the multi-rotor wind estimates adjust more slowly. + type: float + default: 2.5 + min: 0.5 + max: 10.0 + unit: (m/s^2)^2 + decimal: 2 + EKF2_BCOEF_X: + description: + short: X-axis ballistic coefficient used for multi-rotor wind estimation + long: This parameter controls the prediction of drag produced by bluff body + drag along the forward/reverse axis when flying a multi-copter which enables + estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The + drag produced by this effect scales with speed squared. The predicted drag + from the rotors is specified separately by the EKF2_MCOEF parameter. Set + this parameter to zero to turn off the bluff body drag model for this axis. + type: float + default: 100.0 + min: 0.0 + max: 200.0 + unit: kg/m^2 + decimal: 1 + EKF2_BCOEF_Y: + description: + short: Y-axis ballistic coefficient used for multi-rotor wind estimation + long: This parameter controls the prediction of drag produced by bluff body + drag along the right/left axis when flying a multi-copter, which enables + estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The + drag produced by this effect scales with speed squared. The predicted drag + from the rotors is specified separately by the EKF2_MCOEF parameter. Set + this parameter to zero to turn off the bluff body drag model for this axis. + type: float + default: 100.0 + min: 0.0 + max: 200.0 + unit: kg/m^2 + decimal: 1 + EKF2_MCOEF: + description: + short: Propeller momentum drag coefficient used for multi-rotor wind estimation + long: This parameter controls the prediction of drag produced by the propellers + when flying a multi-copter, which enables estimation of wind drift when + enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect + scales with speed not speed squared and is produced because some of the + air velocity normal to the propeller axis of rotation is lost when passing + through the rotor disc. This changes the momentum of the flow which creates + a drag reaction force. When comparing un-ducted propellers of the same diameter, + the effect is roughly proportional to the area of the propeller blades when + viewed side on and changes with propeller selection. Momentum drag is significantly + higher for ducted rotors. To account for the drag produced by the body which + scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y + parameters. Set this parameter to zero to turn off the momentum drag model + for both axis. + type: float + default: 0.15 + min: 0 + max: 1.0 + unit: 1/s + decimal: 2 + EKF2_ASPD_MAX: + description: + short: Upper limit on airspeed along individual axes used to correct baro + for position error effects + type: float + default: 20.0 + min: 5.0 + max: 50.0 + unit: m/s + decimal: 1 + EKF2_PCOEF_XP: + description: + short: Static pressure position error coefficient for the positive X axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a positive wind relative velocity along the X body axis. If the baro + height estimate rises during forward flight, then this will be a negative + number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_XN: + description: + short: Static pressure position error coefficient for the negative X axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a negative wind relative velocity along the X body axis. If the baro + height estimate rises during backwards flight, then this will be a negative + number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_YP: + description: + short: Pressure position error coefficient for the positive Y axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a wind relative velocity along the positive Y (RH) body axis. If the + baro height estimate rises during sideways flight to the right, then this + will be a negative number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_YN: + description: + short: Pressure position error coefficient for the negative Y axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a wind relative velocity along the negative Y (LH) body axis. If the + baro height estimate rises during sideways flight to the left, then this + will be a negative number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_Z: + description: + short: Static pressure position error coefficient for the Z axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a wind relative velocity along the Z body axis. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_ABL_LIM: + description: + short: Accelerometer bias learning limit + long: The ekf accel bias states will be limited to within a range equivalent + to +- of this value. + type: float + default: 0.4 + min: 0.0 + max: 0.8 + unit: m/s^2 + decimal: 2 + EKF2_ABL_ACCLIM: + description: + short: Maximum IMU accel magnitude that allows IMU bias learning + long: If the magnitude of the IMU accelerometer vector exceeds this value, + the EKF accel bias state estimation will be inhibited. This reduces the + adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale + factor errors on the accel bias estimates. + type: float + default: 25.0 + min: 20.0 + max: 200.0 + unit: m/s^2 + decimal: 1 + EKF2_ABL_GYRLIM: + description: + short: Maximum IMU gyro angular rate magnitude that allows IMU bias learning + long: If the magnitude of the IMU angular rate vector exceeds this value, + the EKF accel bias state estimation will be inhibited. This reduces the + adverse effect of rapid rotation rates and associated errors on the accel + bias estimates. + type: float + default: 3.0 + min: 2.0 + max: 20.0 + unit: rad/s + decimal: 1 + EKF2_ABL_TAU: + description: + short: Time constant used by acceleration and angular rate magnitude checks + used to inhibit accel bias learning + long: The vector magnitude of angular rate and acceleration used to check + if learning should be inhibited has a peak hold filter applied to it with + an exponential decay. This parameter controls the time constant of the decay. + type: float + default: 0.5 + min: 0.1 + max: 1.0 + unit: s + decimal: 2 + EKF2_GYR_B_LIM: + description: + short: Gyro bias learning limit + long: The ekf gyro bias states will be limited to within a range equivalent + to +- of this value. + type: float + default: 0.15 + min: 0.0 + max: 0.4 + unit: rad/s + decimal: 3 + EKF2_REQ_GPS_H: + description: + short: Required GPS health time on startup + long: Minimum continuous period without GPS failure required to mark a healthy + GPS status. It can be reduced to speed up initialization, but it's recommended + to keep this unchanged for a vehicle. + type: float + default: 10.0 + min: 0.1 + decimal: 1 + unit: s + reboot_required: true + EKF2_MAG_CHECK: + description: + short: Magnetic field strength test selection + long: 'Bitmask to set which check is used to decide whether the magnetometer + data is valid. If GNSS data is received, the magnetic field is compared + to a World Magnetic Model (WMM), otherwise an average value is used. This + check is useful to reject occasional hard iron disturbance. Set bits to + 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic + field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field + inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find + the theoretical strength and inclination using the WMM' + type: bitmask + bit: + 0: Strength (EKF2_MAG_CHK_STR) + 1: Inclination (EKF2_MAG_CHK_INC) + 2: Wait for WMM + default: 1 + min: 0 + max: 7 + EKF2_MAG_CHK_STR: + description: + short: Magnetic field strength check tolerance + long: Maximum allowed deviation from the expected magnetic field strength + to pass the check. + type: float + default: 0.2 + min: 0.0 + max: 1.0 + unit: gauss + decimal: 2 + EKF2_MAG_CHK_INC: + description: + short: Magnetic field inclination check tolerance + long: Maximum allowed deviation from the expected magnetic field inclination + to pass the check. + type: float + default: 20.0 + min: 0.0 + max: 90.0 + unit: deg + decimal: 1 + EKF2_SYNT_MAG_Z: + description: + short: Enable synthetic magnetometer Z component measurement + long: Use for vehicles where the measured body Z magnetic field is subject + to strong magnetic interference. For magnetic heading fusion the magnetometer + Z measurement will be replaced by a synthetic value calculated using the + knowledge of the 3D magnetic field vector at the location of the drone. + Therefore, this parameter will only have an effect if the global position + of the drone is known. For 3D mag fusion the magnetometer Z measurement + will simply be ignored instead of fusing the synthetic value. + type: boolean + default: 0 + EKF2_GSF_TAS: + description: + short: Default value of true airspeed used in EKF-GSF AHRS calculation + long: If no airspeed measurements are available, the EKF-GSF AHRS calculation + will assume this value of true airspeed when compensating for centripetal + acceleration during turns. Set to zero to disable centripetal acceleration + compensation during fixed wing flight modes. + type: float + default: 15.0 + min: 0.0 + unit: m/s + max: 100.0 + decimal: 1 + EKF2_AGP_CTRL: + description: + short: Aux global position (AGP) sensor aiding + long: 'Set bits in the following positions to enable: 0 : Horizontal position + fusion 1 : Vertical position fusion' + type: bitmask + bit: + 0: Horizontal position + 1: Vertical position + default: 1 + min: 0 + max: 3 + EKF2_AGP_DELAY: + description: + short: Aux global position estimator delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_AGP_NOISE: + description: + short: Measurement noise for aux global position observations used to lower + bound or replace the uncertainty included in the message + type: float + default: 0.9 + min: 0.01 + unit: m + decimal: 2 + EKF2_AGP_GATE: + description: + short: Gate size for aux global position fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 diff --git a/src/modules/ekf2/params_multi.yaml b/src/modules/ekf2/params_multi.yaml new file mode 100644 index 000000000000..04280ce1489c --- /dev/null +++ b/src/modules/ekf2/params_multi.yaml @@ -0,0 +1,24 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_MULTI_IMU: + description: + short: Multi-EKF IMUs + long: Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires + SENS_IMU_MODE 0. + type: int32 + default: 0 + reboot_required: true + min: 0 + max: 4 + EKF2_MULTI_MAG: + description: + short: Multi-EKF Magnetometers + long: Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. + Requires SENS_MAG_MODE 0. + type: int32 + default: 0 + reboot_required: true + min: 0 + max: 4 diff --git a/src/modules/ekf2/params_selector.yaml b/src/modules/ekf2/params_selector.yaml new file mode 100644 index 000000000000..d6b00eb3ff2c --- /dev/null +++ b/src/modules/ekf2/params_selector.yaml @@ -0,0 +1,47 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_SEL_ERR_RED: + description: + short: Selector error reduce threshold + long: EKF2 instances have to be better than the selected by at least this + amount before their relative score can be reduced. + type: float + default: 0.2 + EKF2_SEL_IMU_RAT: + description: + short: Selector angular rate threshold + long: EKF2 selector angular rate error threshold for comparing gyros. Angular + rate vector differences larger than this will result in accumulated angular + error. + type: float + default: 7.0 + unit: deg/s + EKF2_SEL_IMU_ANG: + description: + short: Selector angular threshold + long: EKF2 selector maximum accumulated angular error threshold for comparing + gyros. Accumulated angular error larger than this will result in the sensor + being declared faulty. + type: float + default: 15.0 + unit: deg + EKF2_SEL_IMU_ACC: + description: + short: Selector acceleration threshold + long: EKF2 selector acceleration error threshold for comparing accelerometers. + Acceleration vector differences larger than this will result in accumulated + velocity error. + type: float + default: 1.0 + unit: m/s^2 + EKF2_SEL_IMU_VEL: + description: + short: Selector angular threshold + long: EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. + Accumulated velocity error larger than this will result in the sensor being + declared faulty. + type: float + default: 2.0 + unit: m/s diff --git a/src/modules/ekf2/params_volatile.yaml b/src/modules/ekf2/params_volatile.yaml new file mode 100644 index 000000000000..327ca770ae00 --- /dev/null +++ b/src/modules/ekf2/params_volatile.yaml @@ -0,0 +1,13 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_MAG_DECL: + description: + short: Magnetic declination + category: System + type: float + default: 0 + volatile: true + unit: deg + decimal: 1 From 2476883525ba176cfd7ac4947da73a097d7a455d Mon Sep 17 00:00:00 2001 From: Beniamino Pozzan Date: Sun, 14 Apr 2024 17:35:26 +0100 Subject: [PATCH 115/652] logger: add timesync_status to default logged topics Signed-off-by: Beniamino Pozzan --- src/modules/logger/logged_topics.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 022f0b9068e1..731f087f7934 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -145,6 +145,7 @@ void LoggedTopics::add_default_topics() add_optional_topic_multi("rate_ctrl_status", 200, 2); add_optional_topic_multi("sensor_hygrometer", 500, 4); add_optional_topic_multi("rpm", 200); + add_topic_multi("timesync_status", 1000, 3); add_optional_topic_multi("telemetry_status", 1000, 4); // EKF multi topics (currently max 9 estimators) From c64f5128b43e1c296a44bd4f0c8a7c238ac9da62 Mon Sep 17 00:00:00 2001 From: Sergei Grichine Date: Thu, 11 Apr 2024 11:26:31 -0500 Subject: [PATCH 116/652] Update CMakeLists.txt - included lawn world Added lawn world to make process to allow gz sim building like "make px4_sitl gz_r1_rover_lawn" --- src/modules/simulation/gz_bridge/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/simulation/gz_bridge/CMakeLists.txt b/src/modules/simulation/gz_bridge/CMakeLists.txt index ba36f448d35f..003a712282f9 100644 --- a/src/modules/simulation/gz_bridge/CMakeLists.txt +++ b/src/modules/simulation/gz_bridge/CMakeLists.txt @@ -92,6 +92,7 @@ if(gz-transport_FOUND) default windy baylands + lawn ) # find corresponding airframes From b909cc1b5b33fde3251b034e1df6e705cfe54bec Mon Sep 17 00:00:00 2001 From: Sergei Date: Thu, 11 Apr 2024 19:45:20 -0500 Subject: [PATCH 117/652] Updated GZ submodule to the latest hash (d754381) --- Tools/simulation/gz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/simulation/gz b/Tools/simulation/gz index 6b4ed09d1b49..d754381a1cec 160000 --- a/Tools/simulation/gz +++ b/Tools/simulation/gz @@ -1 +1 @@ -Subproject commit 6b4ed09d1b495fbff663f098979cc046df013abd +Subproject commit d754381a1cecdd7f17050acd72bf5bf1327bced6 From ff1da2ba292df0fea9e337454dbaa3caa3cba3d9 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Thu, 11 Apr 2024 13:16:45 -0800 Subject: [PATCH 118/652] remove clip_limit contraint on INT16_MAX --- src/lib/drivers/accelerometer/PX4Accelerometer.cpp | 2 +- src/lib/drivers/gyroscope/PX4Gyroscope.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/drivers/accelerometer/PX4Accelerometer.cpp b/src/lib/drivers/accelerometer/PX4Accelerometer.cpp index 9994745a0216..f09120a14578 100644 --- a/src/lib/drivers/accelerometer/PX4Accelerometer.cpp +++ b/src/lib/drivers/accelerometer/PX4Accelerometer.cpp @@ -179,5 +179,5 @@ void PX4Accelerometer::updateFIFO(sensor_accel_fifo_s &sample) void PX4Accelerometer::UpdateClipLimit() { // 99.9% of potential max - _clip_limit = math::constrain((_range / _scale) * 0.999f, 0.f, (float)INT16_MAX); + _clip_limit = fabsf(_range / _scale * 0.999f); } diff --git a/src/lib/drivers/gyroscope/PX4Gyroscope.cpp b/src/lib/drivers/gyroscope/PX4Gyroscope.cpp index fdce2004a185..687747d4aa92 100644 --- a/src/lib/drivers/gyroscope/PX4Gyroscope.cpp +++ b/src/lib/drivers/gyroscope/PX4Gyroscope.cpp @@ -178,5 +178,5 @@ void PX4Gyroscope::updateFIFO(sensor_gyro_fifo_s &sample) void PX4Gyroscope::UpdateClipLimit() { // 99.9% of potential max - _clip_limit = math::constrain((_range / _scale) * 0.999f, 0.f, (float)INT16_MAX); + _clip_limit = fabsf(_range / _scale * 0.999f); } From 6796945d0b73ec9bed29adbbc1ee3fa385a4c37f Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 17 Apr 2024 11:28:07 +1000 Subject: [PATCH 119/652] Fix up notes boxes for docs (#22999) * Fix up notes boxes for docs * Update markdownout.py * Update markdownout.py * Update markdownout.py --- Tools/msg/generate_msg_docs.py | 2 +- Tools/px4airframes/markdownout.py | 2 +- Tools/px4moduledoc/markdownout.py | 2 +- src/lib/parameters/px4params/markdownout.py | 4 ++-- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Tools/msg/generate_msg_docs.py b/Tools/msg/generate_msg_docs.py index 620646f2fd15..a44a317b5279 100755 --- a/Tools/msg/generate_msg_docs.py +++ b/Tools/msg/generate_msg_docs.py @@ -89,7 +89,7 @@ def get_msgs_list(msgdir): # Write out the index.md file index_text="""# uORB Message Reference -:::note +::: info This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code. ::: diff --git a/Tools/px4airframes/markdownout.py b/Tools/px4airframes/markdownout.py index e6b69ce31ae2..bf1a605723f7 100644 --- a/Tools/px4airframes/markdownout.py +++ b/Tools/px4airframes/markdownout.py @@ -7,7 +7,7 @@ class MarkdownTablesOutput(): def __init__(self, groups, board, image_path): result = """# Airframes Reference -:::note +::: info **This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/px4airframes/markdownout.py) from the source code** using the build command: `make airframe_metadata`. ::: diff --git a/Tools/px4moduledoc/markdownout.py b/Tools/px4moduledoc/markdownout.py index 290618446ebd..469e031a6380 100644 --- a/Tools/px4moduledoc/markdownout.py +++ b/Tools/px4moduledoc/markdownout.py @@ -19,7 +19,7 @@ def __init__(self, module_groups): They describe the provided functionality, high-level implementation overview and how to use the command-line interface. -:::note +::: info **This is auto-generated from the source code** and contains the most recent modules documentation. ::: diff --git a/src/lib/parameters/px4params/markdownout.py b/src/lib/parameters/px4params/markdownout.py index cd4f5e921cc3..f83c504f8059 100644 --- a/src/lib/parameters/px4params/markdownout.py +++ b/src/lib/parameters/px4params/markdownout.py @@ -7,11 +7,11 @@ def __init__(self, groups): result = ( """# Parameter Reference -:::note +::: info This documentation was auto-generated from the source code for this PX4 version (using `make parameters_metadata`). ::: -:::tip +::: tip If a listed parameter is missing from the Firmware see: [Finding/Updating Parameters](../advanced_config/parameters.md#parameter-not-in-firmware). ::: From a8a67fbf8f5f105e08843b5c9b9932fbe006a618 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 5 Apr 2024 13:49:03 +0200 Subject: [PATCH 120/652] ekf2: set horizon using specific parameter Some sensors can have their delay included in the timestamp. In this case, the buffer cannot be sized using the _DELAY parameter. --- src/modules/ekf2/EKF/common.h | 2 +- src/modules/ekf2/EKF/estimator_interface.cpp | 60 +--------- src/modules/ekf2/EKF2.cpp | 117 ++++++++++++------- src/modules/ekf2/EKF2.hpp | 1 + src/modules/ekf2/module.yaml | 12 ++ 5 files changed, 93 insertions(+), 99 deletions(-) diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index aaabe89eaa6e..e760bfbd9d4a 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -265,7 +265,7 @@ struct parameters { int32_t height_sensor_ref{static_cast(HeightSensor::BARO)}; int32_t position_sensor_ref{static_cast(PositionSensor::GNSS)}; - int32_t sensor_interval_max_ms{10}; ///< maximum time of arrival difference between non IMU sensor updates. Sets the size of the observation buffers. (mSec) + float delay_max_ms{110.f}; ///< maximum time delay of all the aiding sensors. Sets the size of the observation buffers. (mSec) // input noise float gyro_noise{1.5e-2f}; ///< IMU angular rate noise used for covariance prediction (rad/sec) diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index 0b384bfb5649..980328f82083 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -516,71 +516,15 @@ void EstimatorInterface::setDragData(const imuSample &imu) bool EstimatorInterface::initialise_interface(uint64_t timestamp) { - // find the maximum time delay the buffers are required to handle - - // it's reasonable to assume that aux velocity device has low delay. TODO: check the delay only if the aux device is used - float max_time_delay_ms = _params.sensor_interval_max_ms; - - // aux vel -#if defined(CONFIG_EKF2_AUXVEL) - max_time_delay_ms = math::max(_params.auxvel_delay_ms, max_time_delay_ms); -#endif // CONFIG_EKF2_AUXVEL - -#if defined(CONFIG_EKF2_BAROMETER) - // using baro - if (_params.baro_ctrl > 0) { - max_time_delay_ms = math::max(_params.baro_delay_ms, max_time_delay_ms); - } -#endif // CONFIG_EKF2_BAROMETER - -#if defined(CONFIG_EKF2_AIRSPEED) - // using airspeed - if (_params.arsp_thr > FLT_EPSILON) { - max_time_delay_ms = math::max(_params.airspeed_delay_ms, max_time_delay_ms); - } -#endif // CONFIG_EKF2_AIRSPEED - -#if defined(CONFIG_EKF2_MAGNETOMETER) - // mag mode - if (_params.mag_fusion_type != MagFuseType::NONE) { - max_time_delay_ms = math::max(_params.mag_delay_ms, max_time_delay_ms); - } -#endif // CONFIG_EKF2_MAGNETOMETER - -#if defined(CONFIG_EKF2_RANGE_FINDER) - // using range finder - if ((_params.rng_ctrl != static_cast(RngCtrl::DISABLED))) { - max_time_delay_ms = math::max(_params.range_delay_ms, max_time_delay_ms); - } -#endif // CONFIG_EKF2_RANGE_FINDER - -#if defined(CONFIG_EKF2_GNSS) - if (_params.gnss_ctrl > 0) { - max_time_delay_ms = math::max(_params.gps_delay_ms, max_time_delay_ms); - } -#endif // CONFIG_EKF2_GNSS - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - if (_params.flow_ctrl > 0) { - max_time_delay_ms = math::max(_params.flow_delay_ms, max_time_delay_ms); - } -#endif // CONFIG_EKF2_OPTICAL_FLOW - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - if (_params.ev_ctrl > 0) { - max_time_delay_ms = math::max(_params.ev_delay_ms, max_time_delay_ms); - } -#endif // CONFIG_EKF2_EXTERNAL_VISION - const float filter_update_period_ms = _params.filter_update_interval_us / 1000.f; // calculate the IMU buffer length required to accomodate the maximum delay with some allowance for jitter - _imu_buffer_length = math::max(2, (int)ceilf(max_time_delay_ms / filter_update_period_ms)); + _imu_buffer_length = math::max(2, (int)ceilf(_params.delay_max_ms / filter_update_period_ms)); // set the observation buffer length to handle the minimum time of arrival between observations in combination // with the worst case delay from current time to ekf fusion time // allow for worst case 50% extension of the ekf fusion time horizon delay due to timing jitter - const float ekf_delay_ms = max_time_delay_ms * 1.5f; + const float ekf_delay_ms = _params.delay_max_ms * 1.5f; _obs_buffer_length = roundf(ekf_delay_ms / filter_update_period_ms); // limit to be no longer than the IMU buffer (we can't process data faster than the EKF prediction rate) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index e98ddd9a0bc0..f531d99ce7ae 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -64,6 +64,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): #endif // CONFIG_EKF2_WIND _params(_ekf.getParamHandle()), _param_ekf2_predict_us(_params->filter_update_interval_us), + _param_ekf2_delay_max(_params->delay_max_ms), _param_ekf2_imu_ctrl(_params->imu_ctrl), #if defined(CONFIG_EKF2_AUXVEL) _param_ekf2_avel_delay(_params->auxvel_delay_ms), @@ -437,46 +438,6 @@ void EKF2::Run() #endif // CONFIG_EKF2_AIRSPEED -#if defined(CONFIG_EKF2_BAROMETER) - - // if using baro ensure sensor interval minimum is sufficient to accommodate system averaged baro output - if (_params->baro_ctrl == 1) { - float sens_baro_rate = 0.f; - - if (param_get(param_find("SENS_BARO_RATE"), &sens_baro_rate) == PX4_OK) { - if (sens_baro_rate > 0) { - float interval_ms = roundf(1000.f / sens_baro_rate); - - if (PX4_ISFINITE(interval_ms) && (interval_ms > _params->sensor_interval_max_ms)) { - PX4_DEBUG("updating sensor_interval_max_ms %.3f -> %.3f", (double)_params->sensor_interval_max_ms, (double)interval_ms); - _params->sensor_interval_max_ms = interval_ms; - } - } - } - } - -#endif // CONFIG_EKF2_BAROMETER - -#if defined(CONFIG_EKF2_MAGNETOMETER) - - // if using mag ensure sensor interval minimum is sufficient to accommodate system averaged mag output - if (_params->mag_fusion_type != MagFuseType::NONE) { - float sens_mag_rate = 0.f; - - if (param_get(param_find("SENS_MAG_RATE"), &sens_mag_rate) == PX4_OK) { - if (sens_mag_rate > 0) { - float interval_ms = roundf(1000.f / sens_mag_rate); - - if (PX4_ISFINITE(interval_ms) && (interval_ms > _params->sensor_interval_max_ms)) { - PX4_DEBUG("updating sensor_interval_max_ms %.3f -> %.3f", (double)_params->sensor_interval_max_ms, (double)interval_ms); - _params->sensor_interval_max_ms = interval_ms; - } - } - } - } - -#endif // CONFIG_EKF2_MAGNETOMETER - _ekf.updateParameters(); } @@ -822,6 +783,82 @@ void EKF2::VerifyParams() } #endif // CONFIG_EKF2_MAGNETOMETER + + float delay_max = _param_ekf2_delay_max.get(); + +#if defined(CONFIG_EKF2_AUXVEL) + + if (_param_ekf2_avel_delay.get() > delay_max) { + delay_max = _param_ekf2_avel_delay.get(); + } + +#endif // CONFIG_EKF2_AUXVEL + +#if defined(CONFIG_EKF2_BAROMETER) + + if (_param_ekf2_baro_delay.get() > delay_max) { + delay_max = _param_ekf2_baro_delay.get(); + } + +#endif // CONFIG_EKF2_BAROMETER + +#if defined(CONFIG_EKF2_AIRSPEED) + + if (_param_ekf2_asp_delay.get() > delay_max) { + delay_max = _param_ekf2_asp_delay.get(); + } + +#endif // CONFIG_EKF2_AIRSPEED + +#if defined(CONFIG_EKF2_MAGNETOMETER) + + if (_param_ekf2_mag_delay.get() > delay_max) { + delay_max = _param_ekf2_mag_delay.get(); + } + +#endif // CONFIG_EKF2_MAGNETOMETER + +#if defined(CONFIG_EKF2_RANGE_FINDER) + + if (_param_ekf2_rng_delay.get() > delay_max) { + delay_max = _param_ekf2_rng_delay.get(); + } + +#endif // CONFIG_EKF2_RANGE_FINDER + +#if defined(CONFIG_EKF2_GNSS) + + if (_param_ekf2_gps_delay.get() > delay_max) { + delay_max = _param_ekf2_gps_delay.get(); + } + +#endif // CONFIG_EKF2_GNSS + +#if defined(CONFIG_EKF2_OPTICAL_FLOW) + + if (_param_ekf2_of_delay.get() > delay_max) { + delay_max = _param_ekf2_of_delay.get(); + } + +#endif // CONFIG_EKF2_OPTICAL_FLOW + +#if defined(CONFIG_EKF2_EXTERNAL_VISION) + + if (_param_ekf2_ev_delay.get() > delay_max) { + delay_max = _param_ekf2_ev_delay.get(); + } + +#endif // CONFIG_EKF2_EXTERNAL_VISION + + if (delay_max > _param_ekf2_delay_max.get()) { + /* EVENT + * @description EKF2_DELAY_MAX({1}ms) is too small compared to the maximum sensor delay ({2}) + */ + events::send(events::ID("nf_delay_max_too_small"), events::Log::Warning, + "EKF2_DELAY_MAX increased to {2}ms, please reboot", _param_ekf2_delay_max.get(), + delay_max); + _param_ekf2_delay_max.commit_no_notification(delay_max); + } } void EKF2::PublishAidSourceStatus(const hrt_abstime ×tamp) diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index ff425e891d03..28c76dd13046 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -498,6 +498,7 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem DEFINE_PARAMETERS( (ParamExtInt) _param_ekf2_predict_us, + (ParamExtFloat) _param_ekf2_delay_max, (ParamExtInt) _param_ekf2_imu_ctrl, #if defined(CONFIG_EKF2_AUXVEL) diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 030e26779fb4..81c067a36d12 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -29,6 +29,18 @@ parameters: default: 7 min: 0 max: 7 + EKF2_DELAY_MAX: + description: + short: Maximum delay of all the aiding sensors + long: Defines the delay between the current time and the delayed-time horizon. + This value should be at least as large as the largest EKF2_XXX_DELAY parameter. + type: float + default: 200 + min: 0 + max: 1000 + unit: ms + reboot_required: true + decimal: 1 EKF2_MAG_DELAY: description: short: Magnetometer measurement delay relative to IMU measurements From 2dccd6cacb51f3bf23e2d90b2d9c411de7b405de Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Wed, 17 Apr 2024 12:09:35 -0700 Subject: [PATCH 121/652] Voxl ESC driver update (#23022) * Made Serial API open the UART in NON BLOCKING mode * Updated voxl_esc driver to latest from ModalAI fork * Ported voxl_esc driver over to new Serial UART API * Removed voxl_esc serial abstraction since new Serial API is already a serial abstraction --- .../include/px4_platform_common/Serial.hpp | 1 + platforms/nuttx/src/px4/common/SerialImpl.cpp | 2 +- .../src/px4/common/include/SerialImpl.hpp | 1 + platforms/posix/include/SerialImpl.hpp | 1 + platforms/posix/src/px4/common/SerialImpl.cpp | 2 +- platforms/qurt/src/px4/SerialImpl.cpp | 2 +- src/drivers/actuators/voxl_esc/CMakeLists.txt | 2 - src/drivers/actuators/voxl_esc/voxl_esc.cpp | 396 +++++++++++++----- src/drivers/actuators/voxl_esc/voxl_esc.hpp | 52 ++- .../actuators/voxl_esc/voxl_esc_params.c | 33 +- .../actuators/voxl_esc/voxl_esc_serial.cpp | 191 --------- .../actuators/voxl_esc/voxl_esc_serial.hpp | 69 --- 12 files changed, 352 insertions(+), 400 deletions(-) delete mode 100644 src/drivers/actuators/voxl_esc/voxl_esc_serial.cpp delete mode 100644 src/drivers/actuators/voxl_esc/voxl_esc_serial.hpp diff --git a/platforms/common/include/px4_platform_common/Serial.hpp b/platforms/common/include/px4_platform_common/Serial.hpp index 3a9b8b06663d..8b2f5e8f1a06 100644 --- a/platforms/common/include/px4_platform_common/Serial.hpp +++ b/platforms/common/include/px4_platform_common/Serial.hpp @@ -55,6 +55,7 @@ class Serial virtual ~Serial(); // Open sets up the port and gets it configured based on desired configuration + // The port is always opened in NON BLOCKING mode. bool open(); bool isOpen() const; diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index 1094c78cc2e9..dd1ce6a3b8b8 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -181,7 +181,7 @@ bool SerialImpl::open() } // Open the serial port - int serial_fd = ::open(_port, O_RDWR | O_NOCTTY); + int serial_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK); if (serial_fd < 0) { PX4_ERR("failed to open %s err: %d", _port, errno); diff --git a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp index 1253dfecef71..543041bc978f 100644 --- a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp +++ b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp @@ -114,6 +114,7 @@ class SerialImpl bool _single_wire_mode{false}; bool _swap_rx_tx_mode{false}; bool _inverted_mode{false}; + }; } // namespace device diff --git a/platforms/posix/include/SerialImpl.hpp b/platforms/posix/include/SerialImpl.hpp index 1253dfecef71..543041bc978f 100644 --- a/platforms/posix/include/SerialImpl.hpp +++ b/platforms/posix/include/SerialImpl.hpp @@ -114,6 +114,7 @@ class SerialImpl bool _single_wire_mode{false}; bool _swap_rx_tx_mode{false}; bool _inverted_mode{false}; + }; } // namespace device diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 248e414cc72f..03a5a6543739 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -179,7 +179,7 @@ bool SerialImpl::open() } // Open the serial port - int serial_fd = ::open(_port, O_RDWR | O_NOCTTY); + int serial_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK); if (serial_fd < 0) { PX4_ERR("failed to open %s err: %d", _port, errno); diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp index 1d0c20f00025..294cf34daba0 100644 --- a/platforms/qurt/src/px4/SerialImpl.cpp +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -163,7 +163,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) return -1; } - int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 500); + int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 100); if (ret_read < 0) { PX4_DEBUG("%s read error %d", _port, ret_read); diff --git a/src/drivers/actuators/voxl_esc/CMakeLists.txt b/src/drivers/actuators/voxl_esc/CMakeLists.txt index d588dc29a69d..dbfa0c42c384 100644 --- a/src/drivers/actuators/voxl_esc/CMakeLists.txt +++ b/src/drivers/actuators/voxl_esc/CMakeLists.txt @@ -38,8 +38,6 @@ px4_add_module( crc16.c crc16.h - voxl_esc_serial.cpp - voxl_esc_serial.hpp voxl_esc.cpp voxl_esc.hpp qc_esc_packet_types.h diff --git a/src/drivers/actuators/voxl_esc/voxl_esc.cpp b/src/drivers/actuators/voxl_esc/voxl_esc.cpp index 88d070a7cf6c..f5568d7eebc7 100644 --- a/src/drivers/actuators/voxl_esc/voxl_esc.cpp +++ b/src/drivers/actuators/voxl_esc/voxl_esc.cpp @@ -36,7 +36,6 @@ #include #include "voxl_esc.hpp" -#include "voxl_esc_serial.hpp" // future use: #define MODALAI_PUBLISH_ESC_STATUS 0 @@ -83,10 +82,7 @@ VoxlEsc::~VoxlEsc() { _outputs_on = false; - if (_uart_port) { - _uart_port->uart_close(); - _uart_port = nullptr; - } + _uart_port.close(); perf_free(_cycle_perf); perf_free(_output_update_perf); @@ -94,26 +90,181 @@ VoxlEsc::~VoxlEsc() int VoxlEsc::init() { + PX4_INFO("VOXL_ESC: Starting VOXL ESC driver"); /* Getting initial parameter values */ int ret = update_params(); if (ret != OK) { + PX4_ERR("VOXL_ESC: Failed to update params during init"); return ret; } - _uart_port = new VoxlEscSerial(); + print_params(); + + //WARING: uart port initialization and device detection does not happen here + //because init() is called from a different thread from Run(), so fd opened in init() cannot be used in Run() + //this is an issue (feature?) specific to nuttx where each thread group gets separate set of fds + //https://cwiki.apache.org/confluence/display/NUTTX/Detaching+File+Descriptors + //detaching file descriptors is not implemented in the current version of nuttx that px4 uses + // + //There is no problem when running on VOXL2, but in order to have the same logical flow on both systems, + //we will initialize uart and query the device in Run() + + ScheduleNow(); + + return 0; +} + +int VoxlEsc::device_init() +{ + if (_device_initialized) { + return 0; + } + + // Open serial port + if (!_uart_port.isOpen()) { + PX4_INFO("VOXL_ESC: Opening UART ESC device %s, baud rate %" PRIi32, _device, _parameters.baud_rate); +#ifndef __PX4_QURT + + //warn user that unless DMA is enabled for UART RX, data can be lost due to high frequency of per char cpu interrupts + //at least at 2mbit, there are definitely losses, did not test other baud rates to find the cut off + if (_parameters.baud_rate > 250000) { + PX4_WARN("VOXL_ESC: Baud rate is too high for non-DMA based UART, this can lead to loss of RX data"); + } + +#endif + + // Configure UART port + if (! _uart_port.setPort(_device)) { + PX4_ERR("Error configuring serial device on port %s", _device); + return -1; + } + + if (! _uart_port.setBaudrate(_parameters.baud_rate)) { + PX4_ERR("Error setting baudrate to %d on %s", (int) _parameters.baud_rate, _device); + return -1; + } + + // Open the UART. If this is successful then the UART is ready to use. + if (! _uart_port.open()) { + PX4_ERR("Error opening serial device %s", _device); + return -1; + } + } + + // Reset output channel values memset(&_esc_chans, 0x00, sizeof(_esc_chans)); + //reset the ESC version info before requesting for (int esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; ++esc_id) { - _version_info[esc_id].sw_version = UINT16_MAX; - _version_info[esc_id].hw_version = UINT16_MAX; - _version_info[esc_id].id = esc_id; + memset(&(_version_info[esc_id]), 0, sizeof(_version_info[esc_id])); + //_version_info[esc_id].sw_version = 0; //invalid + //_version_info[esc_id].hw_version = 0; //invalid + _version_info[esc_id].id = esc_id; } - //get_instance()->ScheduleOnInterval(10000); //100hz + // Detect ESCs + PX4_INFO("VOXL_ESC: Detecting ESCs..."); + qc_esc_packet_init(&_fb_packet); + + //request extended version info from each ESC and wait for reply + for (uint8_t esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; esc_id++) { + Command cmd; + cmd.len = qc_esc_create_extended_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf)); - ScheduleNow(); + if (_uart_port.write(cmd.buf, cmd.len) != cmd.len) { + PX4_ERR("VOXL_ESC: Could not write version request packet to UART port"); + return -1; + } + + hrt_abstime t_request = hrt_absolute_time(); + hrt_abstime t_timeout = 50000; //50ms timeout for version info response + bool got_response = false; + + while ((!got_response) && (hrt_elapsed_time(&t_request) < t_timeout)) { + px4_usleep(100); //sleep a bit while waiting for ESC to respond + + int nread = _uart_port.read(_read_buf, sizeof(_read_buf)); + + for (int i = 0; i < nread; i++) { + int16_t parse_ret = qc_esc_packet_process_char(_read_buf[i], &_fb_packet); + + if (parse_ret > 0) { + hrt_abstime response_time = hrt_elapsed_time(&t_request); + //PX4_INFO("got packet of length %i",ret); + _rx_packet_count++; + uint8_t packet_type = qc_esc_packet_get_type(&_fb_packet); + uint8_t packet_size = qc_esc_packet_get_size(&_fb_packet); + + if (packet_type == ESC_PACKET_TYPE_VERSION_EXT_RESPONSE && packet_size == sizeof(QC_ESC_EXTENDED_VERSION_INFO)) { + QC_ESC_EXTENDED_VERSION_INFO ver; + memcpy(&ver, _fb_packet.buffer, packet_size); + + PX4_INFO("VOXL_ESC: \tESC ID : %i", ver.id); + PX4_INFO("VOXL_ESC: \tBoard Type : %i: %s", ver.hw_version, board_id_to_name(ver.hw_version)); + + uint8_t *u = &ver.unique_id[0]; + PX4_INFO("VOXL_ESC: \tUnique ID : 0x%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X", + u[11], u[10], u[9], u[8], u[7], u[6], u[5], u[4], u[3], u[2], u[1], u[0]); + + PX4_INFO("VOXL_ESC: \tFirmware : version %4d, hash %.12s", ver.sw_version, ver.firmware_git_version); + PX4_INFO("VOXL_ESC: \tBootloader : version %4d, hash %.12s", ver.bootloader_version, ver.bootloader_git_version); + PX4_INFO("VOXL_ESC: \tReply time : %" PRIu32 "us", (uint32_t)response_time); + PX4_INFO("VOXL_ESC:"); + + if (ver.id == esc_id) { + memcpy(&_version_info[esc_id], &ver, sizeof(ver)); + got_response = true; + } + } + } + } + } + + if (!got_response) { + PX4_ERR("VOXL_ESC: ESC %d version info response timeout", esc_id); + } + } + + //check the SW version of the ESCs + bool esc_detection_fault = false; + + for (int esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; esc_id++) { + if (_version_info[esc_id].sw_version == 0) { + PX4_ERR("VOXL_ESC: ESC ID %d was not detected", esc_id); + esc_detection_fault = true; + } + } + + //check the firmware hashes to make sure they are the same. Firmware hash has 8 chars plus optional "*" + for (int esc_id = 1; esc_id < VOXL_ESC_OUTPUT_CHANNELS; esc_id++) { + if (strncmp(_version_info[0].firmware_git_version, _version_info[esc_id].firmware_git_version, 9) != 0) { + PX4_ERR("VOXL_ESC: ESC %d Firmware hash does not match ESC 0 firmware hash: (%.12s) != (%.12s)", + esc_id, _version_info[esc_id].firmware_git_version, _version_info[0].firmware_git_version); + esc_detection_fault = true; + } + } + + //if firmware version is equal or greater than VOXL_ESC_EXT_RPM, ESC packet with extended rpm range is supported. use it + _extended_rpm = true; + + for (int esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; esc_id++) { + if (_version_info[esc_id].sw_version < VOXL_ESC_EXT_RPM) { + _extended_rpm = false; + } + } + + if (esc_detection_fault) { + PX4_ERR("VOXL_ESC: Critical error during ESC initialization"); + return -1; + } + + PX4_INFO("VOXL_ESC: Use extened rpm packet : %d", _extended_rpm); + + PX4_INFO("VOXL_ESC: All ESCs successfully detected"); + + _device_initialized = true; return 0; } @@ -155,45 +306,48 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map) param_get(param_find("VOXL_ESC_VLOG"), ¶ms->verbose_logging); param_get(param_find("VOXL_ESC_PUB_BST"), ¶ms->publish_battery_status); + param_get(param_find("VOXL_ESC_T_WARN"), ¶ms->esc_warn_temp_threshold); + param_get(param_find("VOXL_ESC_T_OVER"), ¶ms->esc_over_temp_threshold); + if (params->rpm_min >= params->rpm_max) { - PX4_ERR("Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters."); params->rpm_min = 0; ret = PX4_ERROR; } if (params->turtle_motor_percent < 0 || params->turtle_motor_percent > 100) { - PX4_ERR("Invalid parameter VOXL_ESC_T_PERC. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_PERC. Please verify parameters."); params->turtle_motor_percent = 0; ret = PX4_ERROR; } if (params->turtle_motor_deadband < 0 || params->turtle_motor_deadband > 100) { - PX4_ERR("Invalid parameter VOXL_ESC_T_DEAD. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_DEAD. Please verify parameters."); params->turtle_motor_deadband = 0; ret = PX4_ERROR; } if (params->turtle_motor_expo < 0 || params->turtle_motor_expo > 100) { - PX4_ERR("Invalid parameter VOXL_ESC_T_EXPO. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_EXPO. Please verify parameters."); params->turtle_motor_expo = 0; ret = PX4_ERROR; } if (params->turtle_stick_minf < 0.0f || params->turtle_stick_minf > 100.0f) { - PX4_ERR("Invalid parameter VOXL_ESC_T_MINF. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_MINF. Please verify parameters."); params->turtle_stick_minf = 0.0f; ret = PX4_ERROR; } if (params->turtle_cosphi < 0.0f || params->turtle_cosphi > 100.0f) { - PX4_ERR("Invalid parameter VOXL_ESC_T_COSP. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_COSP. Please verify parameters."); params->turtle_cosphi = 0.0f; ret = PX4_ERROR; } for (int i = 0; i < VOXL_ESC_OUTPUT_CHANNELS; i++) { if (params->function_map[i] < (int)OutputFunction::Motor1 || params->function_map[i] > (int)OutputFunction::Motor4) { - PX4_ERR("Invalid parameter VOXL_ESC_FUNCX. Only supports motors 1-4. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_FUNCX. Only supports motors 1-4. Please verify parameters."); params->function_map[i] = 0; ret = PX4_ERROR; @@ -211,7 +365,7 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map) if (params->motor_map[i] == VOXL_ESC_OUTPUT_DISABLED || params->motor_map[i] < -(VOXL_ESC_OUTPUT_CHANNELS) || params->motor_map[i] > VOXL_ESC_OUTPUT_CHANNELS) { - PX4_ERR("Invalid parameter VOXL_ESC_MOTORX. Please verify parameters."); + PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_MOTORX. Please verify parameters."); params->motor_map[i] = 0; ret = PX4_ERROR; } @@ -264,35 +418,11 @@ int VoxlEsc::task_spawn(int argc, char *argv[]) return PX4_ERROR; } -int VoxlEsc::flush_uart_rx() -{ - while (_uart_port->uart_read(_read_buf, sizeof(_read_buf)) > 0) {} - - return 0; -} - -bool VoxlEsc::check_versions_updated() -{ - for (int esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; ++esc_id) { - if (_version_info[esc_id].sw_version == UINT16_MAX) { return false; } - } - - // PX4_INFO("Got all ESC Version info!"); - _extended_rpm = true; - _need_version_info = false; - - for (int esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; ++esc_id) { - if (_version_info[esc_id].sw_version < VOXL_ESC_EXT_RPM) { _extended_rpm = false; } - } - - return true; -} - int VoxlEsc::read_response(Command *out_cmd) { px4_usleep(_current_cmd.resp_delay_us); - int res = _uart_port->uart_read(_read_buf, sizeof(_read_buf)); + int res = _uart_port.read(_read_buf, sizeof(_read_buf)); if (res > 0) { //PX4_INFO("read %i bytes",res); @@ -341,7 +471,8 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback) uint32_t voltage = fb.voltage; int32_t current = fb.current * 8; int32_t temperature = fb.temperature / 100; - PX4_INFO("[%" PRId64 "] ID_RAW=%d ID=%d, RPM=%5d, PWR=%3d%%, V=%5dmV, I=%+5dmA, T=%+3dC", tnow, (int)id, motor_idx + 1, + PX4_INFO("VOXL_ESC: [%" PRId64 "] ID_RAW=%d ID=%d, RPM=%5d, PWR=%3d%%, V=%5dmV, I=%+5dmA, T=%+3dC", tnow, (int)id, + motor_idx + 1, (int)rpm, (int)power, (int)voltage, (int)current, (int)temperature); } @@ -382,6 +513,19 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback) _esc_status.timestamp = _esc_status.esc[id].timestamp; _esc_status.counter++; + + if ((_parameters.esc_over_temp_threshold > 0) + && (_esc_status.esc[id].esc_temperature > _parameters.esc_over_temp_threshold)) { + _esc_status.esc[id].failures |= 1 << (esc_report_s::FAILURE_OVER_ESC_TEMPERATURE); + } + + //TODO: do we also issue a warning if over-temperature threshold is exceeded? + if ((_parameters.esc_warn_temp_threshold > 0) + && (_esc_status.esc[id].esc_temperature > _parameters.esc_warn_temp_threshold)) { + _esc_status.esc[id].failures |= 1 << (esc_report_s::FAILURE_WARN_ESC_TEMPERATURE); + } + + //print ESC status just for debugging /* PX4_INFO("[%lld] ID=%d, ADDR %d, STATE=%d, RPM=%5d, PWR=%3d%%, V=%.2fdV, I=%.2fA, T=%+3dC, CNT %d, FAIL %d", @@ -397,30 +541,24 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback) QC_ESC_VERSION_INFO ver; memcpy(&ver, _fb_packet.buffer, packet_size); - if (_need_version_info) { - memcpy(&_version_info[ver.id], &ver, sizeof(QC_ESC_VERSION_INFO)); - check_versions_updated(); - break; - } - - PX4_INFO("ESC ID: %i", ver.id); - PX4_INFO("HW Version: %i", ver.hw_version); - PX4_INFO("SW Version: %i", ver.sw_version); - PX4_INFO("Unique ID: %i", (int)ver.unique_id); + PX4_INFO("VOXL_ESC: ESC ID: %i", ver.id); + PX4_INFO("VOXL_ESC: HW Version: %i", ver.hw_version); + PX4_INFO("VOXL_ESC: SW Version: %i", ver.sw_version); + PX4_INFO("VOXL_ESC: Unique ID: %i", (int)ver.unique_id); } else if (packet_type == ESC_PACKET_TYPE_VERSION_EXT_RESPONSE && packet_size == sizeof(QC_ESC_EXTENDED_VERSION_INFO)) { QC_ESC_EXTENDED_VERSION_INFO ver; memcpy(&ver, _fb_packet.buffer, packet_size); - PX4_INFO("\tESC ID : %i", ver.id); - PX4_INFO("\tBoard : %i", ver.hw_version); - PX4_INFO("\tSW Version : %i", ver.sw_version); + PX4_INFO("VOXL_ESC: \tESC ID : %i", ver.id); + PX4_INFO("VOXL_ESC: \tBoard : %i", ver.hw_version); + PX4_INFO("VOXL_ESC: \tSW Version : %i", ver.sw_version); uint8_t *u = &ver.unique_id[0]; - PX4_INFO("\tUnique ID : 0x%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X", + PX4_INFO("VOXL_ESC: \tUnique ID : 0x%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X", u[11], u[10], u[9], u[8], u[7], u[6], u[5], u[4], u[3], u[2], u[1], u[0]); - PX4_INFO("\tFirmware : version %4d, hash %.12s", ver.sw_version, ver.firmware_git_version); - PX4_INFO("\tBootloader : version %4d, hash %.12s", ver.bootloader_version, ver.bootloader_git_version); + PX4_INFO("VOXL_ESC: \tFirmware : version %4d, hash %.12s", ver.sw_version, ver.firmware_git_version); + PX4_INFO("VOXL_ESC: \tBootloader : version %4d, hash %.12s", ver.bootloader_version, ver.bootloader_git_version); } else if (packet_type == ESC_PACKET_TYPE_FB_POWER_STATUS && packet_size == sizeof(QC_ESC_FB_POWER_STATUS)) { QC_ESC_FB_POWER_STATUS packet; @@ -525,7 +663,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) const char *verb = argv[argc - 1]; - /* start the FMU if not running */ + /* start the driver if not running */ if (!strcmp(verb, "start")) { if (!is_running()) { return VoxlEsc::task_spawn(argc, argv); @@ -533,7 +671,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) } if (!is_running()) { - PX4_INFO("Not running"); + PX4_INFO("VOXL_ESC:Not running"); return -1; } @@ -592,7 +730,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) if (!strcmp(verb, "reset")) { if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) { - PX4_INFO("Reset ESC: %i", esc_id); + PX4_INFO("VOXL_ESC: Reset ESC: %i", esc_id); cmd.len = qc_esc_create_reset_packet(esc_id, cmd.buf, sizeof(cmd.buf)); cmd.response = false; return get_instance()->send_cmd_thread_safe(&cmd); @@ -604,7 +742,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) } else if (!strcmp(verb, "version")) { if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) { - PX4_INFO("Request version for ESC: %i", esc_id); + PX4_INFO("VOXL_ESC: Request version for ESC: %i", esc_id); cmd.len = qc_esc_create_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf)); cmd.response = true; cmd.resp_delay_us = 2000; @@ -617,7 +755,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) } else if (!strcmp(verb, "version-ext")) { if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) { - PX4_INFO("Request extended version for ESC: %i", esc_id); + PX4_INFO("VOXL_ESC: Request extended version for ESC: %i", esc_id); cmd.len = qc_esc_create_extended_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf)); cmd.response = true; cmd.resp_delay_us = 5000; @@ -630,7 +768,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) } else if (!strcmp(verb, "tone")) { if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) { - PX4_INFO("Request tone for ESC mask: %i", esc_id); + PX4_INFO("VOXL_ESC: Request tone for ESC mask: %i", esc_id); cmd.len = qc_esc_create_sound_packet(period, duration, power, esc_id, cmd.buf, sizeof(cmd.buf)); cmd.response = false; return get_instance()->send_cmd_thread_safe(&cmd); @@ -644,7 +782,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) if (led_mask <= 0x0FFF) { get_instance()->_led_rsc.test = true; get_instance()->_led_rsc.breath_en = false; - PX4_INFO("Request LED control for ESCs with mask: %i", led_mask); + PX4_INFO("VOXL_ESC: Request LED control for ESCs with mask: %i", led_mask); get_instance()->_esc_chans[0].led = (led_mask & 0x0007); get_instance()->_esc_chans[1].led = (led_mask & 0x0038) >> 3; @@ -659,7 +797,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) } else if (!strcmp(verb, "rpm")) { if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) { - PX4_INFO("Request RPM for ESC ID: %i - RPM: %i", esc_id, rate); + PX4_INFO("VOXL_ESC: Request RPM for ESC ID: %i - RPM: %i", esc_id, rate); int16_t rate_req[VOXL_ESC_OUTPUT_CHANNELS] = {0, 0, 0, 0}; uint8_t id_fb = 0; @@ -693,8 +831,8 @@ int VoxlEsc::custom_command(int argc, char *argv[]) cmd.repeat_delay_us = repeat_delay_us; cmd.print_feedback = true; - PX4_INFO("feedback id debug: %i", id_fb); - PX4_INFO("Sending UART ESC RPM command %i", rate); + PX4_INFO("VOXL_ESC: Feedback id debug: %i", id_fb); + PX4_INFO("VOXL_ESC: Sending UART ESC RPM command %i", rate); return get_instance()->send_cmd_thread_safe(&cmd); @@ -705,7 +843,7 @@ int VoxlEsc::custom_command(int argc, char *argv[]) } else if (!strcmp(verb, "pwm")) { if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) { - PX4_INFO("Request PWM for ESC ID: %i - PWM: %i", esc_id, rate); + PX4_INFO("VOXL_ESC: Request PWM for ESC ID: %i - PWM: %i", esc_id, rate); int16_t rate_req[VOXL_ESC_OUTPUT_CHANNELS] = {0, 0, 0, 0}; uint8_t id_fb = 0; @@ -738,8 +876,8 @@ int VoxlEsc::custom_command(int argc, char *argv[]) cmd.repeat_delay_us = repeat_delay_us; cmd.print_feedback = true; - PX4_INFO("feedback id debug: %i", id_fb); - PX4_INFO("Sending UART ESC power command %i", rate); + PX4_INFO("VOXL_ESC: Feedback id debug: %i", id_fb); + PX4_INFO("VOXL_ESC: Sending UART ESC power command %i", rate); return get_instance()->send_cmd_thread_safe(&cmd); @@ -1103,8 +1241,8 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], sizeof(cmd.buf), _extended_rpm); - if (_uart_port->uart_write(cmd.buf, cmd.len) != cmd.len) { - PX4_ERR("Failed to send packet"); + if (_uart_port.write(cmd.buf, cmd.len) != cmd.len) { + PX4_ERR("VOXL_ESC: Failed to send packet"); return false; } @@ -1118,7 +1256,7 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], * uart_read is non-blocking and we will just parse whatever bytes came in up until this point */ - int res = _uart_port->uart_read(_read_buf, sizeof(_read_buf)); + int res = _uart_port.read(_read_buf, sizeof(_read_buf)); if (res > 0) { parse_response(_read_buf, res, false); @@ -1155,8 +1293,8 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], // PX4_INFO(" 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x", // io_data.data[0], io_data.data[1], io_data.data[2], io_data.data[3], // io_data.data[4], io_data.data[5], io_data.data[6], io_data.data[7]); - if (_uart_port->uart_write(io_data.data, io_data.len) != io_data.len) { - PX4_ERR("Failed to send modal io data to esc"); + if (_uart_port.write(io_data.data, io_data.len) != io_data.len) { + PX4_ERR("VOXL_ESC: Failed to send modal io data to esc"); return false; } } @@ -1170,6 +1308,7 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], void VoxlEsc::Run() { if (should_exit()) { + PX4_ERR("VOXL_ESC: Stopping the module"); ScheduleClear(); _mixing_output.unregister(); @@ -1179,32 +1318,28 @@ void VoxlEsc::Run() perf_begin(_cycle_perf); - /* Open serial port in this thread */ - if (!_uart_port->is_open()) { - if (_uart_port->uart_open(_device, _parameters.baud_rate) == PX4_OK) { - PX4_INFO("Opened UART ESC device"); + //check to see if we need to open uart port and query the device + //see comment in init() regarding why we do not initialize the device there - } else { - PX4_ERR("Failed openening device"); - return; - } - } + int retries_left = VOXL_ESC_NUM_INIT_RETRIES; - /* Get ESC FW version info */ - if (_need_version_info) { - for (uint8_t esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; ++esc_id) { - Command cmd; - cmd.len = qc_esc_create_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf)); - - if (_uart_port->uart_write(cmd.buf, cmd.len) == cmd.len) { - if (read_response(&_current_cmd) != 0) { PX4_ERR("Failed to parse version request response packet!"); } + while ((!_device_initialized) && (retries_left > 0)) { + retries_left--; + int dev_init_ret = device_init(); - } else { - PX4_ERR("Failed to send version request packet!"); - } + if (dev_init_ret != 0) { + PX4_WARN("VOXL_ESC: Failed to initialize device, retries left %d", retries_left); } } + if (!_device_initialized) { + PX4_ERR("VOXL_ESC: Failed to initialize device, exiting the module"); + ScheduleClear(); + _mixing_output.unregister(); + exit_and_cleanup(); + return; + } + _mixing_output.update(); //calls MixingOutput::limitAndUpdateOutputs which calls updateOutputs in this module /* update output status if armed */ @@ -1278,11 +1413,11 @@ void VoxlEsc::Run() if (!_outputs_on) { if (_current_cmd.valid()) { //PX4_INFO("sending %d commands with delay %dus",_current_cmd.repeats,_current_cmd.repeat_delay_us); - flush_uart_rx(); + _uart_port.flush(); do { //PX4_INFO("CMDs left %d",_current_cmd.repeats); - if (_uart_port->uart_write(_current_cmd.buf, _current_cmd.len) == _current_cmd.len) { + if (_uart_port.write(_current_cmd.buf, _current_cmd.len) == _current_cmd.len) { if (_current_cmd.repeats == 0) { _current_cmd.clear(); } @@ -1296,19 +1431,19 @@ void VoxlEsc::Run() } else { if (_current_cmd.retries == 0) { _current_cmd.clear(); - PX4_ERR("Failed to send command, errno: %i", errno); + PX4_ERR("VOXL_ESC: Failed to send command, errno: %i", errno); } else { _current_cmd.retries--; - PX4_ERR("Failed to send command, errno: %i", errno); + PX4_ERR("VOXL_ESC: Failed to send command, errno: %i", errno); } } px4_usleep(_current_cmd.repeat_delay_us); } while (_current_cmd.repeats-- > 0); - PX4_INFO("RX packet count: %d", (int)_rx_packet_count); - PX4_INFO("CRC error count: %d", (int)_rx_crc_error_count); + PX4_INFO("VOXL_ESC: RX packet count: %d", (int)_rx_packet_count); + PX4_INFO("VOXL_ESC: CRC error count: %d", (int)_rx_crc_error_count); } else { Command *new_cmd = _pending_cmd.load(); @@ -1385,16 +1520,10 @@ It is typically started with: return 0; } -int VoxlEsc::print_status() +void VoxlEsc::print_params() { - PX4_INFO("Max update rate: %i Hz", _current_update_rate); - PX4_INFO("Outputs on: %s", _outputs_on ? "yes" : "no"); - PX4_INFO("UART port: %s", _device); - PX4_INFO("UART open: %s", _uart_port->is_open() ? "yes" : "no"); - - PX4_INFO(""); - PX4_INFO("Params: VOXL_ESC_CONFIG: %" PRId32, _parameters.config); + PX4_INFO("Params: VOXL_ESC_MODE: %" PRId32, _parameters.mode); PX4_INFO("Params: VOXL_ESC_BAUD: %" PRId32, _parameters.baud_rate); PX4_INFO("Params: VOXL_ESC_FUNC1: %" PRId32, _parameters.function_map[0]); @@ -1410,6 +1539,28 @@ int VoxlEsc::print_status() PX4_INFO("Params: VOXL_ESC_RPM_MIN: %" PRId32, _parameters.rpm_min); PX4_INFO("Params: VOXL_ESC_RPM_MAX: %" PRId32, _parameters.rpm_max); + PX4_INFO("Params: VOXL_ESC_T_PERC: %" PRId32, _parameters.turtle_motor_percent); + PX4_INFO("Params: VOXL_ESC_T_DEAD: %" PRId32, _parameters.turtle_motor_deadband); + PX4_INFO("Params: VOXL_ESC_T_EXPO: %" PRId32, _parameters.turtle_motor_expo); + PX4_INFO("Params: VOXL_ESC_T_MINF: %f", (double)_parameters.turtle_stick_minf); + PX4_INFO("Params: VOXL_ESC_T_COSP: %f", (double)_parameters.turtle_cosphi); + + PX4_INFO("Params: VOXL_ESC_VLOG: %" PRId32, _parameters.verbose_logging); + PX4_INFO("Params: VOXL_ESC_PUB_BST: %" PRId32, _parameters.publish_battery_status); + + PX4_INFO("Params: VOXL_ESC_T_WARN: %" PRId32, _parameters.esc_warn_temp_threshold); + PX4_INFO("Params: VOXL_ESC_T_OVER: %" PRId32, _parameters.esc_over_temp_threshold); +} + +int VoxlEsc::print_status() +{ + PX4_INFO("Max update rate: %i Hz", _current_update_rate); + PX4_INFO("Outputs on: %s", _outputs_on ? "yes" : "no"); + PX4_INFO("UART port: %s", _device); + PX4_INFO("UART open: %s", _uart_port.isOpen() ? "yes" : "no"); + + PX4_INFO(""); + print_params(); PX4_INFO(""); for( int i = 0; i < VOXL_ESC_OUTPUT_CHANNELS; i++){ @@ -1432,6 +1583,25 @@ int VoxlEsc::print_status() return 0; } +const char * VoxlEsc::board_id_to_name(int board_id) +{ + switch(board_id){ + case 31: return "ModalAi 4-in-1 ESC V2 RevB (M0049)"; + case 32: return "Blheli32 4-in-1 ESC Type A (Tmotor F55A PRO F051)"; + case 33: return "Blheli32 4-in-1 ESC Type B (Tmotor F55A PRO G071)"; + case 34: return "ModalAi 4-in-1 ESC (M0117-1)"; + case 35: return "ModalAi I/O Expander (M0065)"; + case 36: return "ModalAi 4-in-1 ESC (M0117-3)"; + case 37: return "ModalAi 4-in-1 ESC (M0134-1)"; + case 38: return "ModalAi 4-in-1 ESC (M0134-3)"; + case 39: return "ModalAi 4-in-1 ESC (M0129-1)"; + case 40: return "ModalAi 4-in-1 ESC (M0129-3)"; + case 41: return "ModalAi 4-in-1 ESC (M0134-6)"; + case 42: return "ModalAi 4-in-1 ESC (M0138-1)"; + default: return "Unknown Board"; + } +} + extern "C" __EXPORT int voxl_esc_main(int argc, char *argv[]); int voxl_esc_main(int argc, char *argv[]) diff --git a/src/drivers/actuators/voxl_esc/voxl_esc.hpp b/src/drivers/actuators/voxl_esc/voxl_esc.hpp index 8cc84435fae4..d894cb93266f 100644 --- a/src/drivers/actuators/voxl_esc/voxl_esc.hpp +++ b/src/drivers/actuators/voxl_esc/voxl_esc.hpp @@ -51,11 +51,13 @@ #include #include -#include "voxl_esc_serial.hpp" +#include #include "qc_esc_packet.h" #include "qc_esc_packet_types.h" +using namespace device; + class VoxlEsc : public ModuleBase, public OutputModuleInterface { public: @@ -76,16 +78,18 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface /** @see ModuleBase::print_status() */ int print_status() override; + void print_params(); /** @see OutputModuleInterface */ bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs, unsigned num_control_groups_updated) override; virtual int init(); + int device_init(); // function where uart port is opened and ESC queried struct Command { uint16_t id = 0; - uint8_t len = 0; + uint8_t len = 0; uint16_t repeats = 0; uint16_t repeat_delay_us = 2000; uint8_t retries = 0; @@ -94,7 +98,7 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface bool print_feedback = false; static const uint8_t BUF_SIZE = 128; - uint8_t buf[BUF_SIZE]; + uint8_t buf[BUF_SIZE]; bool valid() const { return len > 0; } void clear() { len = 0; } @@ -125,16 +129,19 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface static constexpr uint32_t VOXL_ESC_MODE_TURTLE_AUX1 = 1; static constexpr uint32_t VOXL_ESC_MODE_TURTLE_AUX2 = 2; - static constexpr uint16_t VOXL_ESC_EXT_RPM = 39; + static constexpr uint16_t VOXL_ESC_EXT_RPM = + 39; // minimum firmware version for extended RPM command support static constexpr uint16_t VOXL_ESC_RPM_MAX = INT16_MAX - 1; // 32K, Limit max standard range RPM to prevent overflow (rpm packet packing function accepts int32_t) static constexpr uint16_t VOXL_ESC_RPM_MAX_EXT = UINT16_MAX - 5; // 65K, Limit max extended range RPM to prevent overflow (rpm packet packing function accepts int32_t) + static constexpr uint16_t VOXL_ESC_NUM_INIT_RETRIES = 3; + //static constexpr uint16_t max_pwm(uint16_t pwm) { return math::min(pwm, VOXL_ESC_PWM_MAX); } //static constexpr uint16_t max_rpm(uint16_t rpm) { return math::min(rpm, VOXL_ESC_RPM_MAX); } - VoxlEscSerial *_uart_port; + Serial _uart_port{}; typedef struct { int32_t config{VOXL_ESC_UART_CONFIG}; @@ -151,7 +158,9 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface int32_t motor_map[VOXL_ESC_OUTPUT_CHANNELS] {1, 2, 3, 4}; int32_t direction_map[VOXL_ESC_OUTPUT_CHANNELS] {1, 1, 1, 1}; int32_t verbose_logging{0}; - int32_t publish_battery_status{0}; + int32_t publish_battery_status{0}; + int32_t esc_warn_temp_threshold{0}; + int32_t esc_over_temp_threshold{0}; } voxl_esc_params_t; struct EscChan { @@ -161,7 +170,7 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface uint8_t power_applied; uint8_t led; uint8_t cmd_counter; - float voltage; //Volts + float voltage; //Volts float current; //Amps float temperature; //deg C hrt_abstime feedback_time; @@ -182,7 +191,7 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface } led_rsc_t; ch_assign_t _output_map[VOXL_ESC_OUTPUT_CHANNELS] {{1, 1}, {2, 1}, {3, 1}, {4, 1}}; - MixingOutput _mixing_output; + MixingOutput _mixing_output; perf_counter_t _cycle_perf; perf_counter_t _output_update_perf; @@ -193,8 +202,8 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; - uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)}; + uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)}; uORB::Subscription _led_update_sub{ORB_ID(led_control)}; uORB::Subscription _voxl2_io_data_sub{ORB_ID(voxl2_io_data)}; @@ -203,12 +212,12 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface bool _extended_rpm{false}; bool _need_version_info{true}; - QC_ESC_VERSION_INFO _version_info[4]; - bool check_versions_updated(); + QC_ESC_EXTENDED_VERSION_INFO _version_info[VOXL_ESC_OUTPUT_CHANNELS]; voxl_esc_params_t _parameters; int update_params(); int load_params(voxl_esc_params_t *params, ch_assign_t *map); + const char *board_id_to_name(int board_id); bool _turtle_mode_en{false}; int32_t _rpm_turtle_min{0}; @@ -216,7 +225,7 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface manual_control_setpoint_s _manual_control_setpoint{}; uint16_t _cmd_id{0}; - Command _current_cmd; + Command _current_cmd; px4::atomic _pending_cmd{nullptr}; EscChan _esc_chans[VOXL_ESC_OUTPUT_CHANNELS]; @@ -224,24 +233,25 @@ class VoxlEsc : public ModuleBase, public OutputModuleInterface esc_status_s _esc_status; EscPacket _fb_packet; - led_rsc_t _led_rsc; + led_rsc_t _led_rsc; int _fb_idx; uint32_t _rx_crc_error_count{0}; uint32_t _rx_packet_count{0}; - static const uint8_t READ_BUF_SIZE = 128; + static const uint8_t READ_BUF_SIZE = 128; uint8_t _read_buf[READ_BUF_SIZE]; - Battery _battery; + Battery _battery; static constexpr unsigned _battery_report_interval{100_ms}; hrt_abstime _last_battery_report_time; - void update_leds(vehicle_control_mode_s mode, led_control_s control); + bool _device_initialized{false}; + + void update_leds(vehicle_control_mode_s mode, led_control_s control); - int read_response(Command *out_cmd); - int parse_response(uint8_t *buf, uint8_t len, bool print_feedback); - int flush_uart_rx(); - int check_for_esc_timeout(); + int read_response(Command *out_cmd); + int parse_response(uint8_t *buf, uint8_t len, bool print_feedback); + int check_for_esc_timeout(); void mix_turtle_mode(uint16_t outputs[]); void handle_actuator_test(); }; diff --git a/src/drivers/actuators/voxl_esc/voxl_esc_params.c b/src/drivers/actuators/voxl_esc/voxl_esc_params.c index 8c1d03c6e7c1..f2719cea042b 100644 --- a/src/drivers/actuators/voxl_esc/voxl_esc_params.c +++ b/src/drivers/actuators/voxl_esc/voxl_esc_params.c @@ -231,4 +231,35 @@ PARAM_DEFINE_INT32(VOXL_ESC_VLOG, 0); * @min 0 * @max 1 */ -PARAM_DEFINE_INT32(VOXL_ESC_PUB_BST, 1); \ No newline at end of file +PARAM_DEFINE_INT32(VOXL_ESC_PUB_BST, 1); + + +/** + * UART ESC Temperature Warning Threshold (Degrees C) + * + * Only applicable to ESCs that report temperature + * + * @reboot_required true + * + * @group VOXL ESC + * @value 0 - Disabled + * @min 0 + * @max 200 + */ +PARAM_DEFINE_INT32(VOXL_ESC_T_WARN, 0); + + +/** + * UART ESC Over-Temperature Threshold (Degrees C) + * + * Only applicable to ESCs that report temperature + * + * @reboot_required true + * + * @group VOXL ESC + * @value 0 - Disabled + * @min 0 + * @max 200 + */ +PARAM_DEFINE_INT32(VOXL_ESC_T_OVER, 0); + diff --git a/src/drivers/actuators/voxl_esc/voxl_esc_serial.cpp b/src/drivers/actuators/voxl_esc/voxl_esc_serial.cpp deleted file mode 100644 index 1064dc4365c3..000000000000 --- a/src/drivers/actuators/voxl_esc/voxl_esc_serial.cpp +++ /dev/null @@ -1,191 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 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 "string.h" -#include "voxl_esc_serial.hpp" - -VoxlEscSerial::VoxlEscSerial() -{ -} - -VoxlEscSerial::~VoxlEscSerial() -{ - if (_uart_fd >= 0) { - uart_close(); - } -} - -int VoxlEscSerial::uart_open(const char *dev, speed_t speed) -{ - if (_uart_fd >= 0) { - PX4_ERR("Port in use: %s (%i)", dev, errno); - return -1; - } - - /* Open UART */ -#ifdef __PX4_QURT - _uart_fd = qurt_uart_open(dev, speed); -#else - _uart_fd = open(dev, O_RDWR | O_NOCTTY | O_NONBLOCK); -#endif - - if (_uart_fd < 0) { - PX4_ERR("Error opening port: %s (%i)", dev, errno); - return -1; - } - -#ifndef __PX4_QURT - /* Back up the original UART configuration to restore it after exit */ - int termios_state; - - if ((termios_state = tcgetattr(_uart_fd, &_orig_cfg)) < 0) { - PX4_ERR("Error configuring port: tcgetattr %s: %d", dev, termios_state); - uart_close(); - return -1; - } - - /* Fill the struct for the new configuration */ - tcgetattr(_uart_fd, &_cfg); - - /* Disable output post-processing */ - _cfg.c_oflag &= ~OPOST; - - _cfg.c_cflag |= (CLOCAL | CREAD); /* ignore modem controls */ - _cfg.c_cflag &= ~CSIZE; - _cfg.c_cflag |= CS8; /* 8-bit characters */ - _cfg.c_cflag &= ~PARENB; /* no parity bit */ - _cfg.c_cflag &= ~CSTOPB; /* only need 1 stop bit */ - _cfg.c_cflag &= ~CRTSCTS; /* no hardware flowcontrol */ - - /* setup for non-canonical mode */ - _cfg.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON); - _cfg.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN); - - if (cfsetispeed(&_cfg, speed) < 0 || cfsetospeed(&_cfg, speed) < 0) { - PX4_ERR("Error configuring port: %s: %d (cfsetispeed, cfsetospeed)", dev, termios_state); - uart_close(); - return -1; - } - - if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &_cfg)) < 0) { - PX4_ERR("Error configuring port: %s (tcsetattr)", dev); - uart_close(); - return -1; - } - -#endif - - _speed = speed; - - return 0; -} - -int VoxlEscSerial::uart_set_baud(speed_t speed) -{ -#ifndef __PX4_QURT - - if (_uart_fd < 0) { - return -1; - } - - if (cfsetispeed(&_cfg, speed) < 0) { - return -1; - } - - if (tcsetattr(_uart_fd, TCSANOW, &_cfg) < 0) { - return -1; - } - - _speed = speed; - - return 0; -#endif - - return -1; -} - -int VoxlEscSerial::uart_close() -{ -#ifndef __PX4_QURT - - if (_uart_fd < 0) { - PX4_ERR("invalid state for closing"); - return -1; - } - - if (tcsetattr(_uart_fd, TCSANOW, &_orig_cfg)) { - PX4_ERR("failed restoring uart to original state"); - } - - if (close(_uart_fd)) { - PX4_ERR("error closing uart"); - } - -#endif - - _uart_fd = -1; - - return 0; -} - -int VoxlEscSerial::uart_write(FAR void *buf, size_t len) -{ - if (_uart_fd < 0 || buf == NULL) { - PX4_ERR("invalid state for writing or buffer"); - return -1; - } - -#ifdef __PX4_QURT - return qurt_uart_write(_uart_fd, (const char *) buf, len); -#else - return write(_uart_fd, buf, len); -#endif -} - -int VoxlEscSerial::uart_read(FAR void *buf, size_t len) -{ - if (_uart_fd < 0 || buf == NULL) { - PX4_ERR("invalid state for reading or buffer"); - return -1; - } - -#ifdef __PX4_QURT -#define ASYNC_UART_READ_WAIT_US 2000 - // The UART read on SLPI is via an asynchronous service so specify a timeout - // for the return. The driver will poll periodically until the read comes in - // so this may block for a while. However, it will timeout if no read comes in. - return qurt_uart_read(_uart_fd, (char *) buf, len, ASYNC_UART_READ_WAIT_US); -#else - return read(_uart_fd, buf, len); -#endif -} diff --git a/src/drivers/actuators/voxl_esc/voxl_esc_serial.hpp b/src/drivers/actuators/voxl_esc/voxl_esc_serial.hpp deleted file mode 100644 index 99e918886f62..000000000000 --- a/src/drivers/actuators/voxl_esc/voxl_esc_serial.hpp +++ /dev/null @@ -1,69 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 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 - -#ifdef __PX4_QURT -#include -#define FAR -#endif - -class VoxlEscSerial -{ -public: - VoxlEscSerial(); - virtual ~VoxlEscSerial(); - - int uart_open(const char *dev, speed_t speed); - int uart_set_baud(speed_t speed); - int uart_close(); - int uart_write(FAR void *buf, size_t len); - int uart_read(FAR void *buf, size_t len); - bool is_open() { return _uart_fd >= 0; }; - int uart_get_baud() {return _speed; } - -private: - int _uart_fd = -1; - -#if ! defined(__PX4_QURT) - struct termios _orig_cfg; - struct termios _cfg; -#endif - - int _speed = -1; -}; From ec3ceae45e62fb63ba6c518a1f3fcf66ee2ea1b0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 18 Apr 2024 15:14:59 -0400 Subject: [PATCH 122/652] ekf2: move yaw_estimator and derivation to dedicated folder --- src/modules/ekf2/CMakeLists.txt | 14 +++-- src/modules/ekf2/EKF/CMakeLists.txt | 15 +++++- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF/gps_control.cpp | 4 +- .../EKF/python/ekf_derivation/derivation.py | 2 +- .../derivation_terrain_estimator.py | 6 +-- .../python/ekf_derivation/utils/__init__.py | 0 .../{ => utils}/derivation_utils.py | 0 .../ekf2/EKF/yaw_estimator/CMakeLists.txt | 39 ++++++++++++++ .../EKF/{ => yaw_estimator}/EKFGSF_yaw.cpp | 34 ++++++++---- .../ekf2/EKF/{ => yaw_estimator}/EKFGSF_yaw.h | 54 ++++++++----------- .../derivation}/derivation_yaw_estimator.py | 17 +++--- .../yaw_est_compute_measurement_update.h | 0 .../generated/yaw_est_predict_covariance.h | 0 14 files changed, 126 insertions(+), 61 deletions(-) create mode 100644 src/modules/ekf2/EKF/python/ekf_derivation/utils/__init__.py rename src/modules/ekf2/EKF/python/ekf_derivation/{ => utils}/derivation_utils.py (100%) create mode 100644 src/modules/ekf2/EKF/yaw_estimator/CMakeLists.txt rename src/modules/ekf2/EKF/{ => yaw_estimator}/EKFGSF_yaw.cpp (95%) rename src/modules/ekf2/EKF/{ => yaw_estimator}/EKFGSF_yaw.h (78%) rename src/modules/ekf2/EKF/{python/ekf_derivation => yaw_estimator/derivation}/derivation_yaw_estimator.py (90%) rename src/modules/ekf2/EKF/{python/ekf_derivation => yaw_estimator/derivation}/generated/yaw_est_compute_measurement_update.h (100%) rename src/modules/ekf2/EKF/{python/ekf_derivation => yaw_estimator/derivation}/generated/yaw_est_predict_covariance.h (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 2914f5a6b86a..9d42a6e2423b 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -63,7 +63,7 @@ if(EKF2_SYMFORCE_GEN AND (${PYTHON_SYMFORCE_EXIT_CODE} EQUAL 0)) ${PYTHON_EXECUTABLE} ${EKF_DERIVATION_SRC_DIR}/derivation.py DEPENDS ${EKF_DERIVATION_SRC_DIR}/derivation.py - ${EKF_DERIVATION_SRC_DIR}/derivation_utils.py + ${EKF_DERIVATION_SRC_DIR}/utils/derivation_utils.py WORKING_DIRECTORY ${EKF_DERIVATION_SRC_DIR} COMMENT "Symforce code generation (default)" @@ -97,7 +97,7 @@ if(EKF2_SYMFORCE_GEN AND (${PYTHON_SYMFORCE_EXIT_CODE} EQUAL 0)) ${PYTHON_EXECUTABLE} ${EKF_DERIVATION_SRC_DIR}/derivation.py ${SYMFORCE_ARGS} DEPENDS ${EKF_DERIVATION_SRC_DIR}/derivation.py - ${EKF_DERIVATION_SRC_DIR}/derivation_utils.py + ${EKF_DERIVATION_SRC_DIR}/utils/derivation_utils.py WORKING_DIRECTORY ${EKF_DERIVATION_DST_DIR} COMMENT "Symforce code generation" @@ -113,6 +113,7 @@ if(EKF2_SYMFORCE_GEN AND (${PYTHON_SYMFORCE_EXIT_CODE} EQUAL 0)) ) endif() +set(EKF_LIBS) set(EKF_SRCS) list(APPEND EKF_SRCS EKF/bias_estimator.cpp @@ -120,7 +121,6 @@ list(APPEND EKF_SRCS EKF/covariance.cpp EKF/ekf.cpp EKF/ekf_helper.cpp - EKF/EKFGSF_yaw.cpp EKF/estimator_interface.cpp EKF/fake_height_control.cpp EKF/fake_pos_control.cpp @@ -174,6 +174,8 @@ if(CONFIG_EKF2_GNSS) EKF/gps_checks.cpp EKF/gps_control.cpp ) + + list(APPEND EKF_LIBS yaw_estimator) endif() if(CONFIG_EKF2_GNSS_YAW) @@ -215,6 +217,10 @@ if(CONFIG_EKF2_TERRAIN) list(APPEND EKF_SRCS EKF/terrain_estimator.cpp) endif() +add_subdirectory(EKF) + + + px4_add_module( MODULE modules__ekf2 MAIN ekf2 @@ -254,10 +260,10 @@ px4_add_module( EKF2Utility px4_work_queue world_magnetic_model + ${EKF_LIBS} UNITY_BUILD ) if(BUILD_TESTING) - add_subdirectory(EKF) add_subdirectory(test) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 4851bdfc755f..69d4edd146c9 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -31,6 +31,7 @@ # ############################################################################ +set(EKF_LIBS) set(EKF_SRCS) list(APPEND EKF_SRCS bias_estimator.cpp @@ -90,8 +91,10 @@ if(CONFIG_EKF2_GNSS) gnss_height_control.cpp gps_checks.cpp gps_control.cpp - EKFGSF_yaw.cpp ) + + add_subdirectory(yaw_estimator) + list(APPEND EKF_LIBS yaw_estimator) endif() if(CONFIG_EKF2_GNSS_YAW) @@ -133,11 +136,19 @@ if(CONFIG_EKF2_TERRAIN) list(APPEND EKF_SRCS terrain_estimator.cpp) endif() +include_directories(${CMAKE_CURRENT_SOURCE_DIR}) add_library(ecl_EKF ${EKF_SRCS} ) add_dependencies(ecl_EKF prebuild_targets) target_include_directories(ecl_EKF PUBLIC ${EKF_GENERATED_DERIVATION_INCLUDE_PATH}) -target_link_libraries(ecl_EKF PRIVATE geo world_magnetic_model) + +target_link_libraries(ecl_EKF + PRIVATE + geo + world_magnetic_model + ${EKF_LIBS} +) + target_compile_options(ecl_EKF PRIVATE -fno-associative-math) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 139214866aac..b0ca385d909e 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -46,7 +46,7 @@ #include "estimator_interface.h" #if defined(CONFIG_EKF2_GNSS) -# include "EKFGSF_yaw.h" +# include "yaw_estimator/EKFGSF_yaw.h" #endif // CONFIG_EKF2_GNSS #include "bias_estimator.hpp" diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/gps_control.cpp index 8e5e0bff91b4..d8a6b26522e3 100644 --- a/src/modules/ekf2/EKF/gps_control.cpp +++ b/src/modules/ekf2/EKF/gps_control.cpp @@ -51,7 +51,9 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) } // run EKF-GSF yaw estimator once per imu_delayed update - _yawEstimator.predict(imu_delayed, _control_status.flags.in_air && !_control_status.flags.vehicle_at_rest); + _yawEstimator.predict(imu_delayed.delta_ang, imu_delayed.delta_ang_dt, + imu_delayed.delta_vel, imu_delayed.delta_vel_dt, + (_control_status.flags.in_air && !_control_status.flags.vehicle_at_rest)); _gps_intermittent = !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GNSS_MAX_INTERVAL); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py index df3947e45977..452d9f565b19 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py @@ -48,7 +48,7 @@ from symforce.values import Values import sympy as sp -from derivation_utils import * +from utils.derivation_utils import * # Initialize parser parser = argparse.ArgumentParser() diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_terrain_estimator.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation_terrain_estimator.py index 2d321eb6ed00..14914f30c1ce 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_terrain_estimator.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation_terrain_estimator.py @@ -1,7 +1,7 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- """ - Copyright (c) 2023 PX4 Development Team + Copyright (c) 2023-2024 PX4 Development Team Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: @@ -37,7 +37,7 @@ symforce.set_epsilon_to_symbol() import symforce.symbolic as sf -from derivation_utils import * +from utils.derivation_utils import * def predict_opt_flow( terrain_vpos: sf.Scalar, diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/utils/__init__.py b/src/modules/ekf2/EKF/python/ekf_derivation/utils/__init__.py new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_utils.py b/src/modules/ekf2/EKF/python/ekf_derivation/utils/derivation_utils.py similarity index 100% rename from src/modules/ekf2/EKF/python/ekf_derivation/derivation_utils.py rename to src/modules/ekf2/EKF/python/ekf_derivation/utils/derivation_utils.py diff --git a/src/modules/ekf2/EKF/yaw_estimator/CMakeLists.txt b/src/modules/ekf2/EKF/yaw_estimator/CMakeLists.txt new file mode 100644 index 000000000000..1f12a2ba0338 --- /dev/null +++ b/src/modules/ekf2/EKF/yaw_estimator/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. +# +############################################################################ + +add_library(yaw_estimator + EKFGSF_yaw.cpp + EKFGSF_yaw.h +) + +add_dependencies(yaw_estimator prebuild_targets) diff --git a/src/modules/ekf2/EKF/EKFGSF_yaw.cpp b/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp similarity index 95% rename from src/modules/ekf2/EKF/EKFGSF_yaw.cpp rename to src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp index 697e027e6d85..c8655827be96 100644 --- a/src/modules/ekf2/EKF/EKFGSF_yaw.cpp +++ b/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-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,10 +32,24 @@ ****************************************************************************/ #include "EKFGSF_yaw.h" + #include -#include "python/ekf_derivation/generated/yaw_est_predict_covariance.h" -#include "python/ekf_derivation/generated/yaw_est_compute_measurement_update.h" +#include // CONSTANTS_ONE_G + +#include "derivation/generated/yaw_est_predict_covariance.h" +#include "derivation/generated/yaw_est_compute_measurement_update.h" + +using matrix::AxisAnglef; +using matrix::Dcmf; +using matrix::Eulerf; +using matrix::Matrix3f; +using matrix::Quatf; +using matrix::Vector2f; +using matrix::Vector3f; +using matrix::wrap_pi; +using math::Utilities::getEulerYaw; +using math::Utilities::updateYawInRotMat; EKFGSF_yaw::EKFGSF_yaw() { @@ -49,13 +63,14 @@ void EKFGSF_yaw::reset() _gsf_yaw_variance = INFINITY; } -void EKFGSF_yaw::predict(const imuSample &imu_sample, bool in_air) +void EKFGSF_yaw::predict(const matrix::Vector3f &delta_ang, const float delta_ang_dt, const matrix::Vector3f &delta_vel, + const float delta_vel_dt, bool in_air) { - const Vector3f accel = imu_sample.delta_vel / imu_sample.delta_vel_dt; + const Vector3f accel = delta_vel / delta_vel_dt; - if (imu_sample.delta_vel_dt > 0.001f) { + if (delta_vel_dt > 0.001f) { // to reduce effect of vibration, filter using an LPF whose time constant is 1/10 of the AHRS tilt correction time constant - const float filter_coef = fminf(10.f * imu_sample.delta_vel_dt * _tilt_gain, 1.f); + const float filter_coef = fminf(10.f * delta_vel_dt * _tilt_gain, 1.f); _ahrs_accel = _ahrs_accel * (1.f - filter_coef) + accel * filter_coef; } else { @@ -76,7 +91,7 @@ void EKFGSF_yaw::predict(const imuSample &imu_sample, bool in_air) && (accel_lpf_norm_sq > sq(lower_accel_limit)) && (accel_lpf_norm_sq < sq(upper_accel_limit)); if (ok_to_align) { - ahrsAlignTilt(imu_sample.delta_vel); + ahrsAlignTilt(delta_vel); _ahrs_ekf_gsf_tilt_aligned = true; } else { @@ -85,8 +100,7 @@ void EKFGSF_yaw::predict(const imuSample &imu_sample, bool in_air) } for (uint8_t model_index = 0; model_index < N_MODELS_EKFGSF; model_index ++) { - predictEKF(model_index, imu_sample.delta_ang, imu_sample.delta_ang_dt, - imu_sample.delta_vel, imu_sample.delta_vel_dt, in_air); + predictEKF(model_index, delta_ang, delta_ang_dt, delta_vel, delta_vel_dt, in_air); } } diff --git a/src/modules/ekf2/EKF/EKFGSF_yaw.h b/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.h similarity index 78% rename from src/modules/ekf2/EKF/EKFGSF_yaw.h rename to src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.h index 7add1dedef7a..ec84ed06f925 100644 --- a/src/modules/ekf2/EKF/EKFGSF_yaw.h +++ b/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-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 @@ -34,40 +34,28 @@ #ifndef EKF_EKFGSF_YAW_H #define EKF_EKFGSF_YAW_H -#include -#include -#include - -#include "common.h" - -using matrix::AxisAnglef; -using matrix::Dcmf; -using matrix::Eulerf; -using matrix::Matrix3f; -using matrix::Quatf; -using matrix::Vector2f; -using matrix::Vector3f; -using matrix::wrap_pi; +#include +#include static constexpr uint8_t N_MODELS_EKFGSF = 5; -using namespace estimator; - class EKFGSF_yaw { public: EKFGSF_yaw(); // Update Filter States - this should be called whenever new IMU data is available - void predict(const imuSample &imu_sample, bool in_air = false); + void predict(const matrix::Vector3f &delta_ang, const float delta_ang_dt, + const matrix::Vector3f &delta_vel, const float delta_vel_dt, + bool in_air = false); - void fuseVelocity(const Vector2f &vel_NE, // NE velocity measurement (m/s) - float vel_accuracy, // 1-sigma accuracy of velocity measurement (m/s) - bool in_air); + // vel_NE: NE velocity measurement (m/s) + // vel_accuracy: 1-sigma accuracy of velocity measurement (m/s) + void fuseVelocity(const matrix::Vector2f &vel_NE, float vel_accuracy, bool in_air); void setTrueAirspeed(float true_airspeed) { _true_airspeed = true_airspeed; } - void setGyroBias(const Vector3f &imu_gyro_bias, const bool force = false) + void setGyroBias(const matrix::Vector3f &imu_gyro_bias, const bool force = false) { // Initialise to gyro bias estimate from main filter because there could be a large // uncorrected rate gyro bias error about the gravity vector @@ -106,31 +94,31 @@ class EKFGSF_yaw float _true_airspeed{NAN}; // true airspeed used for centripetal accel compensation (m/s) struct { - Dcmf R{matrix::eye()}; // matrix that rotates a vector from body to earth frame - Vector3f gyro_bias{}; // gyro bias learned and used by the quaternion calculation + matrix::Dcmf R{matrix::eye()}; // matrix that rotates a vector from body to earth frame + matrix::Vector3f gyro_bias{}; // gyro bias learned and used by the quaternion calculation } _ahrs_ekf_gsf[N_MODELS_EKFGSF] {}; bool _ahrs_ekf_gsf_tilt_aligned{false}; // true the initial tilt alignment has been calculated - Vector3f _ahrs_accel{0.f, 0.f, 0.f}; // low pass filtered body frame specific force vector used by AHRS calculation (m/s/s) + matrix::Vector3f _ahrs_accel{0.f, 0.f, 0.f}; // low pass filtered body frame specific force vector used by AHRS calculation (m/s/s) // calculate the gain from gravity vector misalingment to tilt correction to be used by all AHRS filters float ahrsCalcAccelGain() const; // update specified AHRS rotation matrix using IMU and optionally true airspeed data - void ahrsPredict(const uint8_t model_index, const Vector3f &delta_ang, const float delta_ang_dt); + void ahrsPredict(const uint8_t model_index, const matrix::Vector3f &delta_ang, const float delta_ang_dt); // align all AHRS roll and pitch orientations using IMU delta velocity vector - void ahrsAlignTilt(const Vector3f &delta_vel); + void ahrsAlignTilt(const matrix::Vector3f &delta_vel); // align all AHRS yaw orientations to initial values void ahrsAlignYaw(); // Efficient propagation of a delta angle in body frame applied to the body to earth frame rotation matrix - Matrix3f ahrsPredictRotMat(const Matrix3f &R, const Vector3f &g); + matrix::Matrix3f ahrsPredictRotMat(const matrix::Matrix3f &R, const matrix::Vector3f &g); // Declarations used by a bank of N_MODELS_EKFGSF EKFs - struct _ekf_gsf_struct { + struct { matrix::Vector3f X{}; // Vel North (m/s), Vel East (m/s), yaw (rad)s matrix::SquareMatrix P{}; // covariance matrix matrix::SquareMatrix S_inverse{}; // inverse of the innovation covariance matrix @@ -141,15 +129,15 @@ class EKFGSF_yaw bool _ekf_gsf_vel_fuse_started{}; // true when the EKF's have started fusing velocity data and the prediction and update processing is active // initialise states and covariance data for the GSF and EKF filters - void initialiseEKFGSF(const Vector2f &vel_NE, const float vel_accuracy); + void initialiseEKFGSF(const matrix::Vector2f &vel_NE, const float vel_accuracy); // predict state and covariance for the specified EKF using inertial data - void predictEKF(const uint8_t model_index, const Vector3f &delta_ang, const float delta_ang_dt, - const Vector3f &delta_vel, const float delta_vel_dt, bool in_air = false); + void predictEKF(const uint8_t model_index, const matrix::Vector3f &delta_ang, const float delta_ang_dt, + const matrix::Vector3f &delta_vel, const float delta_vel_dt, bool in_air = false); // update state and covariance for the specified EKF using a NE velocity measurement // return false if update failed - bool updateEKF(const uint8_t model_index, const Vector2f &vel_NE, const float vel_accuracy); + bool updateEKF(const uint8_t model_index, const matrix::Vector2f &vel_NE, const float vel_accuracy); inline float sq(float x) const { return x * x; }; diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_yaw_estimator.py b/src/modules/ekf2/EKF/yaw_estimator/derivation/derivation_yaw_estimator.py similarity index 90% rename from src/modules/ekf2/EKF/python/ekf_derivation/derivation_yaw_estimator.py rename to src/modules/ekf2/EKF/yaw_estimator/derivation/derivation_yaw_estimator.py index e45fed5b25ce..076c945fde05 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_yaw_estimator.py +++ b/src/modules/ekf2/EKF/yaw_estimator/derivation/derivation_yaw_estimator.py @@ -1,7 +1,7 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- """ - Copyright (c) 2022-2023 PX4 Development Team + Copyright (c) 2022-2024 PX4 Development Team Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: @@ -38,7 +38,12 @@ import symforce.symbolic as sf from symforce.values import Values -from derivation_utils import * + +# generate_px4_function from derivation_utils in EKF/ekf_derivation/utils +import os, sys +derivation_utils_dir = os.path.dirname(os.path.abspath(__file__)) + "/../../python/ekf_derivation/utils" +sys.path.append(derivation_utils_dir) +import derivation_utils State = Values( vel = sf.V2(), @@ -148,7 +153,7 @@ def yaw_est_compute_measurement_update( S = H * P * H.T + R S_det = S[0, 0] * S[1, 1] - S[1, 0] * S[0, 1] - S_det_inv = add_epsilon_sign(1 / S_det, S_det, epsilon) + S_det_inv = derivation_utils.add_epsilon_sign(1 / S_det, S_det, epsilon) # Compute inverse using simple formula for 2x2 matrix and using protected division S_inv = sf.M22([[S[1, 1], -S[0, 1]], [-S[1, 0], S[0, 0]]]) * S_det_inv @@ -166,5 +171,5 @@ def yaw_est_compute_measurement_update( return (S_inv, S_det_inv, K, P_new) print("Derive yaw estimator equations...") -generate_px4_function(yaw_est_predict_covariance, output_names=["P_new"]) -generate_px4_function(yaw_est_compute_measurement_update, output_names=["S_inv", "S_det_inv", "K", "P_new"]) +derivation_utils.generate_px4_function(yaw_est_predict_covariance, output_names=["P_new"]) +derivation_utils.generate_px4_function(yaw_est_compute_measurement_update, output_names=["S_inv", "S_det_inv", "K", "P_new"]) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_est_compute_measurement_update.h b/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_compute_measurement_update.h similarity index 100% rename from src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_est_compute_measurement_update.h rename to src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_compute_measurement_update.h diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_est_predict_covariance.h b/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h similarity index 100% rename from src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_est_predict_covariance.h rename to src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h From 2a328615ede3bc952a906bf8c885eb33a17df6c5 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 18 Apr 2024 18:12:35 -0400 Subject: [PATCH 123/652] drivers/optical_flow/paw3902: fix RegisterRead udelay --- src/drivers/optical_flow/paw3902/PAW3902.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/optical_flow/paw3902/PAW3902.cpp b/src/drivers/optical_flow/paw3902/PAW3902.cpp index 05a8092a3d75..af70f9a5e32a 100644 --- a/src/drivers/optical_flow/paw3902/PAW3902.cpp +++ b/src/drivers/optical_flow/paw3902/PAW3902.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2019-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2019-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 @@ -918,7 +918,7 @@ uint8_t PAW3902::RegisterRead(uint8_t reg) // tSRW/tSRR SPI Time Between Read And Subsequent Commands const hrt_abstime elapsed_last_read = hrt_elapsed_time(&_last_read_time); - if (elapsed_last_write < TIME_TSRW_TSRR_us) { + if (elapsed_last_read < TIME_TSRW_TSRR_us) { px4_udelay(TIME_TSRW_TSRR_us - elapsed_last_read); } From 0a7689f3232eb804e6d6ffb7e6d1ed1930ccca16 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 18 Apr 2024 18:12:44 -0400 Subject: [PATCH 124/652] drivers/optical_flow/paa3905: fix RegisterRead udelay --- src/drivers/optical_flow/paa3905/PAA3905.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/optical_flow/paa3905/PAA3905.cpp b/src/drivers/optical_flow/paa3905/PAA3905.cpp index f5e5facd1e24..e99621f27bca 100644 --- a/src/drivers/optical_flow/paa3905/PAA3905.cpp +++ b/src/drivers/optical_flow/paa3905/PAA3905.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2022-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 @@ -714,7 +714,7 @@ uint8_t PAA3905::RegisterRead(uint8_t reg) // tSRW/tSRR SPI Time Between Read And Subsequent Commands const hrt_abstime elapsed_last_read = hrt_elapsed_time(&_last_read_time); - if (elapsed_last_write < TIME_TSRW_TSRR_us) { + if (elapsed_last_read < TIME_TSRW_TSRR_us) { px4_udelay(TIME_TSRW_TSRR_us - elapsed_last_read); } From c7725d74b4d4234a719bca0f16322758aa8ac420 Mon Sep 17 00:00:00 2001 From: Juyong Shin Date: Mon, 22 Apr 2024 13:57:57 +0900 Subject: [PATCH 125/652] fw offboard control mode: altitude control enabled (#23041) --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 610ddad03a5f..35a3c32c7df8 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1404,6 +1404,9 @@ FixedwingPositionControl::control_auto_path(const float control_interval, const tecs_fw_thr_max, _param_sinkrate_target.get(), _param_climbrate_target.get()); + + _att_sp.thrust_body[0] = min(get_tecs_thrust(), tecs_fw_thr_max); + _att_sp.pitch_body = get_tecs_pitch(); } void From f95a2021cd2151bf64c28e82f866eff7b7ba8aca Mon Sep 17 00:00:00 2001 From: asimopunov <50725049+asimopunov@users.noreply.github.com> Date: Mon, 22 Apr 2024 04:14:39 -0400 Subject: [PATCH 126/652] adsb: warnings fixes & remove UTM_GLOBAL_POSITION (#21663) - warn about full traffic conflict buffer at 1/60hz. - add conflict expiry for buffer. - use only events for buffer full warning. mavlink_log_critical no longer needed. - use icao address for conflict warnings id, stop using uas_id. UTM_GLOBAL_POSITION assumed deprecated. - stop spamming when buffer is full - fix warning wording if buffer is full. - remove UTM_GLOBAL_POSITION Fixes failing unit test: * [adsbTest] Reduce conflict timestamps - not enough time has passed in ci - failed ci output - (passes locally with make tests TESTFILTER=AdsbConflict) - Timestamp: 6000000000 - Time now: 457720038 - Time since timestamp: 0 - Old Conflict warning expired: 0 - -------------------- - adsb_conflict._traffic_state 0 - ../../src/lib/adsb/AdsbConflictTest.cpp:244: Failure - Value of: adsb_conflict._traffic_state == TRAFFIC_STATE::REMIND_CONFLICT - Actual: false - Expected: true --- src/lib/adsb/AdsbConflict.cpp | 193 ++++++++++++----------- src/lib/adsb/AdsbConflict.h | 16 +- src/lib/adsb/AdsbConflictTest.cpp | 31 ++-- src/modules/mavlink/mavlink_main.cpp | 5 - src/modules/mavlink/mavlink_messages.cpp | 4 - src/modules/mavlink/mavlink_receiver.cpp | 89 ----------- src/modules/navigator/navigator_main.cpp | 5 +- 7 files changed, 129 insertions(+), 214 deletions(-) diff --git a/src/lib/adsb/AdsbConflict.cpp b/src/lib/adsb/AdsbConflict.cpp index cb40f27a7df6..8fa11a8f2a72 100644 --- a/src/lib/adsb/AdsbConflict.cpp +++ b/src/lib/adsb/AdsbConflict.cpp @@ -108,12 +108,14 @@ void AdsbConflict::remove_icao_address_from_conflict_list(int traffic_index) { _traffic_buffer.icao_address.remove(traffic_index); _traffic_buffer.timestamp.remove(traffic_index); + PX4_INFO("icao_address removed. Buffer Size: %d", (int)_traffic_buffer.timestamp.size()); } void AdsbConflict::add_icao_address_from_conflict_list(uint32_t icao_address) { _traffic_buffer.timestamp.push_back(hrt_absolute_time()); _traffic_buffer.icao_address.push_back(icao_address); + PX4_INFO("icao_address added. Buffer Size: %d", (int)_traffic_buffer.timestamp.size()); } void AdsbConflict::get_traffic_state() @@ -129,7 +131,6 @@ void AdsbConflict::get_traffic_state() if (old_conflict && _conflict_detected) { old_conflict_warning_expired = (hrt_elapsed_time(&_traffic_buffer.timestamp[traffic_index]) > CONFLICT_WARNING_TIMEOUT); - } if (new_traffic && _conflict_detected && !_traffic_buffer_full) { @@ -154,65 +155,56 @@ void AdsbConflict::get_traffic_state() } +void AdsbConflict::remove_expired_conflicts() +{ + for (uint8_t traffic_index = 0; traffic_index < _traffic_buffer.timestamp.size();) { + if (hrt_elapsed_time(&_traffic_buffer.timestamp[traffic_index]) > TRAFFIC_CONFLICT_LIFETIME) { + events::send(events::ID("navigator_traffic_expired"), events::Log::Notice, + "Traffic Conflict {1} Expired and removed from buffer", + _traffic_buffer.icao_address[traffic_index]); + remove_icao_address_from_conflict_list(traffic_index); + + } else { + traffic_index++; + } + } +} bool AdsbConflict::handle_traffic_conflict() { get_traffic_state(); - char uas_id[UTM_GUID_MSG_LENGTH]; //GUID of incoming UTM messages - - //convert UAS_id byte array to char array for User Warning - for (int i = 0; i < 5; i++) { - snprintf(&uas_id[i * 2], sizeof(uas_id) - i * 2, "%02x", _transponder_report.uas_id[PX4_GUID_BYTE_LENGTH - 5 + i]); - } - - uint64_t uas_id_int = 0; - - for (int i = 0; i < 8; i++) { - uas_id_int |= (uint64_t)(_transponder_report.uas_id[PX4_GUID_BYTE_LENGTH - i - 1]) << (i * 8); - } - - bool take_action = false; switch (_traffic_state) { case TRAFFIC_STATE::ADD_CONFLICT: case TRAFFIC_STATE::REMIND_CONFLICT: { - - take_action = send_traffic_warning(math::degrees(_transponder_report.heading) + 180, - (int)fabsf(_crosstrack_error.distance), _transponder_report.flags, uas_id, + take_action = send_traffic_warning((int)(math::degrees(_transponder_report.heading) + 180.f), + (int)fabsf(_crosstrack_error.distance), _transponder_report.flags, _transponder_report.callsign, - uas_id_int); - + _transponder_report.icao_address); } break; case TRAFFIC_STATE::REMOVE_OLD_CONFLICT: { - - mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC UPDATE: %s is no longer in conflict!", - _transponder_report.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? - _transponder_report.callsign : uas_id); - - events::send(events::ID("navigator_traffic_resolved"), events::Log::Critical, "Traffic Conflict Resolved", - uas_id_int); - + events::send(events::ID("navigator_traffic_resolved"), events::Log::Notice, + "Traffic Conflict Resolved {1}!", + _transponder_report.icao_address); + _last_traffic_warning_time = hrt_absolute_time(); } break; case TRAFFIC_STATE::BUFFER_FULL: { - if (_traffic_state_previous != TRAFFIC_STATE::BUFFER_FULL) { - PX4_WARN("Too much traffic! Showing all messages from now on"); + if ((_traffic_state_previous != TRAFFIC_STATE::BUFFER_FULL) + && (hrt_elapsed_time(&_last_buffer_full_warning_time) > TRAFFIC_WARNING_TIMESTEP)) { + events::send(events::ID("buffer_full"), events::Log::Notice, "Too much traffic! Showing all messages from now on"); + _last_buffer_full_warning_time = hrt_absolute_time(); } - //stop buffering incoming conflicts - take_action = send_traffic_warning(math::degrees(_transponder_report.heading) + 180, - (int)fabsf(_crosstrack_error.distance), _transponder_report.flags, uas_id, - _transponder_report.callsign, - uas_id_int); - + //disable conflict warnings when buffer is full } break; @@ -242,49 +234,67 @@ void AdsbConflict::set_conflict_detection_params(float crosstrack_separation, fl bool AdsbConflict::send_traffic_warning(int traffic_direction, int traffic_seperation, uint16_t tr_flags, - char uas_id[UTM_GUID_MSG_LENGTH], char tr_callsign[UTM_CALLSIGN_LENGTH], uint64_t uas_id_int) + char tr_callsign[UTM_CALLSIGN_LENGTH], uint32_t icao_address) { switch (_conflict_detection_params.traffic_avoidance_mode) { case 0: { - PX4_WARN("TRAFFIC %s! dst %d, hdg %d", - tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, - traffic_seperation, - traffic_direction); + + if (tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN) { + + PX4_WARN("Traffic alert - UTM callsign %s! Separation Distance %d, Heading %d, ICAO Address %d", + tr_callsign, + traffic_seperation, + traffic_direction, (int)icao_address); + + } + + + _last_traffic_warning_time = hrt_absolute_time(); + break; } case 1: { - mavlink_log_critical(&_mavlink_log_pub, "Warning TRAFFIC %s! dst %d, hdg %d\t", - tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, - traffic_seperation, - traffic_direction); + + + if (tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN) { + + PX4_WARN("Traffic alert - UTM callsign %s! Separation Distance %d, Heading %d, ICAO Address %d", + tr_callsign, + traffic_seperation, + traffic_direction, (int)icao_address); + + } + /* EVENT * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees + * - ICAO Address: {1} + * - Traffic Separation Distance: {2m} + * - Heading: {3} degrees */ - events::send(events::ID("navigator_traffic"), events::Log::Critical, "Traffic alert", - uas_id_int, traffic_seperation, traffic_direction); + events::send(events::ID("navigator_traffic"), events::Log::Notice, + "Traffic alert - ICAO Address {1}! Separation Distance {2}, Heading {3}", + icao_address, traffic_seperation, traffic_direction); + + _last_traffic_warning_time = hrt_absolute_time(); + break; } case 2: { - mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Returning home! dst %d, hdg %d\t", - tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, - traffic_seperation, - traffic_direction); /* EVENT * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees + * - ICAO Address: {1} + * - Traffic Separation Distance: {2m} + * - Heading: {3} degrees */ - events::send(events::ID("navigator_traffic_rtl"), events::Log::Critical, - "Traffic alert, returning home", - uas_id_int, traffic_seperation, traffic_direction); + events::send(events::ID("navigator_traffic_rtl"), events::Log::Notice, + "Traffic alert - ICAO Address {1}! Separation Distance {2}, Heading {3}, returning home", + icao_address, traffic_seperation, traffic_direction); + + _last_traffic_warning_time = hrt_absolute_time(); return true; @@ -292,19 +302,17 @@ bool AdsbConflict::send_traffic_warning(int traffic_direction, int traffic_seper } case 3: { - mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Landing! dst %d, hdg % d\t", - tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, - traffic_seperation, - traffic_direction); /* EVENT * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees + * - ICAO Address: {1} + * - Traffic Separation Distance: {2m} + * - Heading: {3} degrees */ - events::send(events::ID("navigator_traffic_land"), events::Log::Critical, - "Traffic alert, landing", - uas_id_int, traffic_seperation, traffic_direction); + events::send(events::ID("navigator_traffic_land"), events::Log::Notice, + "Traffic alert - ICAO Address {1}! Separation Distance {2}, Heading {3}, landing", + icao_address, traffic_seperation, traffic_direction); + + _last_traffic_warning_time = hrt_absolute_time(); return true; @@ -313,19 +321,18 @@ bool AdsbConflict::send_traffic_warning(int traffic_direction, int traffic_seper } case 4: { - mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Holding position! dst %d, hdg %d\t", - tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, - traffic_seperation, - traffic_direction); /* EVENT * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees + * - ICAO Address: {1} + * - Traffic Separation Distance: {2m} + * - Heading: {3} degrees */ - events::send(events::ID("navigator_traffic_hold"), events::Log::Critical, - "Traffic alert, holding position", - uas_id_int, traffic_seperation, traffic_direction); + events::send(events::ID("navigator_traffic_hold"), events::Log::Notice, + "Traffic alert - ICAO Address {1}! Separation Distance {2}, Heading {3}, holding position", + icao_address, traffic_seperation, traffic_direction); + + _last_traffic_warning_time = hrt_absolute_time(); + return true; @@ -391,8 +398,7 @@ void AdsbConflict::fake_traffic(const char *callsign, float distance, float dire void AdsbConflict::run_fake_traffic(double &lat_uav, double &lon_uav, float &alt_uav) { - - /* + //Test with buffer size of 10 //first conflict fake_traffic("LX001", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 1, lat_uav, lon_uav, @@ -402,19 +408,20 @@ void AdsbConflict::run_fake_traffic(double &lat_uav, double &lon_uav, fake_traffic("LX002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 2, lat_uav, lon_uav, alt_uav); - fake_traffic("LX0002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + fake_traffic("LX002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 2, lat_uav, lon_uav, alt_uav); - fake_traffic("LX0002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + fake_traffic("LX002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 2, lat_uav, lon_uav, alt_uav); //stop spamming - + //new conflicts fake_traffic("LX003", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 3, lat_uav, lon_uav, alt_uav); + fake_traffic("LX004", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 4, lat_uav, lon_uav, alt_uav); @@ -445,6 +452,9 @@ void AdsbConflict::run_fake_traffic(double &lat_uav, double &lon_uav, alt_uav); //buffer full + + //buffer full conflicts + fake_traffic("LX011", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 11, lat_uav, lon_uav, alt_uav); @@ -458,7 +468,7 @@ void AdsbConflict::run_fake_traffic(double &lat_uav, double &lon_uav, alt_uav); - //end conflict + //end conflicts fake_traffic("LX001", 5000, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 1, lat_uav, lon_uav, alt_uav); @@ -474,30 +484,29 @@ void AdsbConflict::run_fake_traffic(double &lat_uav, double &lon_uav, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 4, lat_uav, lon_uav, alt_uav); - //new conflicts with space in buffer fake_traffic("LX013", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 13, lat_uav, lon_uav, alt_uav); - + //spam fake_traffic("LX013", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 13, lat_uav, lon_uav, alt_uav); - + //new conflict fake_traffic("LX014", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 14, lat_uav, lon_uav, alt_uav); - + //spam fake_traffic("LX014", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 14, lat_uav, lon_uav, alt_uav); - + //new conflict fake_traffic("LX015", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 15, lat_uav, lon_uav, alt_uav); + for (size_t i = 0; i < _traffic_buffer.icao_address.size(); i++) { PX4_INFO("%u ", static_cast(_traffic_buffer.icao_address[i])); } - */ } diff --git a/src/lib/adsb/AdsbConflict.h b/src/lib/adsb/AdsbConflict.h index b00d04f4dbd3..9942a6b921b6 100644 --- a/src/lib/adsb/AdsbConflict.h +++ b/src/lib/adsb/AdsbConflict.h @@ -46,7 +46,6 @@ #include #include -#include #include #include @@ -57,14 +56,15 @@ using namespace time_literals; static constexpr uint8_t NAVIGATOR_MAX_TRAFFIC{10}; -static constexpr uint8_t UTM_GUID_MSG_LENGTH{11}; - static constexpr uint8_t UTM_CALLSIGN_LENGTH{9}; static constexpr uint64_t CONFLICT_WARNING_TIMEOUT{60_s}; static constexpr float TRAFFIC_TO_UAV_DISTANCE_EXTENSION{1000.0f}; +static constexpr uint64_t TRAFFIC_WARNING_TIMESTEP{60_s}; //limits the max warning rate when traffic conflict buffer is full + +static constexpr uint64_t TRAFFIC_CONFLICT_LIFETIME{120_s}; //limits the time a conflict can be in the buffer without being seen (as a conflict) struct traffic_data_s { double lat_traffic; @@ -118,7 +118,7 @@ class AdsbConflict bool send_traffic_warning(int traffic_direction, int traffic_seperation, uint16_t tr_flags, - char uas_id[UTM_GUID_MSG_LENGTH], char tr_callsign[UTM_CALLSIGN_LENGTH], uint64_t uas_id_int); + char tr_callsign[UTM_CALLSIGN_LENGTH], uint32_t icao_address); transponder_report_s _transponder_report{}; @@ -132,6 +132,8 @@ class AdsbConflict void run_fake_traffic(double &lat_uav, double &lon_uav, float &alt_uav); + void remove_expired_conflicts(); + bool _conflict_detected{false}; TRAFFIC_STATE _traffic_state{TRAFFIC_STATE::NO_CONFLICT}; @@ -144,15 +146,15 @@ class AdsbConflict private: - orb_advert_t _mavlink_log_pub{nullptr}; - crosstrack_error_s _crosstrack_error{}; - transponder_report_s tr{}; orb_advert_t fake_traffic_report_publisher = orb_advertise(ORB_ID(transponder_report), &tr); TRAFFIC_STATE _traffic_state_previous{TRAFFIC_STATE::NO_CONFLICT}; + hrt_abstime _last_traffic_warning_time{0}; + + hrt_abstime _last_buffer_full_warning_time{0}; }; diff --git a/src/lib/adsb/AdsbConflictTest.cpp b/src/lib/adsb/AdsbConflictTest.cpp index d83ad8241463..5d6b6ccbe630 100644 --- a/src/lib/adsb/AdsbConflictTest.cpp +++ b/src/lib/adsb/AdsbConflictTest.cpp @@ -50,7 +50,7 @@ TEST_F(AdsbConflictTest, detectTrafficConflict) for (uint32_t i = 0; i < traffic_dataset_size; i++) { - printf("---------------%d--------------\n", i); + //printf("---------------%d--------------\n", i); struct traffic_data_s traffic = traffic_dataset[i]; @@ -64,10 +64,10 @@ TEST_F(AdsbConflictTest, detectTrafficConflict) adsb_conflict.detect_traffic_conflict(lat_now, lon_now, alt_now, vx_now, vy_now, vz_now); - printf("conflict_detected %d \n", adsb_conflict._conflict_detected); + //printf("conflict_detected %d \n", adsb_conflict._conflict_detected); - printf("------------------------------\n"); - printf("------------------------------\n \n"); + //printf("------------------------------\n"); + //printf("------------------------------\n \n"); EXPECT_TRUE(adsb_conflict._conflict_detected == traffic.in_conflict); } @@ -191,7 +191,6 @@ TEST_F(AdsbConflictTest, trafficAlerts) TEST_F(AdsbConflictTest, trafficReminder) { - struct traffic_buffer_s used_buffer; used_buffer.icao_address.push_back(2345); used_buffer.icao_address.push_back(1234); @@ -201,11 +200,11 @@ TEST_F(AdsbConflictTest, trafficReminder) used_buffer.icao_address.push_back(5000); used_buffer.timestamp.push_back(3_s); - used_buffer.timestamp.push_back(800_s); + used_buffer.timestamp.push_back(80_s); + used_buffer.timestamp.push_back(10_s); + used_buffer.timestamp.push_back(1000_s); used_buffer.timestamp.push_back(100_s); - used_buffer.timestamp.push_back(20000_s); - used_buffer.timestamp.push_back(6000_s); - used_buffer.timestamp.push_back(6587_s); + used_buffer.timestamp.push_back(187_s); struct traffic_buffer_s full_buffer; full_buffer.icao_address.push_back(2345); @@ -220,15 +219,15 @@ TEST_F(AdsbConflictTest, trafficReminder) full_buffer.icao_address.push_back(99999); full_buffer.timestamp.push_back(1_s); - full_buffer.timestamp.push_back(800_s); + full_buffer.timestamp.push_back(80_s); + full_buffer.timestamp.push_back(10_s); + full_buffer.timestamp.push_back(1000_s); full_buffer.timestamp.push_back(100_s); - full_buffer.timestamp.push_back(20000_s); - full_buffer.timestamp.push_back(6000_s); - full_buffer.timestamp.push_back(19000_s); - full_buffer.timestamp.push_back(5000_s); + full_buffer.timestamp.push_back(900_s); + full_buffer.timestamp.push_back(500_s); full_buffer.timestamp.push_back(2_s); - full_buffer.timestamp.push_back(1000_s); - full_buffer.timestamp.push_back(58943_s); + full_buffer.timestamp.push_back(100_s); + full_buffer.timestamp.push_back(5843_s); TestAdsbConflict adsb_conflict; diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 2467554e97a5..a3b17a063409 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1440,7 +1440,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f); configure_stream_local("SYS_STATUS", 1.0f); configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f); - configure_stream_local("UTM_GLOBAL_POSITION", 0.5f); configure_stream_local("VFR_HUD", 4.0f); configure_stream_local("VIBRATION", 0.1f); configure_stream_local("WIND_COV", 0.5f); @@ -1510,7 +1509,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("SYSTEM_TIME", 1.0f); configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f); configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f); - configure_stream_local("UTM_GLOBAL_POSITION", 1.0f); configure_stream_local("VFR_HUD", 10.0f); configure_stream_local("VIBRATION", 0.5f); configure_stream_local("WIND_COV", 10.0f); @@ -1576,7 +1574,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f); configure_stream_local("SYS_STATUS", 5.0f); configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f); - configure_stream_local("UTM_GLOBAL_POSITION", 1.0f); configure_stream_local("VFR_HUD", 4.0f); configure_stream_local("VIBRATION", 0.5f); configure_stream_local("WIND_COV", 1.0f); @@ -1675,7 +1672,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("SYS_STATUS", 1.0f); configure_stream_local("SYSTEM_TIME", 1.0f); configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f); - configure_stream_local("UTM_GLOBAL_POSITION", 1.0f); configure_stream_local("VFR_HUD", 20.0f); configure_stream_local("VIBRATION", 2.5f); configure_stream_local("WIND_COV", 10.0f); @@ -1760,7 +1756,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("SYSTEM_TIME", 2.0f); configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f); configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f); - configure_stream_local("UTM_GLOBAL_POSITION", 1.0f); configure_stream_local("VFR_HUD", 4.0f); configure_stream_local("VIBRATION", 0.5f); configure_stream_local("WIND_COV", 1.0f); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index bcd532861814..3356010b906f 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -150,7 +150,6 @@ # include "streams/SCALED_PRESSURE3.hpp" # include "streams/UAVIONIX_ADSB_OUT_CFG.hpp" # include "streams/UAVIONIX_ADSB_OUT_DYNAMIC.hpp" -# include "streams/UTM_GLOBAL_POSITION.hpp" #endif // !CONSTRAINED_FLASH // ensure PX4 rotation enum and MAV_SENSOR_ROTATION align @@ -419,9 +418,6 @@ static const StreamListItem streams_list[] = { #if defined(ADSB_VEHICLE_HPP) create_stream_list_item(), #endif // ADSB_VEHICLE_HPP -#if defined(UTM_GLOBAL_POSITION_HPP) - create_stream_list_item(), -#endif // UTM_GLOBAL_POSITION_HPP #if defined(COLLISION_HPP) create_stream_list_item(), #endif // COLLISION_HPP diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 928d744b4707..0385c6a1ebb6 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -224,10 +224,6 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_adsb_vehicle(msg); break; - case MAVLINK_MSG_ID_UTM_GLOBAL_POSITION: - handle_message_utm_global_position(msg); - break; - case MAVLINK_MSG_ID_COLLISION: handle_message_collision(msg); break; @@ -2540,91 +2536,6 @@ MavlinkReceiver::handle_message_adsb_vehicle(mavlink_message_t *msg) _transponder_report_pub.publish(t); } -void -MavlinkReceiver::handle_message_utm_global_position(mavlink_message_t *msg) -{ - mavlink_utm_global_position_t utm_pos; - mavlink_msg_utm_global_position_decode(msg, &utm_pos); - - bool is_self_published = false; - - -#ifndef BOARD_HAS_NO_UUID - px4_guid_t px4_guid; - board_get_px4_guid(px4_guid); - is_self_published = sizeof(px4_guid) == sizeof(utm_pos.uas_id) - && memcmp(px4_guid, utm_pos.uas_id, sizeof(px4_guid_t)) == 0; -#else - - is_self_published = msg->sysid == _mavlink->get_system_id(); -#endif /* BOARD_HAS_NO_UUID */ - - - //Ignore selfpublished UTM messages - if (is_self_published) { - return; - } - - // Convert cm/s to m/s - float vx = utm_pos.vx / 100.0f; - float vy = utm_pos.vy / 100.0f; - float vz = utm_pos.vz / 100.0f; - - transponder_report_s t{}; - t.timestamp = hrt_absolute_time(); - mav_array_memcpy(t.uas_id, utm_pos.uas_id, PX4_GUID_BYTE_LENGTH); - t.icao_address = msg->sysid; - t.lat = utm_pos.lat * 1e-7; - t.lon = utm_pos.lon * 1e-7; - t.altitude = utm_pos.alt / 1000.0f; - t.altitude_type = ADSB_ALTITUDE_TYPE_GEOMETRIC; - // UTM_GLOBAL_POSIION uses NED (north, east, down) coordinates for velocity, in cm / s. - t.heading = atan2f(vy, vx); - t.hor_velocity = sqrtf(vy * vy + vx * vx); - t.ver_velocity = -vz; - // TODO: Callsign - // For now, set it to all 0s. This is a null-terminated string, so not explicitly giving it a null - // terminator could cause problems. - memset(&t.callsign[0], 0, sizeof(t.callsign)); - t.emitter_type = ADSB_EMITTER_TYPE_UAV; // TODO: Is this correct?x2? - - // The Mavlink docs do not specify what to do if tslc (time since last communication) is out of range of - // an 8-bit int, or if this is the first communication. - // Here, I assume that if this is the first communication, tslc = 0. - // If tslc > 255, then tslc = 255. - unsigned long time_passed = (t.timestamp - _last_utm_global_pos_com) / 1000000; - - if (_last_utm_global_pos_com == 0) { - time_passed = 0; - - } else if (time_passed > UINT8_MAX) { - time_passed = UINT8_MAX; - } - - t.tslc = (uint8_t) time_passed; - - t.flags = 0; - - if (utm_pos.flags & UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE) { - t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS; - } - - if (utm_pos.flags & UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE) { - t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE; - } - - if (utm_pos.flags & UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE) { - t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING; - t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY; - } - - // Note: t.flags has deliberately NOT set VALID_CALLSIGN or VALID_SQUAWK, because UTM_GLOBAL_POSITION does not - // provide these. - _transponder_report_pub.publish(t); - - _last_utm_global_pos_com = t.timestamp; -} - void MavlinkReceiver::handle_message_collision(mavlink_message_t *msg) { diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 8e2f24e1574c..d5ea7ac22d28 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1273,6 +1273,9 @@ void Navigator::check_traffic() } } } + + _adsb_conflict.remove_expired_conflicts(); + } bool Navigator::abort_landing() @@ -1544,7 +1547,7 @@ controller. PRINT_MODULE_USAGE_NAME("navigator", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_COMMAND_DESCR("fencefile", "load a geofence file from SD card, stored at etc/geofence.txt"); - PRINT_MODULE_USAGE_COMMAND_DESCR("fake_traffic", "publishes 4 fake transponder_report_s uORB messages"); + PRINT_MODULE_USAGE_COMMAND_DESCR("fake_traffic", "publishes 24 fake transponder_report_s uORB messages"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; From e202e719b04962bb7cf87aa62f1892c580cf7055 Mon Sep 17 00:00:00 2001 From: Tero Salminen Date: Fri, 12 Apr 2024 13:40:48 +0300 Subject: [PATCH 127/652] bmp388: check bus return code after register read Check I2C/SPI bus transfer function return code after register read operation. Signed-off-by: Tero Salminen --- src/drivers/barometer/bmp388/bmp388.cpp | 40 +++++++++++++++++---- src/drivers/barometer/bmp388/bmp388.h | 2 +- src/drivers/barometer/bmp388/bmp388_i2c.cpp | 10 +++--- src/drivers/barometer/bmp388/bmp388_spi.cpp | 12 ++++--- 4 files changed, 46 insertions(+), 18 deletions(-) diff --git a/src/drivers/barometer/bmp388/bmp388.cpp b/src/drivers/barometer/bmp388/bmp388.cpp index 50c40e0686f8..04d29dbccfbb 100644 --- a/src/drivers/barometer/bmp388/bmp388.cpp +++ b/src/drivers/barometer/bmp388/bmp388.cpp @@ -68,7 +68,10 @@ BMP388::init() return -EIO; } - _chip_id = _interface->get_reg(BMP3_CHIP_ID_ADDR); + if (_interface->get_reg(BMP3_CHIP_ID_ADDR, &_chip_id) != OK) { + PX4_WARN("failed to get chip id"); + return -EIO; + } if (_chip_id != BMP388_CHIP_ID && _chip_id != BMP390_CHIP_ID) { PX4_WARN("id of your baro is not: 0x%02x or 0x%02x", BMP388_CHIP_ID, BMP390_CHIP_ID); @@ -80,7 +83,10 @@ BMP388::init() this->_item_name = "bmp390"; } - _chip_rev_id = _interface->get_reg(BMP3_REV_ID_ADDR); + if (_interface->get_reg(BMP3_REV_ID_ADDR, &_chip_rev_id) != OK) { + PX4_WARN("failed to get chip rev id"); + return -EIO; + } _cal = _interface->get_calibration(BMP3_CALIB_DATA_ADDR); @@ -204,14 +210,22 @@ BMP388::soft_reset() uint8_t status; int ret; - status = _interface->get_reg(BMP3_SENS_STATUS_REG_ADDR); + ret = _interface->get_reg(BMP3_SENS_STATUS_REG_ADDR, &status); + + if (ret != OK) { + return false; + } if (status & BMP3_CMD_RDY) { ret = _interface->set_reg(BPM3_CMD_SOFT_RESET, BMP3_CMD_ADDR); if (ret == OK) { usleep(BMP3_POST_RESET_WAIT_TIME); - status = _interface->get_reg(BMP3_ERR_REG_ADDR); + ret = _interface->get_reg(BMP3_ERR_REG_ADDR, &status); + + if (ret != OK) { + return false; + } if ((status & BMP3_CMD_ERR) == 0) { result = true; @@ -269,7 +283,9 @@ BMP388::validate_trimming_param() crc = (crc ^ 0xFF); - stored_crc = _interface->get_reg(BMP3_TRIM_CRC_DATA_ADDR); + if (_interface->get_reg(BMP3_TRIM_CRC_DATA_ADDR, &stored_crc) != OK) { + return false; + } return stored_crc == crc; } @@ -404,7 +420,12 @@ BMP388::set_op_mode(uint8_t op_mode) uint8_t op_mode_reg_val; int ret = OK; - op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR); + ret = _interface->get_reg(BMP3_PWR_CTRL_ADDR, &op_mode_reg_val); + + if (ret != OK) { + return false; + } + last_set_mode = BMP3_GET_BITS(op_mode_reg_val, BMP3_OP_MODE); /* Device needs to be put in sleep mode to transition */ @@ -420,7 +441,12 @@ BMP388::set_op_mode(uint8_t op_mode) } if (ret == OK) { - op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR); + ret = _interface->get_reg(BMP3_PWR_CTRL_ADDR, &op_mode_reg_val); + + if (ret != OK) { + return false; + } + op_mode_reg_val = BMP3_SET_BITS(op_mode_reg_val, BMP3_OP_MODE, op_mode); ret = _interface->set_reg(op_mode_reg_val, BMP3_PWR_CTRL_ADDR); diff --git a/src/drivers/barometer/bmp388/bmp388.h b/src/drivers/barometer/bmp388/bmp388.h index 2db3e2238255..a72b95aef4f1 100644 --- a/src/drivers/barometer/bmp388/bmp388.h +++ b/src/drivers/barometer/bmp388/bmp388.h @@ -292,7 +292,7 @@ class IBMP388 virtual int init() = 0; // read reg value - virtual uint8_t get_reg(uint8_t addr) = 0; + virtual int get_reg(uint8_t addr, uint8_t *value) = 0; // bulk read reg value virtual int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) = 0; diff --git a/src/drivers/barometer/bmp388/bmp388_i2c.cpp b/src/drivers/barometer/bmp388/bmp388_i2c.cpp index 0b735d35df4a..73fe0427052a 100644 --- a/src/drivers/barometer/bmp388/bmp388_i2c.cpp +++ b/src/drivers/barometer/bmp388/bmp388_i2c.cpp @@ -49,7 +49,7 @@ class BMP388_I2C: public device::I2C, public IBMP388 int init(); - uint8_t get_reg(uint8_t addr); + int get_reg(uint8_t addr, uint8_t *value); int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len); int set_reg(uint8_t value, uint8_t addr); calibration_s *get_calibration(uint8_t addr); @@ -78,12 +78,10 @@ int BMP388_I2C::init() return I2C::init(); } -uint8_t BMP388_I2C::get_reg(uint8_t addr) +int BMP388_I2C::get_reg(uint8_t addr, uint8_t *value) { - uint8_t cmd[2] = { (uint8_t)(addr), 0}; - transfer(&cmd[0], 1, &cmd[1], 1); - - return cmd[1]; + const uint8_t cmd = (uint8_t)(addr); + return transfer(&cmd, sizeof(cmd), value, 1); } int BMP388_I2C::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) diff --git a/src/drivers/barometer/bmp388/bmp388_spi.cpp b/src/drivers/barometer/bmp388/bmp388_spi.cpp index 18479a4aaf78..2970d2bc00b1 100644 --- a/src/drivers/barometer/bmp388/bmp388_spi.cpp +++ b/src/drivers/barometer/bmp388/bmp388_spi.cpp @@ -66,7 +66,7 @@ class BMP388_SPI: public device::SPI, public IBMP388 int init(); - uint8_t get_reg(uint8_t addr); + int get_reg(uint8_t addr, uint8_t *value); int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len); int set_reg(uint8_t value, uint8_t addr); calibration_s *get_calibration(uint8_t addr); @@ -95,12 +95,16 @@ int BMP388_SPI::init() return SPI::init(); }; -uint8_t BMP388_SPI::get_reg(uint8_t addr) +int BMP388_SPI::get_reg(uint8_t addr, uint8_t *value) { uint8_t cmd[2] = { (uint8_t)(addr | DIR_READ), 0}; //set MSB bit - transfer(&cmd[0], &cmd[0], 2); + int ret = transfer(&cmd[0], &cmd[0], 2); - return cmd[1]; + if (ret == OK) { + *value = cmd[1]; + } + + return ret; } int BMP388_SPI::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) From 4cf51e58332d4a7cbad0fbafa95425ecec222ead Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 22 Apr 2024 14:07:17 +0200 Subject: [PATCH 128/652] baro comp: set hpf optional --- .../baro_static_pressure_compensation_tuning.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py b/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py index 01fe5e758ca9..2629700228c3 100644 --- a/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py +++ b/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py @@ -150,7 +150,7 @@ def baroCorrection(x, v_body): return correction -def run(logfile): +def run(logfile, w_hpf): (t, v_body, baro, v_local_z, gnss_h) = getAllData(logfile) # x[0]: pcoef_xn / g @@ -162,8 +162,10 @@ def run(logfile): # Remove low ferquency part of the signal as we're only interested in the short-term errors baro_error -= baro_error[0] - sos = butter(4, 0.01, 'hp', fs=1/(t[1]-t[0]), output='sos') - baro_error = sosfilt(sos, baro_error) + + if (w_hpf > 0): + sos = butter(4, w_hpf, 'hp', fs=1/(t[1]-t[0]), output='sos') + baro_error = sosfilt(sos, baro_error) J = lambda x: np.sum(np.power(baro_error - baroCorrection(x, v_body), 2.0)) # cost function @@ -224,8 +226,10 @@ def run(logfile): # Provide parameter file path and name parser.add_argument('logfile', help='Full ulog file path, name and extension', type=str) + parser.add_argument('--hpf', help='Cuttoff frequency of high-pass filter on baro error (Hz)', type=float) args = parser.parse_args() logfile = os.path.abspath(args.logfile) # Convert to absolute path + w_hpf = 2 * np.pi * args.hpf - run(logfile) + run(logfile, w_hpf) From bfb04ddd19c4b35e5f5d671403a6f50371c4a87c Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 22 Apr 2024 12:11:53 -0400 Subject: [PATCH 129/652] CMakeLists: install_python_requirements allow --break-system-packages --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 658c32794584..82771613c9ba 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -485,7 +485,7 @@ include(package) # install python requirements using configured python add_custom_target(install_python_requirements - COMMAND ${PYTHON_EXECUTABLE} -m pip install --requirement ${PX4_SOURCE_DIR}/Tools/setup/requirements.txt + COMMAND ${PYTHON_EXECUTABLE} -m pip install --break-system-packages --requirement ${PX4_SOURCE_DIR}/Tools/setup/requirements.txt DEPENDS ${PX4_SOURCE_DIR}/Tools/setup/requirements.txt USES_TERMINAL ) From 26831282058512071ccc589f2fed7b2de8353d75 Mon Sep 17 00:00:00 2001 From: fury1895 Date: Tue, 23 Apr 2024 13:36:12 +0200 Subject: [PATCH 130/652] PM Selector Auterion: remove INA226_SHUNT value reset (skynode only) --- .../pm_selector_auterion/PowerMonitorSelectorAuterion.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp b/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp index 97c89bea611d..baa54bcd7038 100644 --- a/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp +++ b/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp @@ -87,14 +87,6 @@ void PowerMonitorSelectorAuterion::Run() int ret_val = ina226_probe(i); if (ret_val == PX4_OK) { - - float current_shunt_value = 0.0f; - param_get(param_find("INA226_SHUNT"), ¤t_shunt_value); - - if (fabsf(current_shunt_value - _sensors[i].shunt_value) > FLT_EPSILON) { - param_set(param_find("INA226_SHUNT"), &(_sensors[i].shunt_value)); - } - char bus_number[4] = {0}; itoa(_sensors[i].bus_number, bus_number, 10); const char *start_argv[] { From 59232c27ae74399a073ce8833166b55ad2724754 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 27 Feb 2024 13:23:00 +0100 Subject: [PATCH 131/652] autopilot_tester: use normal VTOL mission for airspeed blockage test Signed-off-by: Silvan Fuhrer --- .../mavsdk_tests/test_vtol_loiter_airspeed_failure_blockage.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/mavsdk_tests/test_vtol_loiter_airspeed_failure_blockage.cpp b/test/mavsdk_tests/test_vtol_loiter_airspeed_failure_blockage.cpp index 1b8266d72b9a..5dafefe71443 100644 --- a/test/mavsdk_tests/test_vtol_loiter_airspeed_failure_blockage.cpp +++ b/test/mavsdk_tests/test_vtol_loiter_airspeed_failure_blockage.cpp @@ -47,7 +47,7 @@ TEST_CASE("Fly VTOL Loiter with airspeed failure", "[vtol_airspeed_fail]") const float takeoff_altitude = 10.f; tester.set_takeoff_altitude(takeoff_altitude); - tester.load_qgc_mission_raw_and_move_here("test/mavsdk_tests/vtol_mission_straight_south.plan"); + tester.load_qgc_mission_raw_and_move_here("test/mavsdk_tests/vtol_mission.plan"); tester.arm(); tester.takeoff(); From 818e31833430179c1946b4171b19f51207e5a20e Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 27 Feb 2024 13:24:05 +0100 Subject: [PATCH 132/652] autopilot_tester: reduce mission distance for wind world Signed-off-by: Silvan Fuhrer --- test/mavsdk_tests/vtol_mission_straight_south.plan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/mavsdk_tests/vtol_mission_straight_south.plan b/test/mavsdk_tests/vtol_mission_straight_south.plan index 38e4edcc5103..fa6d37472b7a 100644 --- a/test/mavsdk_tests/vtol_mission_straight_south.plan +++ b/test/mavsdk_tests/vtol_mission_straight_south.plan @@ -49,7 +49,7 @@ 0, 0, null, - 47.38497919751799, + 47.392, 8.54578066404548, 30 ], From 97191bd60f536b4add2e27e3b2124a375e465e17 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 27 Feb 2024 13:25:17 +0100 Subject: [PATCH 133/652] autopilot_tester: for mission end timeout check take speed factor into account And increase the (simulation time) timeouts. Signed-off-by: Silvan Fuhrer --- test/mavsdk_tests/autopilot_tester.cpp | 22 ++++++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/test/mavsdk_tests/autopilot_tester.cpp b/test/mavsdk_tests/autopilot_tester.cpp index e1bbe9efde85..f3ba47f87176 100644 --- a/test/mavsdk_tests/autopilot_tester.cpp +++ b/test/mavsdk_tests/autopilot_tester.cpp @@ -271,9 +271,16 @@ void AutopilotTester::execute_mission() REQUIRE(poll_condition_with_timeout( [this]() { return _mission->start_mission() == Mission::Result::Success; }, std::chrono::seconds(3))); - // TODO: Adapt time limit based on mission size, flight speed, sim speed factor, etc. + float speed_factor = 1.0f; - wait_for_mission_finished(std::chrono::seconds(90)); + if (_info != nullptr) { + speed_factor = _info->get_speed_factor().second; + } + + const float mission_finish_waiting_time_in_simulation_s = 500.f; + float mission_finish_waiting_time_in_real_s = mission_finish_waiting_time_in_simulation_s / speed_factor; + + wait_for_mission_finished(std::chrono::seconds(static_cast(mission_finish_waiting_time_in_real_s))); } void AutopilotTester::execute_mission_and_lose_gps() @@ -388,9 +395,16 @@ void AutopilotTester::execute_mission_raw() { REQUIRE(_mission->start_mission() == Mission::Result::Success); - // TODO: Adapt time limit based on mission size, flight speed, sim speed factor, etc. + float speed_factor = 1.0f; + + if (_info != nullptr) { + speed_factor = _info->get_speed_factor().second; + } + + const float waiting_time_simulation_time_s = 300.f; // currently this is tuned for the VTOL wind test + float waiting_time_absolute_s = waiting_time_simulation_time_s / speed_factor; - wait_for_mission_raw_finished(std::chrono::seconds(120)); + wait_for_mission_raw_finished(std::chrono::seconds(static_cast(waiting_time_absolute_s))); } void AutopilotTester::execute_rtl() From 8bf1cf0b15672963d341b7878c7dfae8329c044a Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 23 Apr 2024 16:03:38 +0200 Subject: [PATCH 134/652] ekf2_params: reduce "short" description --- src/modules/ekf2/module.yaml | 124 +++++++++++++++++----------------- validation/module_schema.yaml | 4 +- 2 files changed, 64 insertions(+), 64 deletions(-) diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 81c067a36d12..9f2f83519637 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -114,8 +114,7 @@ parameters: decimal: 1 EKF2_AVEL_DELAY: description: - short: Auxiliary Velocity Estimate (e.g from a landing target) delay relative - to IMU measurements + short: Auxiliary Velocity Estimate delay relative to IMU measurements type: float default: 5 min: 0 @@ -582,7 +581,8 @@ parameters: max: 3 EKF2_NOAID_TOUT: description: - short: Maximum lapsed time from last fusion of measurements that constrain + short: Maximum inertial dead-reckoning time + long: Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid type: int32 @@ -655,8 +655,8 @@ parameters: decimal: 1 EKF2_EVP_NOISE: description: - short: Measurement noise for vision position observations used to lower bound - or replace the uncertainty included in the message + short: Measurement noise for vision position measurements + long: Used to lower bound or replace the uncertainty included in the message type: float default: 0.1 min: 0.01 @@ -664,8 +664,8 @@ parameters: decimal: 2 EKF2_EVV_NOISE: description: - short: Measurement noise for vision velocity observations used to lower bound - or replace the uncertainty included in the message + short: Measurement noise for vision velocity measurements + long: Used to lower bound or replace the uncertainty included in the message type: float default: 0.1 min: 0.01 @@ -673,8 +673,8 @@ parameters: decimal: 2 EKF2_EVA_NOISE: description: - short: Measurement noise for vision angle observations used to lower bound - or replace the uncertainty included in the message + short: Measurement noise for vision angle measurements + long: Used to lower bound or replace the uncertainty included in the message type: float default: 0.1 min: 0.05 @@ -697,7 +697,8 @@ parameters: default: 0 EKF2_OF_N_MIN: description: - short: Measurement noise for the optical flow sensor when it's reported quality + short: Optical flow minimum noise + long: Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum type: float default: 0.15 @@ -706,9 +707,9 @@ parameters: decimal: 2 EKF2_OF_N_MAX: description: - short: Measurement noise for the optical flow sensor - long: '(when it''s reported quality metric is at the minimum set by EKF2_OF_QMIN). - The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN' + short: Optical flow maximum noise + long: Measurement noise for the optical flow sensor when it's reported quality + metric is at the minimum type: float default: 0.5 min: 0.05 @@ -716,7 +717,8 @@ parameters: decimal: 2 EKF2_OF_QMIN: description: - short: Optical Flow data will only be used in air if the sensor reports a + short: In air optical flow minimum quality + long: Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN type: int32 default: 1 @@ -724,7 +726,8 @@ parameters: max: 255 EKF2_OF_QMIN_GND: description: - short: Optical Flow data will only be used on the ground if the sensor reports + short: On ground optical flow minimum quality + long: Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND type: int32 default: 0 @@ -742,8 +745,7 @@ parameters: decimal: 1 EKF2_TERR_NOISE: description: - short: Terrain altitude process noise - accounts for instability in vehicle - height estimate + short: Terrain altitude process noise type: float default: 5.0 min: 0.5 @@ -759,120 +761,120 @@ parameters: decimal: 2 EKF2_IMU_POS_X: description: - short: X position of IMU in body frame (forward axis with origin relative - to vehicle centre of gravity) + short: X position of IMU in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_IMU_POS_Y: description: - short: Y position of IMU in body frame (right axis with origin relative to - vehicle centre of gravity) + short: Y position of IMU in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_IMU_POS_Z: description: - short: Z position of IMU in body frame (down axis with origin relative to - vehicle centre of gravity) + short: Z position of IMU in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_GPS_POS_X: description: - short: X position of GPS antenna in body frame (forward axis with origin relative - to vehicle centre of gravity) + short: X position of GPS antenna in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_GPS_POS_Y: description: - short: Y position of GPS antenna in body frame (right axis with origin relative - to vehicle centre of gravity) + short: Y position of GPS antenna in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_GPS_POS_Z: description: - short: Z position of GPS antenna in body frame (down axis with origin relative - to vehicle centre of gravity) + short: Z position of GPS antenna in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_RNG_POS_X: description: - short: X position of range finder origin in body frame (forward axis with - origin relative to vehicle centre of gravity) + short: X position of range finder origin in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_RNG_POS_Y: description: - short: Y position of range finder origin in body frame (right axis with origin - relative to vehicle centre of gravity) + short: Y position of range finder origin in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_RNG_POS_Z: description: - short: Z position of range finder origin in body frame (down axis with origin - relative to vehicle centre of gravity) + short: Z position of range finder origin in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_OF_POS_X: description: - short: X position of optical flow focal point in body frame (forward axis - with origin relative to vehicle centre of gravity) + short: X position of optical flow focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_OF_POS_Y: description: - short: Y position of optical flow focal point in body frame (right axis with - origin relative to vehicle centre of gravity) + short: Y position of optical flow focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_OF_POS_Z: description: - short: Z position of optical flow focal point in body frame (down axis with - origin relative to vehicle centre of gravity) + short: Z position of optical flow focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_EV_POS_X: description: - short: X position of VI sensor focal point in body frame (forward axis with - origin relative to vehicle centre of gravity) + short: X position of VI sensor focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_EV_POS_Y: description: - short: Y position of VI sensor focal point in body frame (right axis with - origin relative to vehicle centre of gravity) + short: Y position of VI sensor focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 EKF2_EV_POS_Z: description: - short: Z position of VI sensor focal point in body frame (down axis with origin - relative to vehicle centre of gravity) + short: Z position of VI sensor focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m @@ -908,8 +910,8 @@ parameters: decimal: 2 EKF2_TAU_POS: description: - short: Time constant of the position output prediction and smoothing filter. - Controls how tightly the output track the EKF states + short: Output predictor position time constant + long: Controls how tightly the output track the EKF states type: float default: 0.25 min: 0.1 @@ -968,8 +970,7 @@ parameters: unit: m/s EKF2_RNG_A_HMAX: description: - short: Maximum absolute altitude (height above ground level) allowed for conditional - range aid mode + short: Maximum height above ground allowed for conditional range aid mode long: If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). @@ -990,7 +991,8 @@ parameters: max: 5.0 EKF2_RNG_QLTY_T: description: - short: Minimum duration during which the reported range finder signal quality + short: Minumum range validity period + long: Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s) type: float default: 1.0 @@ -1041,9 +1043,9 @@ parameters: default: 0 EKF2_DRAG_NOISE: description: - short: Specific drag force observation noise variance used by the multi-rotor - specific drag force model - long: Increasing this makes the multi-rotor wind estimates adjust more slowly. + short: Specific drag force observation noise variance + long: Used by the multi-rotor specific drag force model. + Increasing this makes the multi-rotor wind estimates adjust more slowly. type: float default: 2.5 min: 0.5 @@ -1082,7 +1084,7 @@ parameters: decimal: 1 EKF2_MCOEF: description: - short: Propeller momentum drag coefficient used for multi-rotor wind estimation + short: Propeller momentum drag coefficient for multi-rotor wind estimation long: This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect @@ -1104,8 +1106,7 @@ parameters: decimal: 2 EKF2_ASPD_MAX: description: - short: Upper limit on airspeed along individual axes used to correct baro - for position error effects + short: Maximum airspeed used for baro static pressure compensation type: float default: 20.0 min: 5.0 @@ -1209,8 +1210,7 @@ parameters: decimal: 1 EKF2_ABL_TAU: description: - short: Time constant used by acceleration and angular rate magnitude checks - used to inhibit accel bias learning + short: Accel bias learning inhibit time constant long: The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay. @@ -1333,8 +1333,8 @@ parameters: decimal: 1 EKF2_AGP_NOISE: description: - short: Measurement noise for aux global position observations used to lower - bound or replace the uncertainty included in the message + short: Measurement noise for aux global position measurements + long: Used to lower bound or replace the uncertainty included in the message type: float default: 0.9 min: 0.01 diff --git a/validation/module_schema.yaml b/validation/module_schema.yaml index 3d16eedf31eb..827087174e8a 100644 --- a/validation/module_schema.yaml +++ b/validation/module_schema.yaml @@ -142,13 +142,13 @@ parameters: # (Extend this list as needed) type: string allowed: [ - '%', 'Hz', 'mAh', + '%', 'Hz', '1/s', 'mAh', 'rad', '%/rad', 'rad/s', 'rad/s^2', '%/rad/s', 'rad s^2/m','rad s/m', 'bit/s', 'B/s', 'deg', 'deg*1e7', 'deg/s', 'deg/s^2', 'celcius', 'gauss', 'gauss/s', 'mgauss', 'mgauss^2', 'hPa', 'kg', 'kg/m^2', 'kg m^2', 'kg/m^3', - 'mm', 'm', 'm/s', 'm^2', 'm/s^2', 'm/s^3', 'm/s^2/sqrt(Hz)', 'm/s/rad', + 'mm', 'm', 'm/s', 'm^2', 'm/s^2', 'm/s^3', 'm/s^2/sqrt(Hz)', 'm/s/rad', 'g0', 'Ohm', 'V', 'A', 'us', 'ms', 's', 'S', 'A/%', '(m/s^2)^2', 'm/m', 'tan(rad)^2', '(m/s)^2', 'm/rad', From b508df39a29a274a787099d974628f9b92ef4844 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 24 Apr 2024 11:09:10 +0200 Subject: [PATCH 135/652] imu consistency: don't scale param threshold --- .../checks/imuConsistencyCheck.cpp | 16 ++-------------- 1 file changed, 2 insertions(+), 14 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/imuConsistencyCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/imuConsistencyCheck.cpp index ca292d7b14da..ce6e8d4412ff 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/imuConsistencyCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/imuConsistencyCheck.cpp @@ -48,13 +48,7 @@ void ImuConsistencyChecks::checkAndReport(const Context &context, Report &report const float accel_inconsistency_m_s_s = imu.accel_inconsistency_m_s_s[i]; - NavModes required_groups = NavModes::None; - if (accel_inconsistency_m_s_s > _param_com_arm_imu_acc.get()) { - required_groups = NavModes::All; - } - - if (accel_inconsistency_m_s_s > _param_com_arm_imu_acc.get() * 0.8f) { /* EVENT * @description * Check the calibration. @@ -66,7 +60,7 @@ void ImuConsistencyChecks::checkAndReport(const Context &context, Report &report * This check can be configured via COM_ARM_IMU_ACC parameter. * */ - reporter.armingCheckFailure(required_groups, health_component_t::accel, + reporter.armingCheckFailure(NavModes::All, health_component_t::accel, events::ID("check_imu_accel_inconsistent"), events::Log::Warning, "Accel {1} inconsistent", i, accel_inconsistency_m_s_s, _param_com_arm_imu_acc.get()); @@ -85,13 +79,7 @@ void ImuConsistencyChecks::checkAndReport(const Context &context, Report &report const float gyro_inconsistency_rad_s = imu.gyro_inconsistency_rad_s[i]; - NavModes required_groups = NavModes::None; - if (gyro_inconsistency_rad_s > _param_com_arm_imu_gyr.get()) { - required_groups = NavModes::All; - } - - if (gyro_inconsistency_rad_s > _param_com_arm_imu_gyr.get() * 0.5f) { /* EVENT * @description * Check the calibration. @@ -103,7 +91,7 @@ void ImuConsistencyChecks::checkAndReport(const Context &context, Report &report * This check can be configured via COM_ARM_IMU_GYR parameter. * */ - reporter.armingCheckFailure(required_groups, health_component_t::gyro, + reporter.armingCheckFailure(NavModes::All, health_component_t::gyro, events::ID("check_imu_gyro_inconsistent"), events::Log::Warning, "Gyro {1} inconsistent", i, gyro_inconsistency_rad_s, _param_com_arm_imu_gyr.get()); From eb59bb9de90547ed9271c3927db9fde202cc7d25 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 22 Apr 2024 13:29:01 -0400 Subject: [PATCH 136/652] simulation/gz_bridge: eliminate implicit float conversion --- src/modules/simulation/gz_bridge/GZMixingInterfaceWheel.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/simulation/gz_bridge/GZMixingInterfaceWheel.cpp b/src/modules/simulation/gz_bridge/GZMixingInterfaceWheel.cpp index 2fed14dfe716..2198bacbaaf3 100644 --- a/src/modules/simulation/gz_bridge/GZMixingInterfaceWheel.cpp +++ b/src/modules/simulation/gz_bridge/GZMixingInterfaceWheel.cpp @@ -78,8 +78,8 @@ bool GZMixingInterfaceWheel::updateOutputs(bool stop_wheels, uint16_t outputs[MA for (unsigned i = 0; i < active_output_count; i++) { // Offsetting the output allows for negative values despite unsigned integer to reverse the wheels - static constexpr float output_offset = 100.0f; - float scaled_output = (float)outputs[i] - output_offset; + static constexpr double output_offset = 100.0; + double scaled_output = (double)outputs[i] - output_offset; wheel_velocity_message.set_velocity(i, scaled_output); } From 65c7e034dcee0c6c49bf902c115f6138f4fd3143 Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Wed, 24 Apr 2024 11:17:30 +0200 Subject: [PATCH 137/652] VSCode: add EditorConfig extension to recommended and devcontainer.json --- .devcontainer/devcontainer.json | 1 + .vscode/extensions.json | 1 + 2 files changed, 2 insertions(+) diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index a9ac652d18b9..4e9788b228bd 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -15,6 +15,7 @@ "extensions": [ "chiehyu.vscode-astyle", "dan-c-underwood.arm", + "editorconfig.editorconfig", "fredericbonnet.cmake-test-adapter", "github.vscode-pull-request-github", "marus25.cortex-debug", diff --git a/.vscode/extensions.json b/.vscode/extensions.json index ec49a0c75fd1..3da9f2675427 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -4,6 +4,7 @@ "recommendations": [ "chiehyu.vscode-astyle", "dan-c-underwood.arm", + "editorconfig.editorconfig", "fredericbonnet.cmake-test-adapter", "github.vscode-pull-request-github", "marus25.cortex-debug", From 0f6f4c5b0785dc7dee13737fe11cd5b853b622fa Mon Sep 17 00:00:00 2001 From: dirksavage88 Date: Mon, 22 Apr 2024 13:43:32 -0400 Subject: [PATCH 138/652] fix to orientation offsets for scaled yaw, removed unused param Signed-off-by: dirksavage88 --- .../lightware_sf45_serial.cpp | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp b/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp index 1a8c9534283a..5ca35ac66200 100755 --- a/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp +++ b/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp @@ -157,7 +157,6 @@ int SF45LaserSerial::collect() int64_t read_elapsed = hrt_elapsed_time(&_last_read); int ret; /* the buffer for read chars is buflen minus null termination */ - param_get(param_find("SF45_CP_LIMIT"), &_collision_constraint); uint8_t readbuf[SF45_MAX_PAYLOAD]; float distance_m = -1.0f; @@ -664,6 +663,8 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m) } + scaled_yaw = raw_yaw * SF45_SCALE_FACTOR; + // The sensor is facing downward, so the sensor is flipped about it's x-axis -inverse of each yaw angle if (_orient_cfg == 1) { raw_yaw = raw_yaw * -1; @@ -674,29 +675,27 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m) break; case 1: - if (raw_yaw > 180) { - raw_yaw = raw_yaw - 180; + if (scaled_yaw > 180) { + scaled_yaw = scaled_yaw - 180; } else { - raw_yaw = raw_yaw + 180; // rotation facing aft + scaled_yaw = scaled_yaw + 180; // rotation facing aft } break; case 2: - raw_yaw = raw_yaw + 90; // rotation facing right + scaled_yaw = scaled_yaw + 90; // rotation facing right break; case 3: - raw_yaw = raw_yaw - 90; // rotation facing left + scaled_yaw = scaled_yaw - 90; // rotation facing left break; default: break; } - scaled_yaw = raw_yaw * SF45_SCALE_FACTOR; - // Convert to meters for rangefinder update *distance_m = raw_distance * SF45_SCALE_FACTOR; obstacle_dist_cm = (uint16_t)raw_distance; From 6a3e57d428b6fd15dea8d6ac4be92139a5375f64 Mon Sep 17 00:00:00 2001 From: dirksavage88 Date: Mon, 22 Apr 2024 15:47:28 -0400 Subject: [PATCH 139/652] Shift vertical orientation above scaling yaw operation, cp angle sign change Signed-off-by: dirksavage88 --- .../lightware_sf45_serial/lightware_sf45_serial.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp b/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp index 5ca35ac66200..e28bcdfc2b62 100755 --- a/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp +++ b/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial.cpp @@ -75,7 +75,7 @@ SF45LaserSerial::SF45LaserSerial(const char *port, uint8_t rotation) : // populate obstacle map members _obstacle_map_msg.frame = obstacle_distance_s::MAV_FRAME_BODY_FRD; _obstacle_map_msg.increment = 5; - _obstacle_map_msg.angle_offset = -2.5; + _obstacle_map_msg.angle_offset = 2.5; _obstacle_map_msg.min_distance = UINT16_MAX; _obstacle_map_msg.max_distance = 5000; @@ -663,13 +663,14 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m) } - scaled_yaw = raw_yaw * SF45_SCALE_FACTOR; - // The sensor is facing downward, so the sensor is flipped about it's x-axis -inverse of each yaw angle if (_orient_cfg == 1) { raw_yaw = raw_yaw * -1; } + // SF45/B product guide {Data output bit: 8 Description: "Yaw angle [1/100 deg] size: int16}" + scaled_yaw = raw_yaw * SF45_SCALE_FACTOR; + switch (_yaw_cfg) { case 0: break; From 69e082c83def3d3756257210492b9529e5b24984 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Wed, 24 Apr 2024 12:01:18 -0800 Subject: [PATCH 140/652] drivers/magnetometer: new ST IIS2MDC Magnetometer driver --- src/drivers/drv_sensor.h | 1 + src/drivers/magnetometer/CMakeLists.txt | 1 + src/drivers/magnetometer/Kconfig | 1 + src/drivers/magnetometer/st/Kconfig | 3 + .../magnetometer/st/iis2mdc/CMakeLists.txt | 45 ++++++ src/drivers/magnetometer/st/iis2mdc/Kconfig | 5 + .../magnetometer/st/iis2mdc/iis2mdc.cpp | 137 ++++++++++++++++++ src/drivers/magnetometer/st/iis2mdc/iis2mdc.h | 95 ++++++++++++ .../magnetometer/st/iis2mdc/iis2mdc_i2c.cpp | 97 +++++++++++++ .../magnetometer/st/iis2mdc/iis2mdc_main.cpp | 116 +++++++++++++++ 10 files changed, 501 insertions(+) create mode 100644 src/drivers/magnetometer/st/Kconfig create mode 100644 src/drivers/magnetometer/st/iis2mdc/CMakeLists.txt create mode 100644 src/drivers/magnetometer/st/iis2mdc/Kconfig create mode 100644 src/drivers/magnetometer/st/iis2mdc/iis2mdc.cpp create mode 100644 src/drivers/magnetometer/st/iis2mdc/iis2mdc.h create mode 100644 src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp create mode 100644 src/drivers/magnetometer/st/iis2mdc/iis2mdc_main.cpp diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index fc6265ba4b60..4b1d18e76ba0 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -64,6 +64,7 @@ #define DRV_MAG_DEVTYPE_IST8308 0x0B #define DRV_MAG_DEVTYPE_LIS2MDL 0x0C #define DRV_MAG_DEVTYPE_MMC5983MA 0x0D +#define DRV_MAG_DEVTYPE_IIS2MDC 0x0E #define DRV_IMU_DEVTYPE_LSM303D 0x11 diff --git a/src/drivers/magnetometer/CMakeLists.txt b/src/drivers/magnetometer/CMakeLists.txt index 6eb5bbe49262..07bf93cddc2b 100644 --- a/src/drivers/magnetometer/CMakeLists.txt +++ b/src/drivers/magnetometer/CMakeLists.txt @@ -41,4 +41,5 @@ add_subdirectory(lis3mdl) add_subdirectory(lsm303agr) add_subdirectory(memsic) add_subdirectory(rm3100) +add_subdirectory(st) add_subdirectory(vtrantech) diff --git a/src/drivers/magnetometer/Kconfig b/src/drivers/magnetometer/Kconfig index 39ed3db84a3b..018b89502b26 100644 --- a/src/drivers/magnetometer/Kconfig +++ b/src/drivers/magnetometer/Kconfig @@ -14,6 +14,7 @@ menu "Magnetometer" select DRIVERS_MAGNETOMETER_RM3100 select DRIVERS_MAGNETOMETER_VTRANTECH_VCM1193L select DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA + select DRIVERS_MAGNETOMETER_ST_IIS2MDC ---help--- Enable default set of magnetometer drivers rsource "*/Kconfig" diff --git a/src/drivers/magnetometer/st/Kconfig b/src/drivers/magnetometer/st/Kconfig new file mode 100644 index 000000000000..f5acb5b61698 --- /dev/null +++ b/src/drivers/magnetometer/st/Kconfig @@ -0,0 +1,3 @@ +menu "ST" + rsource "*/Kconfig" +endmenu diff --git a/src/drivers/magnetometer/st/iis2mdc/CMakeLists.txt b/src/drivers/magnetometer/st/iis2mdc/CMakeLists.txt new file mode 100644 index 000000000000..041f142ca1a3 --- /dev/null +++ b/src/drivers/magnetometer/st/iis2mdc/CMakeLists.txt @@ -0,0 +1,45 @@ +############################################################################ +# +# 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_module( + MODULE drivers__magnetometer__st__iis2mdc + MAIN iis2mdc + COMPILE_FLAGS + # -DDEBUG_BUILD + SRCS + iis2mdc_i2c.cpp + iis2mdc_main.cpp + iis2mdc.cpp + DEPENDS + drivers_magnetometer + px4_work_queue + ) diff --git a/src/drivers/magnetometer/st/iis2mdc/Kconfig b/src/drivers/magnetometer/st/iis2mdc/Kconfig new file mode 100644 index 000000000000..fdd140c17eb6 --- /dev/null +++ b/src/drivers/magnetometer/st/iis2mdc/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_ST_IIS2MDC + bool "iis2mdc" + default n + ---help--- + Enable support for iis2mdc diff --git a/src/drivers/magnetometer/st/iis2mdc/iis2mdc.cpp b/src/drivers/magnetometer/st/iis2mdc/iis2mdc.cpp new file mode 100644 index 000000000000..23ce5ac5390b --- /dev/null +++ b/src/drivers/magnetometer/st/iis2mdc/iis2mdc.cpp @@ -0,0 +1,137 @@ +/**************************************************************************** + * + * 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 "iis2mdc.h" + +using namespace time_literals; + +IIS2MDC::IIS2MDC(device::Device *interface, const I2CSPIDriverConfig &config) : + I2CSPIDriver(config), + _interface(interface), + _px4_mag(interface->get_device_id(), config.rotation), + _sample_count(perf_alloc(PC_COUNT, "iis2mdc_read")), + _comms_errors(perf_alloc(PC_COUNT, "iis2mdc_comms_errors")) +{} + +IIS2MDC::~IIS2MDC() +{ + perf_free(_sample_count); + perf_free(_comms_errors); + delete _interface; +} + +int IIS2MDC::init() +{ + if (hrt_absolute_time() < 20_ms) { + px4_usleep(20_ms); // ~10ms power-on time + } + + write_register(IIS2MDC_ADDR_CFG_REG_A, MD_CONTINUOUS | ODR_100 | COMP_TEMP_EN); + write_register(IIS2MDC_ADDR_CFG_REG_B, OFF_CANC); + write_register(IIS2MDC_ADDR_CFG_REG_C, BDU); + + _px4_mag.set_scale(100.f / 65535.f); // +/- 50 Gauss, 16bit + + ScheduleDelayed(20_ms); + + return PX4_OK; +} + +void IIS2MDC::RunImpl() +{ + uint8_t status = read_register(IIS2MDC_ADDR_STATUS_REG); + + if (status & IIS2MDC_STATUS_REG_READY) { + SensorData data = {}; + + if (read_register_block(&data) == PX4_OK) { + int16_t x = int16_t((data.xout1 << 8) | data.xout0); + int16_t y = int16_t((data.yout1 << 8) | data.yout0); + int16_t z = -int16_t((data.zout1 << 8) | data.zout0); + int16_t t = int16_t((data.tout1 << 8) | data.tout0); + // 16 bits twos complement with a sensitivity of 8 LSB/°C. Typically, the output zero level corresponds to 25 °C. + _px4_mag.set_temperature(float(t) / 8.f + 25.f); + _px4_mag.update(hrt_absolute_time(), x, y, z); + _px4_mag.set_error_count(perf_event_count(_comms_errors)); + perf_count(_sample_count); + + } else { + PX4_DEBUG("read failed"); + perf_count(_comms_errors); + } + + } else { + PX4_DEBUG("not ready: %u", status); + perf_count(_comms_errors); + } + + ScheduleDelayed(10_ms); +} + +uint8_t IIS2MDC::read_register_block(SensorData *data) +{ + uint8_t reg = IIS2MDC_ADDR_OUTX_L_REG; + + if (_interface->read(reg, data, sizeof(SensorData)) != PX4_OK) { + perf_count(_comms_errors); + + return PX4_ERROR; + } + + return PX4_OK; +} + +uint8_t IIS2MDC::read_register(uint8_t reg) +{ + uint8_t value = 0; + + if (_interface->read(reg, &value, sizeof(value)) != PX4_OK) { + perf_count(_comms_errors); + } + + return value; +} + +void IIS2MDC::write_register(uint8_t reg, uint8_t value) +{ + if (_interface->write(reg, &value, sizeof(value)) != PX4_OK) { + perf_count(_comms_errors); + } +} + +void IIS2MDC::print_status() +{ + I2CSPIDriverBase::print_status(); + perf_print_counter(_sample_count); + perf_print_counter(_comms_errors); +} diff --git a/src/drivers/magnetometer/st/iis2mdc/iis2mdc.h b/src/drivers/magnetometer/st/iis2mdc/iis2mdc.h new file mode 100644 index 000000000000..40da40469d69 --- /dev/null +++ b/src/drivers/magnetometer/st/iis2mdc/iis2mdc.h @@ -0,0 +1,95 @@ +/**************************************************************************** + * + * 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 + +// IIS2MDC Registers +#define IIS2MDC_ADDR_CFG_REG_A 0x60 +#define IIS2MDC_ADDR_CFG_REG_B 0x61 +#define IIS2MDC_ADDR_CFG_REG_C 0x62 +#define IIS2MDC_ADDR_STATUS_REG 0x67 +#define IIS2MDC_ADDR_OUTX_L_REG 0x68 +#define IIS2MDC_ADDR_WHO_AM_I 0x4F + +// IIS2MDC Definitions +#define IIS2MDC_WHO_AM_I 0b01000000 +#define IIS2MDC_STATUS_REG_READY 0b00001111 +// CFG_REG_A +#define COMP_TEMP_EN (1 << 7) +#define MD_CONTINUOUS (0 << 0) +#define ODR_100 ((1 << 3) | (1 << 2)) +// CFG_REG_B +#define OFF_CANC (1 << 1) +// CFG_REG_C +#define BDU (1 << 4) + +extern device::Device *IIS2MDC_I2C_interface(const I2CSPIDriverConfig &config); + +class IIS2MDC : public I2CSPIDriver +{ +public: + IIS2MDC(device::Device *interface, const I2CSPIDriverConfig &config); + virtual ~IIS2MDC(); + + struct SensorData { + uint8_t xout0; + uint8_t xout1; + uint8_t yout0; + uint8_t yout1; + uint8_t zout0; + uint8_t zout1; + uint8_t tout0; + uint8_t tout1; + }; + + static I2CSPIDriverBase *instantiate(const I2CSPIDriverConfig &config, int runtime_instance); + static void print_usage(); + + int init(); + void print_status() override; + + void RunImpl(); + +private: + uint8_t read_register_block(SensorData *data); + uint8_t read_register(uint8_t reg); + void write_register(uint8_t reg, uint8_t value); + + device::Device *_interface; + PX4Magnetometer _px4_mag; + perf_counter_t _sample_count; + perf_counter_t _comms_errors; +}; diff --git a/src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp b/src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp new file mode 100644 index 000000000000..c3cd02813c19 --- /dev/null +++ b/src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp @@ -0,0 +1,97 @@ +/**************************************************************************** + * + * 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 "iis2mdc.h" +#include + +class IIS2MDC_I2C : public device::I2C +{ +public: + IIS2MDC_I2C(const I2CSPIDriverConfig &config); + virtual ~IIS2MDC_I2C() = default; + + virtual int read(unsigned address, void *data, unsigned count) override; + virtual int write(unsigned address, void *data, unsigned count) override; + +protected: + virtual int probe(); +}; + +IIS2MDC_I2C::IIS2MDC_I2C(const I2CSPIDriverConfig &config) : + I2C(config) +{ +} + +int IIS2MDC_I2C::probe() +{ + uint8_t data = 0; + + if (read(IIS2MDC_ADDR_WHO_AM_I, &data, 1)) { + DEVICE_DEBUG("read_reg fail"); + return -EIO; + } + + if (data != IIS2MDC_WHO_AM_I) { + DEVICE_DEBUG("IIS2MDC bad ID: %02x", data); + return -EIO; + } + + _retries = 1; + + return OK; +} + +int IIS2MDC_I2C::read(unsigned address, void *data, unsigned count) +{ + uint8_t cmd = address; + return transfer(&cmd, 1, (uint8_t *)data, count); +} + +int IIS2MDC_I2C::write(unsigned address, void *data, unsigned count) +{ + uint8_t buf[32]; + + if (sizeof(buf) < (count + 1)) { + return -EIO; + } + + buf[0] = address; + memcpy(&buf[1], data, count); + + return transfer(&buf[0], count + 1, nullptr, 0); +} + +device::Device *IIS2MDC_I2C_interface(const I2CSPIDriverConfig &config) +{ + return new IIS2MDC_I2C(config); +} diff --git a/src/drivers/magnetometer/st/iis2mdc/iis2mdc_main.cpp b/src/drivers/magnetometer/st/iis2mdc/iis2mdc_main.cpp new file mode 100644 index 000000000000..09ff5eceff86 --- /dev/null +++ b/src/drivers/magnetometer/st/iis2mdc/iis2mdc_main.cpp @@ -0,0 +1,116 @@ +/**************************************************************************** + * + * 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 "iis2mdc.h" +#include + +I2CSPIDriverBase *IIS2MDC::instantiate(const I2CSPIDriverConfig &config, int runtime_instance) +{ + device::Device *interface = IIS2MDC_I2C_interface(config); + + if (interface == nullptr) { + PX4_ERR("alloc failed"); + return nullptr; + } + + if (interface->init() != OK) { + delete interface; + PX4_DEBUG("no device on bus %i (devid 0x%lx)", config.bus, config.spi_devid); + return nullptr; + } + + IIS2MDC *dev = new IIS2MDC(interface, config); + + if (dev == nullptr) { + delete interface; + return nullptr; + } + + if (OK != dev->init()) { + delete dev; + return nullptr; + } + + return dev; +} + +void IIS2MDC::print_usage() +{ + PRINT_MODULE_USAGE_NAME("iis2mdc", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("magnetometer"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false); + PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x30); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +extern "C" int iis2mdc_main(int argc, char *argv[]) +{ + using ThisDriver = IIS2MDC; + int ch; + BusCLIArguments cli{true, false}; + cli.i2c_address = 0x1E; + cli.default_i2c_frequency = 400000; + + while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { + switch (ch) { + case 'R': + cli.rotation = (enum Rotation)atoi(cli.optArg()); + break; + } + } + + const char *verb = cli.optArg(); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_IIS2MDC); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; +} From f543951e107517f0fa5a4a1811c9c25d8f8be09f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 10 Apr 2024 11:10:50 +0200 Subject: [PATCH 141/652] commander: set correct health component when reporting errors --- .../commander/HealthAndArmingChecks/checks/modeCheck.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp index 598531a0da9b..8e3c0e3a5a49 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp @@ -58,7 +58,7 @@ void ModeChecks::checkAndReport(const Context &context, Report &reporter) * @description * Wait until the estimator initialized */ - reporter.armingCheckFailure((NavModes)reporter.failsafeFlags().mode_req_attitude, health_component_t::system, + reporter.armingCheckFailure((NavModes)reporter.failsafeFlags().mode_req_attitude, health_component_t::attitude_estimate, events::ID("check_modes_attitude"), events::Log::Critical, "No valid attitude estimate"); reporter.clearCanRunBits((NavModes)reporter.failsafeFlags().mode_req_attitude); @@ -78,7 +78,7 @@ void ModeChecks::checkAndReport(const Context &context, Report &reporter) if (local_position_modes != NavModes::None) { /* EVENT */ - reporter.armingCheckFailure(local_position_modes, health_component_t::system, + reporter.armingCheckFailure(local_position_modes, health_component_t::local_position_estimate, events::ID("check_modes_local_pos"), events::Log::Error, "No valid local position estimate"); reporter.clearCanRunBits(local_position_modes); @@ -87,7 +87,8 @@ void ModeChecks::checkAndReport(const Context &context, Report &reporter) if (reporter.failsafeFlags().global_position_invalid && reporter.failsafeFlags().mode_req_global_position != 0) { /* EVENT */ - reporter.armingCheckFailure((NavModes)reporter.failsafeFlags().mode_req_global_position, health_component_t::system, + reporter.armingCheckFailure((NavModes)reporter.failsafeFlags().mode_req_global_position, + health_component_t::global_position_estimate, events::ID("check_modes_global_pos"), events::Log::Error, "No valid global position estimate"); reporter.clearCanRunBits((NavModes)reporter.failsafeFlags().mode_req_global_position); From df2cc4af05fd6e387abb40fa9cf32639b44c378f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Tue, 14 Feb 2023 12:12:36 +0100 Subject: [PATCH 142/652] commander: fix check for availability of high latency link Signed-off-by: RomanBapst --- src/modules/commander/Commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 444f5b0c8dba..fc26a052ffb0 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -1109,7 +1109,7 @@ Commander::handle_command(const vehicle_command_s &cmd) case vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY: { // if no high latency telemetry exists send a failed acknowledge - if (_high_latency_datalink_heartbeat > _boot_timestamp) { + if (_high_latency_datalink_heartbeat < _boot_timestamp) { cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED; mavlink_log_critical(&_mavlink_log_pub, "Control high latency failed! Telemetry unavailable\t"); events::send(events::ID("commander_ctrl_high_latency_failed"), {events::Log::Critical, events::LogInternal::Info}, From 760bcdec2fff40590bfdc6f65848c8ca44446a41 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Tue, 14 Feb 2023 16:58:09 +0100 Subject: [PATCH 143/652] high_latency_stream: fixed bug where fields were not updating - topic update was checked twice in the same loop and thus the second time the topic would never indicate to have updated Co-authored-by: RomanBapst --- src/modules/mavlink/streams/HIGH_LATENCY2.hpp | 53 ++++++++++--------- 1 file changed, 28 insertions(+), 25 deletions(-) diff --git a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp index c349340ac3a5..a7d522e06337 100644 --- a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp +++ b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp @@ -125,18 +125,20 @@ class MavlinkStreamHighLatency2 : public MavlinkStream updated |= _temperature.valid(); updated |= _throttle.valid(); updated |= _windspeed.valid(); - updated |= write_airspeed(&msg); - updated |= write_attitude_sp(&msg); - updated |= write_battery_status(&msg); - updated |= write_estimator_status(&msg); - updated |= write_fw_ctrl_status(&msg); - updated |= write_geofence_result(&msg); - updated |= write_global_position(&msg); - updated |= write_mission_result(&msg); - updated |= write_tecs_status(&msg); - updated |= write_vehicle_status(&msg); + updated |= write_attitude_setpoint_if_updated(&msg); + updated |= write_estimator_status_if_updated(&msg); + updated |= write_fw_ctrl_status_if_updated(&msg); + updated |= write_geofence_result_if_updated(&msg); + updated |= write_global_position_if_updated(&msg); + updated |= write_mission_result_if_updated(&msg); updated |= write_failsafe_flags(&msg); - updated |= write_wind(&msg); + + // these topics are already updated in update_data() and thus we just copy them here + write_airspeed(&msg); + write_battery_status(&msg); + write_tecs_status(&msg); + write_vehicle_status(&msg); + write_wind(&msg); if (updated) { msg.timestamp = t / 1000; @@ -244,7 +246,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream { airspeed_s airspeed; - if (_airspeed_sub.update(&airspeed)) { + if (_airspeed_sub.copy(&airspeed)) { if (airspeed.confidence < 0.95f) { // the same threshold as for the commander msg->failure_flags |= HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE; } @@ -255,7 +257,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream return false; } - bool write_attitude_sp(mavlink_high_latency2_t *msg) + bool write_attitude_setpoint_if_updated(mavlink_high_latency2_t *msg) { vehicle_attitude_setpoint_s attitude_sp; @@ -274,7 +276,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream for (int i = 0; i < battery_status_s::MAX_INSTANCES; i++) { battery_status_s battery; - if (_batteries[i].subscription.update(&battery)) { + if (_batteries[i].subscription.copy(&battery)) { updated = true; _batteries[i].connected = battery.connected; @@ -287,11 +289,12 @@ class MavlinkStreamHighLatency2 : public MavlinkStream return updated; } - bool write_estimator_status(mavlink_high_latency2_t *msg) + bool write_estimator_status_if_updated(mavlink_high_latency2_t *msg) { // use primary estimator_status - if (_estimator_selector_status_sub.updated()) { - estimator_selector_status_s estimator_selector_status; + estimator_selector_status_s estimator_selector_status; + + if (_estimator_selector_status_sub.update(&estimator_selector_status)) { if (_estimator_selector_status_sub.copy(&estimator_selector_status)) { if (estimator_selector_status.primary_instance != _estimator_status_sub.get_instance()) { @@ -320,7 +323,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream return false; } - bool write_fw_ctrl_status(mavlink_high_latency2_t *msg) + bool write_fw_ctrl_status_if_updated(mavlink_high_latency2_t *msg) { position_controller_status_s pos_ctrl_status; @@ -334,7 +337,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream return false; } - bool write_geofence_result(mavlink_high_latency2_t *msg) + bool write_geofence_result_if_updated(mavlink_high_latency2_t *msg) { geofence_result_s geofence; @@ -350,12 +353,12 @@ class MavlinkStreamHighLatency2 : public MavlinkStream return false; } - bool write_global_position(mavlink_high_latency2_t *msg) + bool write_global_position_if_updated(mavlink_high_latency2_t *msg) { vehicle_global_position_s global_pos; vehicle_local_position_s local_pos; - if (_global_pos_sub.update(&global_pos) && _local_pos_sub.update(&local_pos)) { + if (_global_pos_sub.update(&global_pos) && _local_pos_sub.copy(&local_pos)) { msg->latitude = global_pos.lat * 1e7; msg->longitude = global_pos.lon * 1e7; @@ -378,7 +381,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream return false; } - bool write_mission_result(mavlink_high_latency2_t *msg) + bool write_mission_result_if_updated(mavlink_high_latency2_t *msg) { mission_result_s mission_result; @@ -394,7 +397,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream { tecs_status_s tecs_status; - if (_tecs_status_sub.update(&tecs_status)) { + if (_tecs_status_sub.copy(&tecs_status)) { int16_t target_altitude; convert_limit_safe(tecs_status.altitude_sp, target_altitude); msg->target_altitude = target_altitude; @@ -409,7 +412,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream { vehicle_status_s status; - if (_status_sub.update(&status)) { + if (_status_sub.copy(&status)) { health_report_s health_report; if (_health_report_sub.copy(&health_report)) { @@ -476,7 +479,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream { wind_s wind; - if (_wind_sub.update(&wind)) { + if (_wind_sub.copy(&wind)) { msg->wind_heading = static_cast(math::degrees(matrix::wrap_2pi(atan2f(wind.windspeed_east, wind.windspeed_north))) * 0.5f); return true; From d3b853a7f9b181e32d2f371864a7c48864906ffe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Tue, 14 Feb 2023 17:00:13 +0100 Subject: [PATCH 144/652] mavlink: fix handling of transmission enable/disable Co-authored-by: RomanBapst --- src/modules/mavlink/mavlink_main.cpp | 294 +++++++++++++-------------- src/modules/mavlink/mavlink_main.h | 6 + 2 files changed, 147 insertions(+), 153 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index a3b17a063409..00828e4525e7 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1057,10 +1057,9 @@ Mavlink::send_statustext_emergency(const char *string) bool Mavlink::send_autopilot_capabilities() { - uORB::Subscription status_sub{ORB_ID(vehicle_status)}; vehicle_status_s status; - if (status_sub.copy(&status)) { + if (_vehicle_status_sub.copy(&status)) { mavlink_autopilot_version_t msg{}; msg.capabilities = MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT; @@ -2236,12 +2235,18 @@ Mavlink::task_main(int argc, char *argv[]) _task_running.store(true); + bool cmd_logging_start_acknowledgement = false; + bool cmd_logging_stop_acknowledgement = false; + while (!should_exit()) { /* main loop */ px4_usleep(_main_loop_delay); if (!should_transmit()) { check_requested_subscriptions(); + handleStatus(); + handleCommands(); + handleAndGetCurrentCommandAck(cmd_logging_start_acknowledgement, cmd_logging_stop_acknowledgement); continue; } @@ -2264,157 +2269,9 @@ Mavlink::task_main(int argc, char *argv[]) configure_sik_radio(); - if (_vehicle_status_sub.updated()) { - vehicle_status_s vehicle_status; - - if (_vehicle_status_sub.copy(&vehicle_status)) { - /* switch HIL mode if required */ - set_hil_enabled(vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON); - - if (_mode == MAVLINK_MODE_IRIDIUM) { - - if (_transmitting_enabled && vehicle_status.high_latency_data_link_lost && - !_transmitting_enabled_commanded && _first_heartbeat_sent) { - - _transmitting_enabled = false; - mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s\t", _device_name); - events::send(events::ID("mavlink_iridium_disable"), events::Log::Info, - "Disabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id); - - } else if (!_transmitting_enabled && !vehicle_status.high_latency_data_link_lost) { - _transmitting_enabled = true; - mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s\t", _device_name); - events::send(events::ID("mavlink_iridium_enable"), events::Log::Info, - "Enabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id); - } - } - } - } - - - // MAVLINK_MODE_IRIDIUM: handle VEHICLE_CMD_CONTROL_HIGH_LATENCY - if (_mode == MAVLINK_MODE_IRIDIUM) { - int vehicle_command_updates = 0; - - while (_vehicle_command_sub.updated() && (vehicle_command_updates < vehicle_command_s::ORB_QUEUE_LENGTH)) { - vehicle_command_updates++; - const unsigned last_generation = _vehicle_command_sub.get_last_generation(); - vehicle_command_s vehicle_cmd; - - if (_vehicle_command_sub.update(&vehicle_cmd)) { - if (_vehicle_command_sub.get_last_generation() != last_generation + 1) { - PX4_ERR("vehicle_command lost, generation %u -> %u", last_generation, _vehicle_command_sub.get_last_generation()); - } - - if ((vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY) && - _mode == MAVLINK_MODE_IRIDIUM) { - - if (vehicle_cmd.param1 > 0.5f) { - if (!_transmitting_enabled) { - mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s by command\t", - _device_name); - events::send(events::ID("mavlink_iridium_enable_cmd"), events::Log::Info, - "Enabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id); - } - - _transmitting_enabled = true; - _transmitting_enabled_commanded = true; - - } else { - if (_transmitting_enabled) { - mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s by command\t", - _device_name); - events::send(events::ID("mavlink_iridium_disable_cmd"), events::Log::Info, - "Disabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id); - } - - _transmitting_enabled = false; - _transmitting_enabled_commanded = false; - } - - // send positive command ack - vehicle_command_ack_s command_ack{}; - command_ack.command = vehicle_cmd.command; - command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; - command_ack.from_external = !vehicle_cmd.from_external; - command_ack.target_system = vehicle_cmd.source_system; - command_ack.target_component = vehicle_cmd.source_component; - command_ack.timestamp = vehicle_cmd.timestamp; - _vehicle_command_ack_pub.publish(command_ack); - } - } - } - } - - /* send command ACK */ - bool cmd_logging_start_acknowledgement = false; - bool cmd_logging_stop_acknowledgement = false; - - if (_vehicle_command_ack_sub.updated()) { - static constexpr size_t COMMAND_ACK_TOTAL_LEN = MAVLINK_MSG_ID_COMMAND_ACK_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; - - while ((get_free_tx_buf() >= COMMAND_ACK_TOTAL_LEN) && _vehicle_command_ack_sub.updated()) { - vehicle_command_ack_s command_ack; - const unsigned last_generation = _vehicle_command_ack_sub.get_last_generation(); - - if (_vehicle_command_ack_sub.update(&command_ack)) { - if (_vehicle_command_ack_sub.get_last_generation() != last_generation + 1) { - PX4_ERR("vehicle_command_ack lost, generation %u -> %u", last_generation, - _vehicle_command_ack_sub.get_last_generation()); - } - - const bool is_target_known = _receiver.component_was_seen(command_ack.target_system, command_ack.target_component); - - if (!command_ack.from_external - && command_ack.command < vehicle_command_s::VEHICLE_CMD_PX4_INTERNAL_START - && is_target_known - && command_ack.target_component < vehicle_command_s::COMPONENT_MODE_EXECUTOR_START) { - - mavlink_command_ack_t msg{}; - msg.result = command_ack.result; - msg.command = command_ack.command; - msg.progress = command_ack.result_param1; - msg.result_param2 = command_ack.result_param2; - msg.target_system = command_ack.target_system; - msg.target_component = command_ack.target_component; - - mavlink_msg_command_ack_send_struct(get_channel(), &msg); - - if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) { - cmd_logging_start_acknowledgement = true; - - } else if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP - && command_ack.result == vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) { - cmd_logging_stop_acknowledgement = true; - } - } - } - } - } - - // For legacy gimbals using the mavlink gimbal v1 protocol, we need to send out commands. - // We don't care about acks for these though. - if (_gimbal_v1_command_sub.updated()) { - vehicle_command_s cmd; - _gimbal_v1_command_sub.copy(&cmd); - - // FIXME: filter for target system/component - - mavlink_command_long_t msg{}; - msg.param1 = cmd.param1; - msg.param2 = cmd.param2; - msg.param3 = cmd.param3; - msg.param4 = cmd.param4; - msg.param5 = cmd.param5; - msg.param6 = cmd.param6; - msg.param7 = cmd.param7; - msg.command = cmd.command; - msg.target_system = cmd.target_system; - msg.target_component = cmd.target_component; - msg.confirmation = 0; - - mavlink_msg_command_long_send_struct(get_channel(), &msg); - } + handleStatus(); + handleCommands(); + handleAndGetCurrentCommandAck(cmd_logging_start_acknowledgement, cmd_logging_stop_acknowledgement); /* check for shell output */ if (_mavlink_shell && _mavlink_shell->available() > 0) { @@ -2583,6 +2440,137 @@ Mavlink::task_main(int argc, char *argv[]) return OK; } +void Mavlink::handleStatus() +{ + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status; + + if (_vehicle_status_sub.copy(&vehicle_status)) { + /* switch HIL mode if required */ + set_hil_enabled(vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON); + + if (_mode == MAVLINK_MODE_IRIDIUM) { + + if (_transmitting_enabled && vehicle_status.high_latency_data_link_lost && + !_transmitting_enabled_commanded && _first_heartbeat_sent) { + + _transmitting_enabled = false; + mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s\t", _device_name); + events::send(events::ID("mavlink_iridium_disable"), events::Log::Info, + "Disabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id); + + } else if (!_transmitting_enabled && !vehicle_status.high_latency_data_link_lost) { + _transmitting_enabled = true; + mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s\t", _device_name); + events::send(events::ID("mavlink_iridium_enable"), events::Log::Info, + "Enabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id); + } + } + } + } +} + +void Mavlink::handleCommands() +{ + if (_mode == MAVLINK_MODE_IRIDIUM) { + int vehicle_command_updates = 0; + + while (_vehicle_command_sub.updated() && (vehicle_command_updates < vehicle_command_s::ORB_QUEUE_LENGTH)) { + vehicle_command_updates++; + const unsigned last_generation = _vehicle_command_sub.get_last_generation(); + vehicle_command_s vehicle_cmd; + + if (_vehicle_command_sub.update(&vehicle_cmd)) { + if (_vehicle_command_sub.get_last_generation() != last_generation + 1) { + PX4_ERR("vehicle_command lost, generation %u -> %u", last_generation, _vehicle_command_sub.get_last_generation()); + } + + if ((vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY) && + _mode == MAVLINK_MODE_IRIDIUM) { + + if (vehicle_cmd.param1 > 0.5f) { + if (!_transmitting_enabled) { + mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s by command\t", + _device_name); + events::send(events::ID("mavlink_iridium_enable_cmd"), events::Log::Info, + "Enabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id); + } + + _transmitting_enabled = true; + _transmitting_enabled_commanded = true; + + } else { + if (_transmitting_enabled) { + mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s by command\t", + _device_name); + events::send(events::ID("mavlink_iridium_disable_cmd"), events::Log::Info, + "Disabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id); + } + + _transmitting_enabled = false; + _transmitting_enabled_commanded = false; + } + + // send positive command ack + vehicle_command_ack_s command_ack{}; + command_ack.command = vehicle_cmd.command; + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; + command_ack.from_external = !vehicle_cmd.from_external; + command_ack.target_system = vehicle_cmd.source_system; + command_ack.target_component = vehicle_cmd.source_component; + command_ack.timestamp = vehicle_cmd.timestamp; + _vehicle_command_ack_pub.publish(command_ack); + } + } + } + } +} + +void Mavlink::handleAndGetCurrentCommandAck(bool &start_ack, bool &stop_ack) +{ + if (_vehicle_command_ack_sub.updated()) { + static constexpr size_t COMMAND_ACK_TOTAL_LEN = MAVLINK_MSG_ID_COMMAND_ACK_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + + while ((get_free_tx_buf() >= COMMAND_ACK_TOTAL_LEN) && _vehicle_command_ack_sub.updated()) { + vehicle_command_ack_s command_ack; + const unsigned last_generation = _vehicle_command_ack_sub.get_last_generation(); + + if (_vehicle_command_ack_sub.update(&command_ack)) { + if (_vehicle_command_ack_sub.get_last_generation() != last_generation + 1) { + PX4_ERR("vehicle_command_ack lost, generation %u -> %u", last_generation, + _vehicle_command_ack_sub.get_last_generation()); + } + + const bool is_target_known = _receiver.component_was_seen(command_ack.target_system, command_ack.target_component); + + if (!command_ack.from_external + && command_ack.command < vehicle_command_s::VEHICLE_CMD_PX4_INTERNAL_START + && is_target_known + && command_ack.target_component < vehicle_command_s::COMPONENT_MODE_EXECUTOR_START) { + + mavlink_command_ack_t msg{}; + msg.result = command_ack.result; + msg.command = command_ack.command; + msg.progress = command_ack.result_param1; + msg.result_param2 = command_ack.result_param2; + msg.target_system = command_ack.target_system; + msg.target_component = command_ack.target_component; + + mavlink_msg_command_ack_send_struct(get_channel(), &msg); + + if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) { + start_ack = true; + + } else if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP + && command_ack.result == vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) { + stop_ack = true; + } + } + } + } + } +} + void Mavlink::check_requested_subscriptions() { if (_subscribe_to_stream != nullptr) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 1ba71c6a2ba1..9d105dcb4161 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -707,6 +707,12 @@ class Mavlink final : public ModuleParams void check_requested_subscriptions(); + void handleCommands(); + + void handleAndGetCurrentCommandAck(bool &start_ack, bool &stop_ack); + + void handleStatus(); + /** * Reconfigure a SiK radio if requested by MAV_SIK_RADIO_ID * From de23c10b68feb9f7489f6b13ea6180125816080c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Wed, 15 Feb 2023 09:45:13 +0100 Subject: [PATCH 145/652] commander: improve handling high latency link lost/regain --- src/modules/commander/Commander.cpp | 53 +++++++++++++++++------------ src/modules/commander/Commander.hpp | 1 + 2 files changed, 33 insertions(+), 21 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index fc26a052ffb0..03a16c9951d2 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -2672,6 +2672,28 @@ void Commander::enable_hil() void Commander::dataLinkCheck() { + // high latency data link + iridiumsbd_status_s iridium_status; + + if (_iridiumsbd_status_sub.update(&iridium_status)) { + _high_latency_datalink_heartbeat = iridium_status.last_heartbeat; + + if (_vehicle_status.high_latency_data_link_lost && + (_high_latency_datalink_heartbeat > _high_latency_datalink_lost) && + (_high_latency_datalink_regained == 0) + ) { + _high_latency_datalink_regained = _high_latency_datalink_heartbeat; + } + + if (_vehicle_status.high_latency_data_link_lost && + (_high_latency_datalink_regained != 0) && + (hrt_elapsed_time(&_high_latency_datalink_regained) > (_param_com_hldl_reg_t.get() * 1_s)) + ) { + _vehicle_status.high_latency_data_link_lost = false; + _status_changed = true; + } + } + for (auto &telemetry_status : _telemetry_status_subs) { telemetry_status_s telemetry; @@ -2685,16 +2707,18 @@ void Commander::dataLinkCheck() break; case telemetry_status_s::LINK_TYPE_IRIDIUM: { - iridiumsbd_status_s iridium_status; - if (_iridiumsbd_status_sub.update(&iridium_status)) { - _high_latency_datalink_heartbeat = iridium_status.last_heartbeat; + if ((_high_latency_datalink_heartbeat > 0) && + (hrt_elapsed_time(&_high_latency_datalink_heartbeat) > (_param_com_hldl_loss_t.get() * 1_s))) { - if (_vehicle_status.high_latency_data_link_lost) { - if (hrt_elapsed_time(&_high_latency_datalink_lost) > (_param_com_hldl_reg_t.get() * 1_s)) { - _vehicle_status.high_latency_data_link_lost = false; - _status_changed = true; - } + _high_latency_datalink_lost = _high_latency_datalink_heartbeat; + _high_latency_datalink_regained = 0; + + if (!_vehicle_status.high_latency_data_link_lost) { + _vehicle_status.high_latency_data_link_lost = true; + mavlink_log_critical(&_mavlink_log_pub, "High latency data link lost\t"); + events::send(events::ID("commander_high_latency_lost"), events::Log::Critical, "High latency data link lost"); + _status_changed = true; } } @@ -2836,19 +2860,6 @@ void Commander::dataLinkCheck() _vehicle_status.avoidance_system_valid = false; } } - - // high latency data link loss failsafe - if (_high_latency_datalink_heartbeat > 0 - && hrt_elapsed_time(&_high_latency_datalink_heartbeat) > (_param_com_hldl_loss_t.get() * 1_s)) { - _high_latency_datalink_lost = hrt_absolute_time(); - - if (!_vehicle_status.high_latency_data_link_lost) { - _vehicle_status.high_latency_data_link_lost = true; - mavlink_log_critical(&_mavlink_log_pub, "High latency data link lost\t"); - events::send(events::ID("commander_high_latency_lost"), events::Log::Critical, "High latency data link lost"); - _status_changed = true; - } - } } void Commander::battery_status_check() diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index d477585c0345..e98132227dba 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -248,6 +248,7 @@ class Commander : public ModuleBase, public ModuleParams hrt_abstime _high_latency_datalink_heartbeat{0}; hrt_abstime _high_latency_datalink_lost{0}; + hrt_abstime _high_latency_datalink_regained{0}; hrt_abstime _boot_timestamp{0}; hrt_abstime _last_disarmed_timestamp{0}; From 208909d47178096f6b8b8cf83c3c7844c4474d00 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Wed, 15 Feb 2023 10:42:26 +0100 Subject: [PATCH 146/652] mavlink: use high_latency_data_link_lost as backup to normal data_link --- src/modules/mavlink/mavlink_main.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 00828e4525e7..c5a7da35aae1 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2451,15 +2451,16 @@ void Mavlink::handleStatus() if (_mode == MAVLINK_MODE_IRIDIUM) { - if (_transmitting_enabled && vehicle_status.high_latency_data_link_lost && - !_transmitting_enabled_commanded && _first_heartbeat_sent) { + if (_transmitting_enabled && (!vehicle_status.gcs_connection_lost || (vehicle_status.high_latency_data_link_lost && + !_transmitting_enabled_commanded && _first_heartbeat_sent))) { _transmitting_enabled = false; mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s\t", _device_name); events::send(events::ID("mavlink_iridium_disable"), events::Log::Info, "Disabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id); - } else if (!_transmitting_enabled && !vehicle_status.high_latency_data_link_lost) { + } else if (!_transmitting_enabled && vehicle_status.gcs_connection_lost + && !vehicle_status.high_latency_data_link_lost) { _transmitting_enabled = true; mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s\t", _device_name); events::send(events::ID("mavlink_iridium_enable"), events::Log::Info, From 29af189cd0d931eba5e610763653711286030ba1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Tue, 7 Jun 2022 18:47:49 +0200 Subject: [PATCH 147/652] mavlink: don't send events over Iridium --- src/modules/mavlink/mavlink_events.cpp | 28 ++++++++++++++------------ 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/src/modules/mavlink/mavlink_events.cpp b/src/modules/mavlink/mavlink_events.cpp index c1596530d45e..135cf154d2e7 100644 --- a/src/modules/mavlink/mavlink_events.cpp +++ b/src/modules/mavlink/mavlink_events.cpp @@ -208,17 +208,18 @@ void SendProtocol::handle_request_event(const mavlink_message_t &msg) const void SendProtocol::send_event(const Event &event) const { - mavlink_event_t event_msg{}; - event_msg.event_time_boot_ms = event.timestamp_ms; - event_msg.destination_component = MAV_COMP_ID_ALL; - event_msg.destination_system = 0; - event_msg.id = event.id; - event_msg.sequence = event.sequence; - event_msg.log_levels = event.log_levels; - static_assert(sizeof(event_msg.arguments) >= sizeof(event.arguments), "MAVLink message arguments buffer too small"); - memcpy(&event_msg.arguments, event.arguments, sizeof(event.arguments)); - mavlink_msg_event_send_struct(_mavlink.get_channel(), &event_msg); - + if (_mavlink.get_mode() != Mavlink::MAVLINK_MODE_IRIDIUM) { + mavlink_event_t event_msg{}; + event_msg.event_time_boot_ms = event.timestamp_ms; + event_msg.destination_component = MAV_COMP_ID_ALL; + event_msg.destination_system = 0; + event_msg.id = event.id; + event_msg.sequence = event.sequence; + event_msg.log_levels = event.log_levels; + static_assert(sizeof(event_msg.arguments) >= sizeof(event.arguments), "MAVLink message arguments buffer too small"); + memcpy(&event_msg.arguments, event.arguments, sizeof(event.arguments)); + mavlink_msg_event_send_struct(_mavlink.get_channel(), &event_msg); + } } void SendProtocol::on_gcs_connected() @@ -228,8 +229,9 @@ void SendProtocol::on_gcs_connected() void SendProtocol::send_current_sequence(const hrt_abstime &now, bool force_reset) { - // only send if enough tx buffer space available - if (_mavlink.get_free_tx_buf() < MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) { + // only send if enough tx buffer space available or not MAVLINK_MODE_IRIDIUM + if (_mavlink.get_free_tx_buf() < MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES || + _mavlink.get_mode() == Mavlink::MAVLINK_MODE_IRIDIUM) { return; } From 5be0adc779d441dd3345eb6cf76827ae1f9756da Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Wed, 15 Feb 2023 09:51:40 +0100 Subject: [PATCH 148/652] mavlink: don't send command ACK for internal commands over Iridium --- src/modules/mavlink/mavlink_main.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index c5a7da35aae1..c6ecb1c53818 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2557,7 +2557,15 @@ void Mavlink::handleAndGetCurrentCommandAck(bool &start_ack, bool &stop_ack) msg.target_system = command_ack.target_system; msg.target_component = command_ack.target_component; - mavlink_msg_command_ack_send_struct(get_channel(), &msg); + if (_mode == MAVLINK_MODE_IRIDIUM) { + if (command_ack.from_external) { + // for MAVLINK_MODE_IRIDIUM send only if external + mavlink_msg_command_ack_send_struct(get_channel(), &msg); + } + + } else { + mavlink_msg_command_ack_send_struct(get_channel(), &msg); + } if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) { start_ack = true; From 4f8de500af2c1ad7418ad4eaf18501f601eceb63 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Wed, 15 Feb 2023 10:25:24 +0100 Subject: [PATCH 149/652] iridiumsbd: update logic for detecting if the modem is not responsive --- msg/IridiumsbdStatus.msg | 2 +- .../telemetry/iridiumsbd/IridiumSBD.cpp | 41 ++++++------------- src/drivers/telemetry/iridiumsbd/IridiumSBD.h | 4 +- src/modules/commander/Commander.cpp | 14 +++---- src/modules/commander/Commander.hpp | 2 +- 5 files changed, 23 insertions(+), 40 deletions(-) diff --git a/msg/IridiumsbdStatus.msg b/msg/IridiumsbdStatus.msg index 39e3de780a00..14ea1d30a55f 100644 --- a/msg/IridiumsbdStatus.msg +++ b/msg/IridiumsbdStatus.msg @@ -1,5 +1,5 @@ uint64 timestamp # time since system start (microseconds) -uint64 last_heartbeat # timestamp of the last successful sbd session +uint64 last_successful_at_cmd # timestamp of the last successful AT command uint16 tx_buf_write_index # current size of the tx buffer uint16 rx_buf_read_index # the rx buffer is parsed up to that index uint16 rx_buf_end_index # current size of the rx buffer diff --git a/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp b/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp index 5fddd4ac46fe..1ee9d2c6276a 100644 --- a/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp +++ b/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp @@ -235,7 +235,7 @@ int IridiumSBD::print_status() PX4_INFO("RX session pending: %d", _rx_session_pending); PX4_INFO("RX read pending: %d", _rx_read_pending); PX4_INFO("Time since last signal check: %" PRId64, hrt_absolute_time() - _last_signal_check); - PX4_INFO("Last heartbeat: %" PRId64, _last_heartbeat); + PX4_INFO("Last heartbeat: %" PRId64, _last_at_ok_timestamp); return 0; } @@ -333,6 +333,11 @@ void IridiumSBD::standby_loop(void) } } + if (!is_modem_responsive()) { + VERBOSE_INFO("MODEM IS NOT RENSPONSIVE"); + return; + } + // check for incoming SBDRING, handled inside read_at_command() read_at_command(); @@ -477,7 +482,6 @@ void IridiumSBD::sbdsession_loop(void) _ring_pending = false; _tx_session_pending = false; _last_read_time = hrt_absolute_time(); - _last_heartbeat = _last_read_time; ++_successful_sbd_sessions; if (mt_queued > 0) { @@ -498,8 +502,6 @@ void IridiumSBD::sbdsession_loop(void) case 1: VERBOSE_INFO("SBD SESSION: MO SUCCESS, MT FAIL"); - _last_heartbeat = hrt_absolute_time(); - // after a successful session reset the tx buffer _tx_buf_write_idx = 0; ++_successful_sbd_sessions; @@ -552,11 +554,6 @@ void IridiumSBD::start_csq(void) _last_signal_check = hrt_absolute_time(); - if (!is_modem_ready()) { - VERBOSE_INFO("UPDATE SIGNAL QUALITY: MODEM NOT READY!"); - return; - } - write_at("AT+CSQ"); _new_state = SATCOM_STATE_CSQ; } @@ -571,11 +568,6 @@ void IridiumSBD::start_sbd_session(void) VERBOSE_INFO("STARTING SBD SESSION"); } - if (!is_modem_ready()) { - VERBOSE_INFO("SBD SESSION: MODEM NOT READY!"); - return; - } - if (_ring_pending) { write_at("AT+SBDIXA"); @@ -610,8 +602,8 @@ void IridiumSBD::start_test(void) printf("\n"); } - if (!is_modem_ready()) { - PX4_WARN("MODEM NOT READY!"); + if (!is_modem_responsive()) { + PX4_WARN("MODEM NOT RENSPONSIVE!"); return; } @@ -718,11 +710,6 @@ ssize_t IridiumSBD::read(struct file *filp, char *buffer, size_t buflen) void IridiumSBD::write_tx_buf() { - if (!is_modem_ready()) { - VERBOSE_INFO("WRITE SBD: MODEM NOT READY!"); - return; - } - pthread_mutex_lock(&_tx_buf_mutex); char command[13]; @@ -779,11 +766,6 @@ void IridiumSBD::write_tx_buf() void IridiumSBD::read_rx_buf(void) { - if (!is_modem_ready()) { - VERBOSE_INFO("READ SBD: MODEM NOT READY!"); - return; - } - pthread_mutex_lock(&_rx_buf_mutex); @@ -949,11 +931,12 @@ satcom_uart_status IridiumSBD::open_uart(char *uart_name) return SATCOM_UART_OK; } -bool IridiumSBD::is_modem_ready(void) +bool IridiumSBD::is_modem_responsive(void) { write_at("AT"); if (read_at_command() == SATCOM_RESULT_OK) { + _last_at_ok_timestamp = hrt_absolute_time(); return true; } else { @@ -980,9 +963,9 @@ void IridiumSBD::publish_iridium_status() { bool need_to_publish = false; - if (_status.last_heartbeat != _last_heartbeat) { + if (_status.last_at_ok_timestamp != _last_at_ok_timestamp) { need_to_publish = true; - _status.last_heartbeat = _last_heartbeat; + _status.last_at_ok_timestamp = _last_at_ok_timestamp; } if (_status.tx_buf_write_index != _tx_buf_write_idx) { diff --git a/src/drivers/telemetry/iridiumsbd/IridiumSBD.h b/src/drivers/telemetry/iridiumsbd/IridiumSBD.h index 3d628440e6ac..897201cf715c 100644 --- a/src/drivers/telemetry/iridiumsbd/IridiumSBD.h +++ b/src/drivers/telemetry/iridiumsbd/IridiumSBD.h @@ -245,7 +245,7 @@ class IridiumSBD : public cdev::CDev, public ModuleBase /* * Checks if the modem responds to the "AT" command */ - bool is_modem_ready(void); + bool is_modem_responsive(void); /* * Get the poll state @@ -321,7 +321,7 @@ class IridiumSBD : public cdev::CDev, public ModuleBase hrt_abstime _last_write_time = 0; hrt_abstime _last_read_time = 0; - hrt_abstime _last_heartbeat = 0; + hrt_abstime _last_at_ok_timestamp = 0; hrt_abstime _session_start_time = 0; satcom_state _state = SATCOM_STATE_STANDBY; diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 03a16c9951d2..f7ac58e9617f 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -1109,7 +1109,7 @@ Commander::handle_command(const vehicle_command_s &cmd) case vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY: { // if no high latency telemetry exists send a failed acknowledge - if (_high_latency_datalink_heartbeat < _boot_timestamp) { + if (_high_latency_datalink_timestamp < _boot_timestamp) { cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED; mavlink_log_critical(&_mavlink_log_pub, "Control high latency failed! Telemetry unavailable\t"); events::send(events::ID("commander_ctrl_high_latency_failed"), {events::Log::Critical, events::LogInternal::Info}, @@ -2676,13 +2676,13 @@ void Commander::dataLinkCheck() iridiumsbd_status_s iridium_status; if (_iridiumsbd_status_sub.update(&iridium_status)) { - _high_latency_datalink_heartbeat = iridium_status.last_heartbeat; + _high_latency_datalink_timestamp = iridium_status.last_successful_at_cmd; if (_vehicle_status.high_latency_data_link_lost && - (_high_latency_datalink_heartbeat > _high_latency_datalink_lost) && + (_high_latency_datalink_timestamp > _high_latency_datalink_lost) && (_high_latency_datalink_regained == 0) ) { - _high_latency_datalink_regained = _high_latency_datalink_heartbeat; + _high_latency_datalink_regained = _high_latency_datalink_timestamp; } if (_vehicle_status.high_latency_data_link_lost && @@ -2708,10 +2708,10 @@ void Commander::dataLinkCheck() case telemetry_status_s::LINK_TYPE_IRIDIUM: { - if ((_high_latency_datalink_heartbeat > 0) && - (hrt_elapsed_time(&_high_latency_datalink_heartbeat) > (_param_com_hldl_loss_t.get() * 1_s))) { + if ((_high_latency_datalink_timestamp > 0) && + (hrt_elapsed_time(&_high_latency_datalink_timestamp) > (_param_com_hldl_loss_t.get() * 1_s))) { - _high_latency_datalink_lost = _high_latency_datalink_heartbeat; + _high_latency_datalink_lost = _high_latency_datalink_timestamp; _high_latency_datalink_regained = 0; if (!_vehicle_status.high_latency_data_link_lost) { diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index e98132227dba..3108d3386a0b 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -246,7 +246,7 @@ class Commander : public ModuleBase, public ModuleParams hrt_abstime _last_print_mode_reject_time{0}; ///< To remember when last notification was sent - hrt_abstime _high_latency_datalink_heartbeat{0}; + hrt_abstime _high_latency_datalink_timestamp{0}; hrt_abstime _high_latency_datalink_lost{0}; hrt_abstime _high_latency_datalink_regained{0}; From 61ca65d863b7fd30604e57cc88b97bb567cc1329 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Wed, 15 Feb 2023 10:58:06 +0100 Subject: [PATCH 150/652] mavlink: use high_latency_data_link_lost as backup to normal data_link --- msg/IridiumsbdStatus.msg | 2 +- src/modules/commander/Commander.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/msg/IridiumsbdStatus.msg b/msg/IridiumsbdStatus.msg index 14ea1d30a55f..436654e4ffab 100644 --- a/msg/IridiumsbdStatus.msg +++ b/msg/IridiumsbdStatus.msg @@ -1,5 +1,5 @@ uint64 timestamp # time since system start (microseconds) -uint64 last_successful_at_cmd # timestamp of the last successful AT command +uint64 last_at_ok_timestamp # timestamp of the last "OK" received after the "AT" command uint16 tx_buf_write_index # current size of the tx buffer uint16 rx_buf_read_index # the rx buffer is parsed up to that index uint16 rx_buf_end_index # current size of the rx buffer diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index f7ac58e9617f..8efd9b1bbaab 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -2676,7 +2676,7 @@ void Commander::dataLinkCheck() iridiumsbd_status_s iridium_status; if (_iridiumsbd_status_sub.update(&iridium_status)) { - _high_latency_datalink_timestamp = iridium_status.last_successful_at_cmd; + _high_latency_datalink_timestamp = iridium_status.last_at_ok_timestamp; if (_vehicle_status.high_latency_data_link_lost && (_high_latency_datalink_timestamp > _high_latency_datalink_lost) && From d0532f45b2bedbd005cc7451e607e93e849a7e32 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Tue, 7 Jun 2022 18:53:41 +0200 Subject: [PATCH 151/652] telemetry: enable iridium --- boards/px4/fmu-v5x/default.px4board | 1 + src/drivers/telemetry/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 2bede96763c0..34ffe203d5b2 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -45,6 +45,7 @@ CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TELEMETRY_IRIDIUMSBD=y CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_UAVCAN=y CONFIG_MODULES_AIRSPEED_SELECTOR=y diff --git a/src/drivers/telemetry/CMakeLists.txt b/src/drivers/telemetry/CMakeLists.txt index 0980f2d9f3e8..97e0ed7806cd 100644 --- a/src/drivers/telemetry/CMakeLists.txt +++ b/src/drivers/telemetry/CMakeLists.txt @@ -34,4 +34,4 @@ add_subdirectory(bst) add_subdirectory(frsky_telemetry) add_subdirectory(hott) -#add_subdirectory(iridiumsbd) +add_subdirectory(iridiumsbd) From d0e7f2c368ac515b32be1a9ecb17ffbaa645bfbb Mon Sep 17 00:00:00 2001 From: oravla5 Date: Mon, 22 Apr 2024 13:12:57 +0200 Subject: [PATCH 152/652] high_latency_stream: heading taken from vehicle_attitude topic --- src/modules/mavlink/streams/HIGH_LATENCY2.hpp | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp index a7d522e06337..6eb56abbad8a 100644 --- a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp +++ b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp @@ -53,6 +53,7 @@ #include #include #include +#include #include #include #include @@ -130,6 +131,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream updated |= write_fw_ctrl_status_if_updated(&msg); updated |= write_geofence_result_if_updated(&msg); updated |= write_global_position_if_updated(&msg); + updated |= write_heading_if_updated(&msg); updated |= write_mission_result_if_updated(&msg); updated |= write_failsafe_flags(&msg); @@ -373,7 +375,20 @@ class MavlinkStreamHighLatency2 : public MavlinkStream msg->altitude = altitude; - msg->heading = static_cast(math::degrees(matrix::wrap_2pi(local_pos.heading)) * 0.5f); + return true; + } + + return false; + } + + bool write_heading_if_updated(mavlink_high_latency2_t *msg) + { + vehicle_attitude_s attitude; + + if (_attitude_sub.update(&attitude) && _attitude_sub.copy(&attitude)) { + + const matrix::Eulerf euler = matrix::Quatf(attitude.q); + msg->heading = static_cast(math::degrees(matrix::wrap_2pi(euler.psi())) * 0.5f); return true; } @@ -628,6 +643,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream uORB::Subscription _vehicle_thrust_setpoint_0_sub{ORB_ID(vehicle_thrust_setpoint), 0}; uORB::Subscription _vehicle_thrust_setpoint_1_sub{ORB_ID(vehicle_thrust_setpoint), 1}; uORB::Subscription _airspeed_sub{ORB_ID(airspeed)}; + uORB::Subscription _attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _attitude_sp_sub{ORB_ID(vehicle_attitude_setpoint)}; uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _estimator_status_sub{ORB_ID(estimator_status)}; From 03652beef8cf5e27bfe497e8df4356da66368c03 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Tue, 23 Apr 2024 16:31:35 +0200 Subject: [PATCH 153/652] commander: fixed format --- src/modules/commander/Commander.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 3108d3386a0b..9431381d8cc4 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -248,7 +248,7 @@ class Commander : public ModuleBase, public ModuleParams hrt_abstime _high_latency_datalink_timestamp{0}; hrt_abstime _high_latency_datalink_lost{0}; - hrt_abstime _high_latency_datalink_regained{0}; + hrt_abstime _high_latency_datalink_regained{0}; hrt_abstime _boot_timestamp{0}; hrt_abstime _last_disarmed_timestamp{0}; From bf1266af11ea7996ad0eba4f9455df73821f687b Mon Sep 17 00:00:00 2001 From: oravla5 Date: Tue, 23 Apr 2024 16:32:48 +0200 Subject: [PATCH 154/652] mavlink: added back gimbal v1 protocol command --- src/modules/mavlink/mavlink_main.cpp | 26 +++++++++++++++++++++++++- src/modules/mavlink/mavlink_main.h | 2 +- 2 files changed, 26 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index c6ecb1c53818..681c91148826 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2525,9 +2525,33 @@ void Mavlink::handleCommands() } } } + + // For legacy gimbals using the mavlink gimbal v1 protocol, we need to send out commands. + // We don't care about acks for these though. + if (_gimbal_v1_command_sub.updated()) { + vehicle_command_s cmd; + _gimbal_v1_command_sub.copy(&cmd); + + // FIXME: filter for target system/component + + mavlink_command_long_t msg{}; + msg.param1 = cmd.param1; + msg.param2 = cmd.param2; + msg.param3 = cmd.param3; + msg.param4 = cmd.param4; + msg.param5 = cmd.param5; + msg.param6 = cmd.param6; + msg.param7 = cmd.param7; + msg.command = cmd.command; + msg.target_system = cmd.target_system; + msg.target_component = cmd.target_component; + msg.confirmation = 0; + + mavlink_msg_command_long_send_struct(get_channel(), &msg); + } } -void Mavlink::handleAndGetCurrentCommandAck(bool &start_ack, bool &stop_ack) +void Mavlink::handleAndGetCurrentCommandAck(bool &logging_start_ack, bool &logging_stop_ack) { if (_vehicle_command_ack_sub.updated()) { static constexpr size_t COMMAND_ACK_TOTAL_LEN = MAVLINK_MSG_ID_COMMAND_ACK_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 9d105dcb4161..498e083c4164 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -709,7 +709,7 @@ class Mavlink final : public ModuleParams void handleCommands(); - void handleAndGetCurrentCommandAck(bool &start_ack, bool &stop_ack); + void handleAndGetCurrentCommandAck(bool &logging_start_ack, bool &logging_stop_ack); void handleStatus(); From 3cb48feb617328b0b10a2e552059f3e002705180 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Tue, 23 Apr 2024 16:36:49 +0200 Subject: [PATCH 155/652] high_latency_stream: minor PR fix --- src/modules/mavlink/streams/HIGH_LATENCY2.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp index 6eb56abbad8a..6ce85a2e7583 100644 --- a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp +++ b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp @@ -385,7 +385,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream { vehicle_attitude_s attitude; - if (_attitude_sub.update(&attitude) && _attitude_sub.copy(&attitude)) { + if (_attitude_sub.update(&attitude)) { const matrix::Eulerf euler = matrix::Quatf(attitude.q); msg->heading = static_cast(math::degrees(matrix::wrap_2pi(euler.psi())) * 0.5f); From 283ae60a15b4e64a03c8ed48058e043a0cbf3b2b Mon Sep 17 00:00:00 2001 From: oravla5 Date: Wed, 24 Apr 2024 09:01:05 +0200 Subject: [PATCH 156/652] telemetry: removed iridium driver --- boards/px4/fmu-v5x/default.px4board | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 34ffe203d5b2..2bede96763c0 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -45,7 +45,6 @@ CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y CONFIG_COMMON_TELEMETRY=y -CONFIG_DRIVERS_TELEMETRY_IRIDIUMSBD=y CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_UAVCAN=y CONFIG_MODULES_AIRSPEED_SELECTOR=y From 98b23e41f70196889b31f28335e89f328e5d1341 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Wed, 24 Apr 2024 09:01:45 +0200 Subject: [PATCH 157/652] mavlink: fixed compilation error after var renaming --- src/modules/mavlink/mavlink_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 681c91148826..20b8322ca2c2 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2592,11 +2592,11 @@ void Mavlink::handleAndGetCurrentCommandAck(bool &logging_start_ack, bool &loggi } if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) { - start_ack = true; + logging_start_ack = true; } else if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP && command_ack.result == vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) { - stop_ack = true; + logging_stop_ack = true; } } } From ba448fb549faab02f38a2f87a0e0f31ba3701230 Mon Sep 17 00:00:00 2001 From: "murata,katsutoshi" Date: Thu, 25 Apr 2024 20:53:05 +0900 Subject: [PATCH 158/652] MC Auto: add fixed yaw mode --- .../tasks/Auto/FlightTaskAuto.cpp | 20 ++++++++++++------- .../tasks/Auto/FlightTaskAuto.hpp | 9 +++++++++ .../multicopter_autonomous_params.c | 1 + 3 files changed, 23 insertions(+), 7 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index 4c5fbc8be785..606776aea8c4 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -170,7 +170,8 @@ bool FlightTaskAuto::update() waypoints[2] = _position_setpoint; } - const bool should_wait_for_yaw_align = _param_mpc_yaw_mode.get() == 4 && !_yaw_sp_aligned; + const bool should_wait_for_yaw_align = _param_mpc_yaw_mode.get() == int32_t(yaw_mode::towards_waypoint_yaw_first) + && !_yaw_sp_aligned; const bool force_zero_velocity_setpoint = should_wait_for_yaw_align || _is_emergency_braking_active; _updateTrajConstraints(); PositionSmoothing::PositionSmoothingSetpoints smoothed_setpoints; @@ -532,32 +533,37 @@ void FlightTaskAuto::_set_heading_from_mode() Vector2f v; // Vector that points towards desired location - switch (_param_mpc_yaw_mode.get()) { + switch (yaw_mode(_param_mpc_yaw_mode.get())) { - case 0: // Heading points towards the current waypoint. - case 4: // Same as 0 but yaw first and then go + case yaw_mode::towards_waypoint: // Heading points towards the current waypoint. + case yaw_mode::towards_waypoint_yaw_first: // Same as 0 but yaw first and then go v = Vector2f(_target) - Vector2f(_position); break; - case 1: // Heading points towards home. + case yaw_mode::towards_home: // Heading points towards home. if (_sub_home_position.get().valid_lpos) { v = Vector2f(&_sub_home_position.get().x) - Vector2f(_position); } break; - case 2: // Heading point away from home. + case yaw_mode::away_from_home: // Heading point away from home. if (_sub_home_position.get().valid_lpos) { v = Vector2f(_position) - Vector2f(&_sub_home_position.get().x); } break; - case 3: // Along trajectory. + case yaw_mode::along_trajectory: // Along trajectory. // The heading depends on the kind of setpoint generation. This needs to be implemented // in the subclasses where the velocity setpoints are generated. v.setAll(NAN); break; + + case yaw_mode::yaw_fixed: // Yaw fixed. + // Yaw is operated via manual control or MAVLINK messages. + break; + } if (v.isAllFinite()) { diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp index fc671cd5e5d6..90a98cac23ad 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp @@ -81,6 +81,15 @@ enum class State { none /**< Vehicle is in normal tracking mode from triplet previous to triplet target */ }; +enum class yaw_mode : int32_t { + towards_waypoint = 0, + towards_home = 1, + away_from_home = 2, + along_trajectory = 3, + towards_waypoint_yaw_first = 4, + yaw_fixed = 5, +}; + class FlightTaskAuto : public FlightTask { public: diff --git a/src/modules/mc_pos_control/multicopter_autonomous_params.c b/src/modules/mc_pos_control/multicopter_autonomous_params.c index 1bfc336fce48..8c97e779be32 100644 --- a/src/modules/mc_pos_control/multicopter_autonomous_params.c +++ b/src/modules/mc_pos_control/multicopter_autonomous_params.c @@ -172,6 +172,7 @@ PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_ACC, 60.f); * @value 2 away from home * @value 3 along trajectory * @value 4 towards waypoint (yaw first) + * @value 5 yaw fixed * @group Mission */ PARAM_DEFINE_INT32(MPC_YAW_MODE, 0); From 7cefc3172a0cb56971855f2fae6f86cfa9068588 Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 25 Apr 2024 09:54:42 +0200 Subject: [PATCH 159/652] estimatorCheck: get param only if handle is valid --- .../HealthAndArmingChecks/checks/estimatorCheck.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index dc5b4566839f..c67fdfd21343 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -99,8 +99,12 @@ void EstimatorChecks::checkAndReport(const Context &context, Report &reporter) } } + param_t param_ekf2_en_handle = param_find_no_notification("EKF2_EN"); int32_t param_ekf2_en = 0; - param_get(param_find_no_notification("EKF2_EN"), ¶m_ekf2_en); + + if (param_ekf2_en_handle != PARAM_INVALID) { + param_get(param_ekf2_en_handle, ¶m_ekf2_en); + } if (missing_data && (param_ekf2_en == 1)) { /* EVENT From e7b4c5903f031cc90f1d61ed0c2b704f747ef025 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Mon, 22 Apr 2024 16:03:24 +0200 Subject: [PATCH 160/652] px4_cli: Added px4_get_parameter_value function overload for float type --- .../common/include/px4_platform_common/cli.h | 12 +++++ platforms/common/px4_cli.cpp | 46 +++++++++++++++++++ 2 files changed, 58 insertions(+) diff --git a/platforms/common/include/px4_platform_common/cli.h b/platforms/common/include/px4_platform_common/cli.h index 1e08cfabd0c7..5667ae685eb0 100644 --- a/platforms/common/include/px4_platform_common/cli.h +++ b/platforms/common/include/px4_platform_common/cli.h @@ -50,3 +50,15 @@ * @return 0 on success, -errno otherwise */ int px4_get_parameter_value(const char *option, int &value); + +/** + * Parse a CLI argument to a float. There are 2 valid formats: + * - 'p:' + * in this case the parameter is loaded from an integer parameter + * - + * a floating-point value, so just a string to float conversion is done + * @param option CLI argument + * @param value returned value + * @return 0 on success, -errno otherwise + */ +int px4_get_parameter_value(const char *option, float &value); diff --git a/platforms/common/px4_cli.cpp b/platforms/common/px4_cli.cpp index bf0e5f394967..d2ffa7230da5 100644 --- a/platforms/common/px4_cli.cpp +++ b/platforms/common/px4_cli.cpp @@ -59,6 +59,7 @@ int px4_get_parameter_value(const char *option, int &value) if (param_handle != PARAM_INVALID) { if (param_type(param_handle) != PARAM_TYPE_INT32) { + PX4_ERR("Type of param '%s' is different from INT32", param_name); return -EINVAL; } @@ -87,3 +88,48 @@ int px4_get_parameter_value(const char *option, int &value) return 0; } + +int px4_get_parameter_value(const char *option, float &value) +{ + value = 0; + + /* check if this is a param name */ + if (strncmp("p:", option, 2) == 0) { + + const char *param_name = option + 2; + + /* user wants to use a param name */ + param_t param_handle = param_find(param_name); + + if (param_handle != PARAM_INVALID) { + + if (param_type(param_handle) != PARAM_TYPE_FLOAT) { + PX4_ERR("Type of param '%s' is different from FLOAT", param_name); + return -EINVAL; + } + + float pwm_parm; + int ret = param_get(param_handle, &pwm_parm); + + if (ret != 0) { + return ret; + } + + value = pwm_parm; + + } else { + PX4_ERR("param name '%s' not found", param_name); + return -ENXIO; + } + + } else { + char *ep; + value = strtof(option, &ep); + + if (*ep != '\0') { + return -EINVAL; + } + } + + return 0; +} From 2b2e1c9521bf90309352ab0845681e0ee9af7578 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Tue, 23 Apr 2024 08:55:20 +0200 Subject: [PATCH 161/652] mavlink: Added parsing of CLI option to configure HL frequency --- src/modules/mavlink/mavlink_main.cpp | 26 ++++++++++++++++++++++++-- src/modules/mavlink/mavlink_main.h | 1 + 2 files changed, 25 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 20b8322ca2c2..57742aa98c31 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1689,7 +1689,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) break; case MAVLINK_MODE_IRIDIUM: - configure_stream_local("HIGH_LATENCY2", 0.015f); + configure_stream_local("HIGH_LATENCY2", _high_latency_freq); break; case MAVLINK_MODE_MINIMAL: @@ -1843,7 +1843,7 @@ Mavlink::task_main(int argc, char *argv[]) int temp_int_arg; #endif - while ((ch = px4_getopt(argc, argv, "b:r:d:n:u:o:m:t:c:fswxzZp", &myoptind, &myoptarg)) != EOF) { + while ((ch = px4_getopt(argc, argv, "b:r:d:n:u:o:m:t:c:F:fswxzZp", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'b': if (px4_get_parameter_value(myoptarg, _baudrate) != 0) { @@ -2031,6 +2031,24 @@ Mavlink::task_main(int argc, char *argv[]) break; } + case 'F': { + float freq; + + if (px4_get_parameter_value(myoptarg, freq) != 0) { + PX4_ERR("iridium mode frequency parsing failed"); + err_flag = true; + } + else { + if (freq >= 0) { + _high_latency_freq = freq; + } else { + PX4_ERR("Invalid value for iridium mode frequency."); + err_flag = true; + } + } + break; + } + case 'f': _forwarding_on = true; break; @@ -2904,6 +2922,9 @@ Mavlink::display_status() _ftp_on ? "YES" : "NO", _transmitting_enabled ? "YES" : "NO"); printf("\tmode: %s\n", mavlink_mode_str(_mode)); + if (_mode == MAVLINK_MODE_IRIDIUM) { + printf("\t iridium tx freq: %.3f\n", (double)(_high_latency_freq)); + } printf("\tForwarding: %s\n", get_forwarding_on() ? "On" : "Off"); printf("\tMAVLink version: %" PRId32 "\n", _protocol_version); @@ -3284,6 +3305,7 @@ Start mavlink on UDP port 14556 and enable the HIGHRES_IMU message with 50Hz: #if defined(CONFIG_NET_IGMP) && defined(CONFIG_NET_ROUTE) PRINT_MODULE_USAGE_PARAM_STRING('c', nullptr, "Multicast address in the range [239.0.0.0,239.255.255.255]", "Multicast address (multicasting can be enabled via MAV_{i}_BROADCAST param)", true); #endif + PRINT_MODULE_USAGE_PARAM_FLOAT('F', 0.015, 0.0, 50.0, "Sets the transmission frequency for iridium mode", true); PRINT_MODULE_USAGE_PARAM_FLAG('f', "Enable message forwarding to other Mavlink instances", true); PRINT_MODULE_USAGE_PARAM_FLAG('w', "Wait to send, until first message received", true); PRINT_MODULE_USAGE_PARAM_FLAG('x', "Enable FTP", true); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 498e083c4164..5bf47913274b 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -584,6 +584,7 @@ class Mavlink final : public ModuleParams int _baudrate{57600}; int _datarate{1000}; ///< data rate for normal streams (attitude, position, etc.) float _rate_mult{1.0f}; + float _high_latency_freq{0.015f}; ///< frequency of HIGH_LATENCY2 stream bool _radio_status_available{false}; bool _radio_status_critical{false}; From 9d6ac0b87a914b3a7c73c2d6c52a0b6251e5b115 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Tue, 23 Apr 2024 08:56:16 +0200 Subject: [PATCH 162/652] mavlink: Added MAV_{i}_HL_FREQ parameter --- src/modules/mavlink/mavlink_main.cpp | 10 +++++++--- src/modules/mavlink/module.yaml | 23 +++++++++++++++++++++++ 2 files changed, 30 insertions(+), 3 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 57742aa98c31..727360df8ff5 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2037,15 +2037,17 @@ Mavlink::task_main(int argc, char *argv[]) if (px4_get_parameter_value(myoptarg, freq) != 0) { PX4_ERR("iridium mode frequency parsing failed"); err_flag = true; - } - else { - if (freq >= 0) { + + } else { + if (freq >= 0.f) { _high_latency_freq = freq; + } else { PX4_ERR("Invalid value for iridium mode frequency."); err_flag = true; } } + break; } @@ -2922,9 +2924,11 @@ Mavlink::display_status() _ftp_on ? "YES" : "NO", _transmitting_enabled ? "YES" : "NO"); printf("\tmode: %s\n", mavlink_mode_str(_mode)); + if (_mode == MAVLINK_MODE_IRIDIUM) { printf("\t iridium tx freq: %.3f\n", (double)(_high_latency_freq)); } + printf("\tForwarding: %s\n", get_forwarding_on() ? "On" : "Off"); printf("\tMAVLink version: %" PRId32 "\n", _protocol_version); diff --git a/src/modules/mavlink/module.yaml b/src/modules/mavlink/module.yaml index dfa9a2da7ff3..aef154a025b8 100644 --- a/src/modules/mavlink/module.yaml +++ b/src/modules/mavlink/module.yaml @@ -32,6 +32,10 @@ serial_config: then set MAV_ARGS "${MAV_ARGS} -z" fi + if param compare MAV_${i}_MODE 6 + then + set MAV_ARGS "${MAV_ARGS} -F p:MAV_${i}_HL_FREQ" + fi mavlink start ${MAV_ARGS} -x port_config_param: name: MAV_${i}_CONFIG @@ -178,3 +182,22 @@ parameters: num_instances: *max_num_config_instances default: [2, 2, 2] reboot_required: true + + MAV_${i}_HL_FREQ: + description: + short: Configures the frequency of HIGH_LATENCY2 stream for instance ${i} + long: | + Positive real value that configures the transmission frequency of the + HIGH_LATENCY2 stream for instance ${i}, configured in iridium mode. + This parameter has no effect if the instance mode is different from iridium. + + type: float + decimal: 3 + increment: 0.001 + unit: Hz + min: 0.0 + max: 50.0 + num_instances: *max_num_config_instances + default: [0.015, 0.015, 0.015] + reboot_required: true + From f91103af6ee465bb7dff676837ff90e9b9472940 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Fri, 26 Apr 2024 08:44:05 +0200 Subject: [PATCH 163/652] boards: removed CONFIG_SYSTEMCMDS_REFLECT from Sky-Drones AIRLink board support --- boards/sky-drones/smartap-airlink/default.px4board | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index c57168389c58..4bb3c7cc406c 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -86,7 +86,6 @@ CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y -CONFIG_SYSTEMCMDS_REFLECT=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y CONFIG_SYSTEMCMDS_SERIAL_TEST=y From 34cb69898e8b2757223554890a5012d12bd0f110 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 25 Apr 2024 16:35:01 +0200 Subject: [PATCH 164/652] FW Position Controller: fix Altitude mode without valid z reference (e.g. no GPS) Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 35a3c32c7df8..c4ce648381ad 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -2304,7 +2304,7 @@ FixedwingPositionControl::Run() _reference_altitude = 0.f; } - _current_altitude = -_local_pos.z + _local_pos.ref_alt; // Altitude AMSL in meters + _current_altitude = -_local_pos.z + _reference_altitude; // Altitude AMSL in meters // handle estimator reset events. we only adjust setpoins for manual modes if (_control_mode.flag_control_manual_enabled) { From 500332e42413cc7dc9ae52bdcd95cbdca136c6ae Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 3 Mar 2024 21:25:59 +0100 Subject: [PATCH 165/652] imxrt: flexpwm remove 1:1 mapping requirement --- .../output_groups_from_timer_config.py | 28 ++-- .../src/px4/nxp/imxrt/io_pins/io_timer.c | 152 ++++++++++++------ 2 files changed, 116 insertions(+), 64 deletions(-) diff --git a/Tools/module_config/output_groups_from_timer_config.py b/Tools/module_config/output_groups_from_timer_config.py index ce16545a7d3b..62ea7c8214c6 100755 --- a/Tools/module_config/output_groups_from_timer_config.py +++ b/Tools/module_config/output_groups_from_timer_config.py @@ -34,24 +34,23 @@ def extract_timer(line): if search: return search.group(1), 'generic' - # nxp rt1062 format: initIOPWM(PWM::FlexPWM2), - search = re.search('PWM::Flex([0-9a-zA-Z_]+)[,\)]', line, re.IGNORECASE) + # NXP FlexPWM format format: initIOPWM(PWM::FlexPWM2), + search = re.search('PWM::Flex([0-9a-zA-Z_]+)..PWM::Submodule([0-9])[,\)]', line, re.IGNORECASE) if search: - return search.group(1), 'imxrt' + return (search.group(1) + '_' + search.group(2)), 'imxrt' return None, 'unknown' -def extract_timer_from_channel(line, num_channels_already_found): +def extract_timer_from_channel(line, timer_names): # Try format: initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), search = re.search('Timer::([0-9a-zA-Z_]+), ', line, re.IGNORECASE) if search: return search.group(1) - # nxp rt1062 format: initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06), - search = re.search('PWM::(PWM[0-9]+)[_,\)]', line, re.IGNORECASE) + # NXP FlexPWM format: initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06), + search = re.search('PWM::(PWM[0-9]+).*PWM::Submodule([0-9])', line, re.IGNORECASE) if search: - # imxrt uses a 1:1 timer group to channel association - return str(num_channels_already_found) + return str(timer_names.index((search.group(1) + '_' + search.group(2)))) return None @@ -69,6 +68,7 @@ def get_timer_groups(timer_config_file, verbose=False): open_idx, close_idx = find_matching_brackets(('{', '}'), timer_config, verbose) timers_str = timer_config[open_idx:close_idx] timers = [] + timer_names = [] for line in timers_str.splitlines(): line = line.strip() if len(line) == 0 or line.startswith('//'): @@ -77,14 +77,12 @@ def get_timer_groups(timer_config_file, verbose=False): if timer_type == 'imxrt': if verbose: print('imxrt timer found') - max_num_channels = 16 # Just add a fixed number of timers - timers = [str(i) for i in range(max_num_channels)] - dshot_support = {str(i): False for i in range(max_num_channels)} + timer_names.append(timer) + timers.append(str(len(timers))) + dshot_support = {str(i): False for i in range(16)} for i in range(8): # First 8 channels support dshot dshot_support[str(i)] = True - break - - if timer: + elif timer: if verbose: print('found timer def: {:}'.format(timer)) dshot_support[timer] = 'DMA' in line timers.append(timer) @@ -111,7 +109,7 @@ def get_timer_groups(timer_config_file, verbose=False): continue if verbose: print('--'+line+'--') - timer = extract_timer_from_channel(line, len(channel_timers)) + timer = extract_timer_from_channel(line, timer_names) if timer: if verbose: print('Found timer: {:} in channel line {:}'.format(timer, line)) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/io_pins/io_timer.c b/platforms/nuttx/src/px4/nxp/imxrt/io_pins/io_timer.c index 240c62d062dc..4fa7d7fdb6fb 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/io_pins/io_timer.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/io_pins/io_timer.c @@ -255,6 +255,34 @@ static inline int channels_timer(unsigned channel) return timer_io_channels[channel].timer_index; } +static uint32_t get_timer_channels(unsigned timer) +{ + uint32_t channels = 0; + static uint32_t channels_cache[MAX_IO_TIMERS] = {0}; + + if (validate_timer_index(timer) < 0) { + return channels; + + } else { + if (channels_cache[timer] == 0) { + /* Gather the channel bits that belong to the timer */ + + uint32_t first_channel_index = io_timers_channel_mapping.element[timer].first_channel_index; + uint32_t last_channel_index = first_channel_index + io_timers_channel_mapping.element[timer].channel_count; + + for (unsigned chan_index = first_channel_index; chan_index < last_channel_index; chan_index++) { + channels |= 1 << chan_index; + } + + /* cache them */ + + channels_cache[timer] = channels; + } + } + + return channels_cache[timer]; +} + static uint32_t get_channel_mask(unsigned channel) { return io_timer_validate_channel_index(channel) == 0 ? 1 << channel : 0; @@ -391,41 +419,66 @@ static int allocate_channel(unsigned channel, io_timer_channel_mode_t mode) return rv; } -static int timer_set_rate(unsigned channel, unsigned rate) +static int timer_set_rate(unsigned timer, unsigned rate) { + int channels = get_timer_channels(timer); + irqstate_t flags = px4_enter_critical_section(); - rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT - ; - rVAL1(channels_timer(channel), timer_io_channels[channel].sub_module) = (BOARD_PWM_FREQ / rate) - 1; - rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits; + + for (uint32_t channel = 0; channel < DIRECT_PWM_OUTPUT_CHANNELS; ++channel) { + if ((1 << channel) & channels) { + rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT + ; + rVAL1(channels_timer(channel), timer_io_channels[channel].sub_module) = (BOARD_PWM_FREQ / rate) - 1; + rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits; + + } + } + px4_leave_critical_section(flags); return 0; } -static inline void io_timer_set_oneshot_mode(unsigned channel) +static inline void io_timer_set_oneshot_mode(unsigned timer) { + int channels = get_timer_channels(timer); + irqstate_t flags = px4_enter_critical_section(); - uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module); - rvalue &= ~SMCTRL_PRSC_MASK; - rvalue |= SMCTRL_PRSC_DIV2 | SMCTRL_LDMOD; - rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT - ; - rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue; - rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits; + + for (uint32_t channel = 0; channel < DIRECT_PWM_OUTPUT_CHANNELS; ++channel) { + if ((1 << channel) & channels) { + uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module); + rvalue &= ~SMCTRL_PRSC_MASK; + rvalue |= SMCTRL_PRSC_DIV2 | SMCTRL_LDMOD; + rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT + ; + rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue; + rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits; + } + } + px4_leave_critical_section(flags); } -static inline void io_timer_set_PWM_mode(unsigned channel) +static inline void io_timer_set_PWM_mode(unsigned timer) { + int channels = get_timer_channels(timer); + irqstate_t flags = px4_enter_critical_section(); - uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module); - rvalue &= ~(SMCTRL_PRSC_MASK | SMCTRL_LDMOD); - rvalue |= SMCTRL_PRSC_DIV16; - rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT - ; - rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue; - rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits; + + for (uint32_t channel = 0; channel < DIRECT_PWM_OUTPUT_CHANNELS; ++channel) { + if ((1 << channel) & channels) { + uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module); + rvalue &= ~(SMCTRL_PRSC_MASK | SMCTRL_LDMOD); + rvalue |= SMCTRL_PRSC_DIV16; + rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT + ; + rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue; + rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits; + } + } + px4_leave_critical_section(flags); } @@ -530,33 +583,35 @@ int io_timer_init_timer(unsigned timer, io_timer_channel_mode_t mode) break; } - uint32_t first_channel_index = io_timers_channel_mapping.element[timer].first_channel_index; - uint32_t last_channel_index = first_channel_index + io_timers_channel_mapping.element[timer].channel_count; - - for (uint32_t chan = first_channel_index; chan < last_channel_index; chan++) { - - /* Clear all Faults */ - rFSTS0(timer) = FSTS_FFLAG_MASK; - - rCTRL2(timer, timer_io_channels[chan].sub_module) = SMCTRL2_CLK_SEL_EXT_CLK | SMCTRL2_DBGEN | SMCTRL2_INDEP; - rCTRL(timer, timer_io_channels[chan].sub_module) = SMCTRL_PRSC_DIV16 | SMCTRL_FULL; - /* Edge aligned at 0 */ - rINIT(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; - rVAL0(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; - rVAL2(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; - rVAL4(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; - rFFILT0(timer) &= ~FFILT_FILT_PER_MASK; - rDISMAP0(timer, timer_io_channels[chan].sub_module) = 0xf000; - rDISMAP1(timer, timer_io_channels[chan].sub_module) = 0xf000; - rOUTEN(timer) |= timer_io_channels[chan].val_offset == PWMA_VAL ? OUTEN_PWMA_EN(1 << timer_io_channels[chan].sub_module) - : OUTEN_PWMB_EN(1 << timer_io_channels[chan].sub_module); - rDTSRCSEL(timer) = 0; - rMCTRL(timer) = MCTRL_LDOK(1 << timer_io_channels[chan].sub_module); - rMCTRL(timer) = timer_io_channels[chan].sub_module_bits; - io_timer_set_PWM_mode(chan); - timer_set_rate(chan, 50); + int channels = get_timer_channels(timer); + + for (uint32_t chan = 0; chan < DIRECT_PWM_OUTPUT_CHANNELS; ++chan) { + if ((1 << chan) & channels) { + + /* Clear all Faults */ + rFSTS0(timer) = FSTS_FFLAG_MASK; + + rCTRL2(timer, timer_io_channels[chan].sub_module) = SMCTRL2_CLK_SEL_EXT_CLK | SMCTRL2_DBGEN | SMCTRL2_INDEP; + rCTRL(timer, timer_io_channels[chan].sub_module) = SMCTRL_PRSC_DIV16 | SMCTRL_FULL; + /* Edge aligned at 0 */ + rINIT(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; + rVAL0(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; + rVAL2(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; + rVAL4(channels_timer(chan), timer_io_channels[chan].sub_module) = 0; + rFFILT0(timer) &= ~FFILT_FILT_PER_MASK; + rDISMAP0(timer, timer_io_channels[chan].sub_module) = 0xf000; + rDISMAP1(timer, timer_io_channels[chan].sub_module) = 0xf000; + rOUTEN(timer) |= timer_io_channels[chan].val_offset == PWMA_VAL ? OUTEN_PWMA_EN(1 << timer_io_channels[chan].sub_module) + : OUTEN_PWMB_EN(1 << timer_io_channels[chan].sub_module); + rDTSRCSEL(timer) = 0; + rMCTRL(timer) = MCTRL_LDOK(1 << timer_io_channels[chan].sub_module); + rMCTRL(timer) = timer_io_channels[chan].sub_module_bits; + } } + io_timer_set_PWM_mode(timer); + timer_set_rate(timer, 50); + px4_leave_critical_section(flags); } @@ -818,8 +873,7 @@ uint16_t io_channel_get_ccr(unsigned channel) return value; } -// The rt has 1:1 group to channel -uint32_t io_timer_get_group(unsigned group) +uint32_t io_timer_get_group(unsigned timer) { - return get_channel_mask(group); + return get_timer_channels(timer); } From 902712b97fb5891355071770e06dd964c8a3b076 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Mon, 29 Apr 2024 12:02:09 +1000 Subject: [PATCH 166/652] LogMessage.msg - expand out descriptive string (#23054) --- msg/LogMessage.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/LogMessage.msg b/msg/LogMessage.msg index 3ea1de23dd47..afb690b145c0 100644 --- a/msg/LogMessage.msg +++ b/msg/LogMessage.msg @@ -1,4 +1,4 @@ -# A logging message, output with PX4_{WARN,ERR,INFO} +# A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO uint64 timestamp # time since system start (microseconds) From 6435e2592932de551da5ab21522abff33551e95c Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 19 Apr 2024 14:08:35 +0300 Subject: [PATCH 167/652] commander: Use PX4_STACK_ADJUSTED to increase stack for 64-bit targets Signed-off-by: Jukka Laitinen --- src/modules/commander/Commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 8efd9b1bbaab..c4e3d331e45d 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -2634,7 +2634,7 @@ int Commander::task_spawn(int argc, char *argv[]) _task_id = px4_task_spawn_cmd("commander", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT + 40, - 3250, + PX4_STACK_ADJUSTED(3250), (px4_main_t)&run_trampoline, (char *const *)argv); From 9dc7719d4a8c989459ff57a7843fe9d86cb25eab Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 26 Apr 2024 09:06:31 +0200 Subject: [PATCH 168/652] ekf2: Only reset to GNSS heading if necessary When North-East (e.g.: GNSS pos/vel) aiding is active, the heading estimate is constrained and consistent with the vel/pos aiding. Reset to GNSS heading should only occur if no N-E aiding is active or if the filter is not yes aligned. Otherwise, just wait for the consistency check to pass again (will pass at some point if the heading uncertainty of the filter is getting too high). --- src/modules/ekf2/EKF/ekf.h | 1 - src/modules/ekf2/EKF/gps_control.cpp | 46 +++++++++------------- src/modules/ekf2/test/test_EKF_gps_yaw.cpp | 22 +++++------ 3 files changed, 30 insertions(+), 39 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index b0ca385d909e..fd3cdbd18cfb 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -672,7 +672,6 @@ class Ekf final : public EstimatorInterface # if defined(CONFIG_EKF2_GNSS_YAW) estimator_aid_source1d_s _aid_src_gnss_yaw{}; - uint8_t _nb_gps_yaw_reset_available{0}; ///< remaining number of resets allowed before switching to another aiding source # endif // CONFIG_EKF2_GNSS_YAW #endif // CONFIG_EKF2_GNSS diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/gps_control.cpp index d8a6b26522e3..a88bb5739c16 100644 --- a/src/modules/ekf2/EKF/gps_control.cpp +++ b/src/modules/ekf2/EKF/gps_control.cpp @@ -358,7 +358,6 @@ void Ekf::controlGpsYawFusion(const gnssSample &gps_sample) && !_gps_intermittent; if (_control_status.flags.gps_yaw) { - if (continuing_conditions_passing) { fuseGpsYaw(gps_sample.yaw_offset); @@ -366,27 +365,7 @@ void Ekf::controlGpsYawFusion(const gnssSample &gps_sample) const bool is_fusion_failing = isTimedOut(_aid_src_gnss_yaw.time_last_fuse, _params.reset_timeout_max); if (is_fusion_failing) { - if (_nb_gps_yaw_reset_available > 0) { - // Data seems good, attempt a reset - resetYawToGps(gps_sample.yaw, gps_sample.yaw_offset); - - if (_control_status.flags.in_air) { - _nb_gps_yaw_reset_available--; - } - - } else if (starting_conditions_passing) { - // Data seems good, but previous reset did not fix the issue - // something else must be wrong, declare the sensor faulty and stop the fusion - _control_status.flags.gps_yaw_fault = true; - stopGpsYawFusion(); - - } else { - // A reset did not fix the issue but all the starting checks are not passing - // This could be a temporary issue, stop the fusion without declaring the sensor faulty - stopGpsYawFusion(); - } - - // TODO: should we give a new reset credit when the fusion does not fail for some time? + stopGpsYawFusion(); } } else { @@ -397,14 +376,27 @@ void Ekf::controlGpsYawFusion(const gnssSample &gps_sample) } else { if (starting_conditions_passing) { // Try to activate GPS yaw fusion - if (resetYawToGps(gps_sample.yaw, gps_sample.yaw_offset)) { - ECL_INFO("starting GPS yaw fusion"); + const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; + + if (!_control_status.flags.in_air + || !_control_status.flags.yaw_align + || not_using_ne_aiding) { - _aid_src_gnss_yaw.time_last_fuse = _time_delayed_us; + // Reset before starting the fusion + if (resetYawToGps(gps_sample.yaw, gps_sample.yaw_offset)) { + _aid_src_gnss_yaw.time_last_fuse = _time_delayed_us; + _control_status.flags.gps_yaw = true; + _control_status.flags.yaw_align = true; + } + + } else if (!_aid_src_gnss_yaw.innovation_rejected) { + // Do not force a reset but wait for the consistency check to pass _control_status.flags.gps_yaw = true; - _control_status.flags.yaw_align = true; + fuseGpsYaw(gps_sample.yaw_offset); + } - _nb_gps_yaw_reset_available = 1; + if (_control_status.flags.gps_yaw) { + ECL_INFO("starting GPS yaw fusion"); } } } diff --git a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp index 2c3afc655ac4..9fd8c4b17949 100644 --- a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp +++ b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp @@ -275,9 +275,15 @@ TEST_F(EkfGpsHeadingTest, yawJmpOnGround) _sensor_simulator._gps.setYaw(gps_heading); _sensor_simulator.runSeconds(8); - // THEN: the fusion should reset - EXPECT_TRUE(_ekf_wrapper.isIntendingGpsHeadingFusion()); + // THEN: the fusion should stop, reset to mag + EXPECT_FALSE(_ekf_wrapper.isIntendingGpsHeadingFusion()); + EXPECT_TRUE(_ekf_wrapper.isIntendingMagHeadingFusion()); EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 1); + + // AND THEN: restart GNSS yaw fusion + _sensor_simulator.runSeconds(5); + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsHeadingFusion()); + EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 2); EXPECT_LT(fabsf(matrix::wrap_pi(_ekf_wrapper.getYawAngle() - gps_heading)), math::radians(1.f)); } @@ -285,7 +291,7 @@ TEST_F(EkfGpsHeadingTest, yawJumpInAir) { // GIVEN: the GPS yaw fusion activated float gps_heading = _ekf_wrapper.getYawAngle(); - _sensor_simulator._gps.setYaw(gps_heading); + _sensor_simulator._gps.setYaw(gps_heading + math::radians(90.f)); _sensor_simulator.runSeconds(5); _ekf->set_in_air_status(true); @@ -295,20 +301,14 @@ TEST_F(EkfGpsHeadingTest, yawJumpInAir) _sensor_simulator._gps.setYaw(gps_heading); _sensor_simulator.runSeconds(7.5); - // THEN: the fusion should reset - EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 1); - - // BUT WHEN: the measurement jumps a 2nd time - gps_heading = matrix::wrap_pi(_ekf_wrapper.getYawAngle() + math::radians(180.f)); - _sensor_simulator._gps.setYaw(gps_heading); - _sensor_simulator.runSeconds(7.5); + // THEN: the fusion should not reset as heading is still observable through GNSS vel/pos fusion + EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter); // THEN: after a few seconds, the fusion should stop and // the estimator doesn't fall back to mag fusion because it has // been declared inconsistent with the filter states EXPECT_FALSE(_ekf_wrapper.isIntendingGpsHeadingFusion()); EXPECT_FALSE(_ekf_wrapper.isMagHeadingConsistent()); - //TODO: should we force a reset to mag if the GNSS yaw fusion was forced to stop? EXPECT_FALSE(_ekf_wrapper.isIntendingMagHeadingFusion()); } From 547209e1dc0b6e31501472178891c2a7a2b30579 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 16 Apr 2024 10:48:49 +0200 Subject: [PATCH 169/652] libevents: update submodule And remove obsolete libevents_definitions.h --- .../common/include/libevents_definitions.h | 48 ------------------- .../include/px4_platform_common/events.h | 8 ++-- src/lib/events/events.cpp | 2 +- src/lib/events/events_ioctl.h | 2 +- src/lib/events/libevents | 2 +- src/lib/events/usr_events.cpp | 2 +- .../HealthAndArmingChecks/Common.cpp | 2 +- .../HealthAndArmingChecks/Common.hpp | 2 +- 8 files changed, 10 insertions(+), 58 deletions(-) delete mode 100644 platforms/common/include/libevents_definitions.h diff --git a/platforms/common/include/libevents_definitions.h b/platforms/common/include/libevents_definitions.h deleted file mode 100644 index 4706a20693ba..000000000000 --- a/platforms/common/include/libevents_definitions.h +++ /dev/null @@ -1,48 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 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. - * - ****************************************************************************/ - -/* - * This header defines the events::EventType type. - */ - -#pragma once - -#include - -namespace events -{ -using EventType = event_s; -} // namespace events - - - diff --git a/platforms/common/include/px4_platform_common/events.h b/platforms/common/include/px4_platform_common/events.h index b7356bed3de2..b3dad933ba54 100644 --- a/platforms/common/include/px4_platform_common/events.h +++ b/platforms/common/include/px4_platform_common/events.h @@ -45,7 +45,7 @@ #endif #include -#include +#include #include @@ -93,7 +93,7 @@ constexpr unsigned sizeofArguments(const T &t, const Args &... args) /** * publish/send an event */ -void send(EventType &event); +void send(event_s &event); /** * Generate event ID from an event name @@ -109,7 +109,7 @@ constexpr uint32_t ID(const char (&name)[N]) template inline void send(uint32_t id, const LogLevels &log_levels, const char *message, Args... args) { - EventType e{}; + event_s e{}; e.log_levels = ((uint8_t)log_levels.internal << 4) | (uint8_t)log_levels.external; e.id = id; static_assert(util::sizeofArguments(args...) <= sizeof(e.arguments), "Too many arguments"); @@ -120,7 +120,7 @@ inline void send(uint32_t id, const LogLevels &log_levels, const char *message, inline void send(uint32_t id, const LogLevels &log_levels, const char *message) { - EventType e{}; + event_s e{}; e.log_levels = ((uint8_t)log_levels.internal << 4) | (uint8_t)log_levels.external; e.id = id; CONSOLE_PRINT_EVENT(e.log_level_external, e.id, message); diff --git a/src/lib/events/events.cpp b/src/lib/events/events.cpp index 9bb215d3561f..2cac17c3f1e5 100644 --- a/src/lib/events/events.cpp +++ b/src/lib/events/events.cpp @@ -45,7 +45,7 @@ static uint16_t event_sequence{events::initial_event_sequence}; namespace events { -void send(EventType &event) +void send(event_s &event) { event.timestamp = hrt_absolute_time(); diff --git a/src/lib/events/events_ioctl.h b/src/lib/events/events_ioctl.h index 7b97c66aa41a..e3b6b0e07461 100644 --- a/src/lib/events/events_ioctl.h +++ b/src/lib/events/events_ioctl.h @@ -47,5 +47,5 @@ #define EVENTSIOCSEND _EVENTSIOC(1) typedef struct eventiocsend { - events::EventType &event; + event_s &event; } eventiocsend_t; diff --git a/src/lib/events/libevents b/src/lib/events/libevents index 59f7f5c0ec2e..8d5c44661bf7 160000 --- a/src/lib/events/libevents +++ b/src/lib/events/libevents @@ -1 +1 @@ -Subproject commit 59f7f5c0ec2e76fadbc1dc40cc0705d614472edc +Subproject commit 8d5c44661bf79106361eb0b5170025b86e85a525 diff --git a/src/lib/events/usr_events.cpp b/src/lib/events/usr_events.cpp index a2f076d06555..e989437a7734 100644 --- a/src/lib/events/usr_events.cpp +++ b/src/lib/events/usr_events.cpp @@ -44,7 +44,7 @@ namespace events { -void send(EventType &event) +void send(event_s &event) { eventiocsend_t data = {event}; boardctl(EVENTSIOCSEND, reinterpret_cast(&data)); diff --git a/src/modules/commander/HealthAndArmingChecks/Common.cpp b/src/modules/commander/HealthAndArmingChecks/Common.cpp index 678d26636b64..796427180fee 100644 --- a/src/modules/commander/HealthAndArmingChecks/Common.cpp +++ b/src/modules/commander/HealthAndArmingChecks/Common.cpp @@ -284,7 +284,7 @@ bool Report::report(bool is_armed, bool force) // send all events int offset = 0; - events::EventType event; + event_s event; for (int i = 0; i < max_num_events && offset < _next_buffer_idx; ++i) { EventBufferHeader *header = (EventBufferHeader *)(_event_buffer + offset); diff --git a/src/modules/commander/HealthAndArmingChecks/Common.hpp b/src/modules/commander/HealthAndArmingChecks/Common.hpp index 9c16c6203d7a..da7c5c296509 100644 --- a/src/modules/commander/HealthAndArmingChecks/Common.hpp +++ b/src/modules/commander/HealthAndArmingChecks/Common.hpp @@ -376,7 +376,7 @@ bool Report::addEvent(uint32_t event_id, const events::LogLevels &log_levels, co Args... args) { constexpr unsigned args_size = events::util::sizeofArguments(modes, args...); - static_assert(args_size <= sizeof(events::EventType::arguments), "Too many arguments"); + static_assert(args_size <= sizeof(event_s::arguments), "Too many arguments"); unsigned total_size = sizeof(EventBufferHeader) + args_size; if (total_size > sizeof(_event_buffer) - _next_buffer_idx) { From b6da0b141d9945128bc069a9a5a25f3c3c86893e Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 29 Apr 2024 21:04:21 -0400 Subject: [PATCH 170/652] ekf2: GPS yaw only invalidate yaw_align if stopping due to fusion failure --- src/modules/ekf2/EKF/gps_control.cpp | 17 ++++++++--------- src/modules/ekf2/test/test_EKF_gps_yaw.cpp | 6 +++--- 2 files changed, 11 insertions(+), 12 deletions(-) diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/gps_control.cpp index a88bb5739c16..f0d2c24270a3 100644 --- a/src/modules/ekf2/EKF/gps_control.cpp +++ b/src/modules/ekf2/EKF/gps_control.cpp @@ -366,6 +366,13 @@ void Ekf::controlGpsYawFusion(const gnssSample &gps_sample) if (is_fusion_failing) { stopGpsYawFusion(); + + // Before takeoff, we do not want to continue to rely on the current heading + // if we had to stop the fusion + if (!_control_status.flags.in_air) { + ECL_INFO("clearing yaw alignment"); + _control_status.flags.yaw_align = false; + } } } else { @@ -416,15 +423,7 @@ void Ekf::stopGpsYawFusion() _control_status.flags.gps_yaw = false; resetEstimatorAidStatus(_aid_src_gnss_yaw); - // Before takeoff, we do not want to continue to rely on the current heading - // if we had to stop the fusion - if (!_control_status.flags.in_air) { - ECL_INFO("stopping GPS yaw fusion, clearing yaw alignment"); - _control_status.flags.yaw_align = false; - - } else { - ECL_INFO("stopping GPS yaw fusion"); - } + ECL_INFO("stopping GPS yaw fusion"); } } #endif // CONFIG_EKF2_GNSS_YAW diff --git a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp index 9fd8c4b17949..93dd222375f9 100644 --- a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp +++ b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp @@ -204,7 +204,7 @@ TEST_F(EkfGpsHeadingTest, fallBackToMag) EXPECT_FALSE(_ekf_wrapper.isIntendingMagHeadingFusion()); EXPECT_FALSE(_ekf_wrapper.isIntendingMag3DFusion()); - const int initial_quat_reset_counter = _ekf_wrapper.getQuaternionResetCounter(); + //const int initial_quat_reset_counter = _ekf_wrapper.getQuaternionResetCounter(); // BUT WHEN: the GPS yaw is suddenly invalid gps_heading = NAN; @@ -215,7 +215,7 @@ TEST_F(EkfGpsHeadingTest, fallBackToMag) // the estimator should fall back to mag fusion EXPECT_FALSE(_ekf_wrapper.isIntendingGpsHeadingFusion()); EXPECT_TRUE(_ekf_wrapper.isIntendingMagHeadingFusion()); - EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 1); + //EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 1); } TEST_F(EkfGpsHeadingTest, fallBackToYawEmergencyEstimator) @@ -328,7 +328,7 @@ TEST_F(EkfGpsHeadingTest, stopOnGround) // THEN: the fusion should stop and the GPS pos/vel aiding // should stop as well because the yaw is not aligned anymore EXPECT_FALSE(_ekf_wrapper.isIntendingGpsHeadingFusion()); - EXPECT_FALSE(_ekf_wrapper.isIntendingGpsFusion()); + //EXPECT_FALSE(_ekf_wrapper.isIntendingGpsFusion()); // AND IF: the mag fusion type is set to NONE _ekf_wrapper.setMagFuseTypeNone(); From 67b39314bf8981fd803f7cf1d06b43d7e5680de7 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Tue, 30 Apr 2024 18:25:07 -0600 Subject: [PATCH 171/652] boards: update ark_pi6x EKF delays --- boards/ark/pi6x/init/rc.board_defaults | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/boards/ark/pi6x/init/rc.board_defaults b/boards/ark/pi6x/init/rc.board_defaults index 03134c887801..50c60d5f837a 100644 --- a/boards/ark/pi6x/init/rc.board_defaults +++ b/boards/ark/pi6x/init/rc.board_defaults @@ -32,17 +32,17 @@ then param set-default SENS_TEMP_ID 2490378 fi -param set-default EKF2_BARO_DELAY 13 +param set-default EKF2_BARO_DELAY 39 param set-default EKF2_BARO_NOISE 0.9 -param set-default EKF2_HGT_REF 2 -param set-default EKF2_MAG_DELAY 100 +param set-default EKF2_HGT_REF 0 +param set-default EKF2_MAG_DELAY 60 param set-default EKF2_MAG_NOISE 0.06 param set-default EKF2_MULTI_IMU 2 param set-default EKF2_OF_CTRL 1 -param set-default EKF2_OF_DELAY 48 +param set-default EKF2_OF_DELAY 28 param set-default EKF2_OF_N_MIN 0.05 param set-default EKF2_RNG_A_HMAX 25 -param set-default EKF2_RNG_DELAY 48 +param set-default EKF2_RNG_DELAY 105 param set-default EKF2_RNG_NOISE 0.03 param set-default EKF2_RNG_QLTY_T 0.1 param set-default EKF2_RNG_SFE 0.03 From 2498ce6a5cbdc63a7bf5d30025fae994c62b9adc Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Tue, 30 Apr 2024 18:47:28 -0600 Subject: [PATCH 172/652] boards: add iis2mdc mag to ark pi6x --- boards/ark/pi6x/default.px4board | 1 + boards/ark/pi6x/init/rc.board_sensors | 6 ++++-- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 98f6300f579c..45f992d69eed 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -15,6 +15,7 @@ CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_COMMON_LIGHT=y CONFIG_DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA=y +CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_PWM_OUT=y diff --git a/boards/ark/pi6x/init/rc.board_sensors b/boards/ark/pi6x/init/rc.board_sensors index 647e685c7f43..cc97b1d601fd 100644 --- a/boards/ark/pi6x/init/rc.board_sensors +++ b/boards/ark/pi6x/init/rc.board_sensors @@ -21,8 +21,10 @@ then fi # Internal magnetometer on I2C -# TODO: Write a driver for the MMC5983MA -mmc5983ma -I -b 4 start +if ! iis2mdc -R 4 -I -b 4 start +then + mmc5983ma -I -b 4 start +fi # Internal Baro on I2C bmp388 -I -b 4 start From c90ccabbe0af9580878e975ce82cead3c4760ded Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Mon, 12 Feb 2024 15:00:26 -0700 Subject: [PATCH 173/652] gps: add ZED-F9P-15B --- boards/ark/can-rtk-gps/init/rc.board_defaults | 1 + src/drivers/gps/devices | 2 +- src/drivers/gps/params.c | 8 ++++++-- 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/boards/ark/can-rtk-gps/init/rc.board_defaults b/boards/ark/can-rtk-gps/init/rc.board_defaults index c50d81602629..99b30c747f8a 100644 --- a/boards/ark/can-rtk-gps/init/rc.board_defaults +++ b/boards/ark/can-rtk-gps/init/rc.board_defaults @@ -6,6 +6,7 @@ param set-default CBRK_IO_SAFETY 0 param set-default CANNODE_SUB_MBD 1 param set-default CANNODE_SUB_RTCM 1 +param set-default GPS_1_GNSS 63 param set-default MBE_ENABLE 1 param set-default SENS_IMU_CLPNOTI 0 diff --git a/src/drivers/gps/devices b/src/drivers/gps/devices index 17c0e2bfad1e..d92cf3a2b270 160000 --- a/src/drivers/gps/devices +++ b/src/drivers/gps/devices @@ -1 +1 @@ -Subproject commit 17c0e2bfad1e544c4b11329c742630a765c7537f +Subproject commit d92cf3a2b2704d5509b651bfca33cdfea3a7a18a diff --git a/src/drivers/gps/params.c b/src/drivers/gps/params.c index 49b4da7065bf..de58e9e90795 100644 --- a/src/drivers/gps/params.c +++ b/src/drivers/gps/params.c @@ -247,14 +247,16 @@ PARAM_DEFINE_INT32(GPS_2_PROTOCOL, 1); * 2 : Use Galileo * 3 : Use BeiDou * 4 : Use GLONASS + * 5 : Use NAVIC * * @min 0 - * @max 31 + * @max 63 * @bit 0 GPS (with QZSS) * @bit 1 SBAS * @bit 2 Galileo * @bit 3 BeiDou * @bit 4 GLONASS + * @bit 5 NAVIC * * @reboot_required true * @group GPS @@ -277,14 +279,16 @@ PARAM_DEFINE_INT32(GPS_1_GNSS, 0); * 2 : Use Galileo * 3 : Use BeiDou * 4 : Use GLONASS + * 5 : Use NAVIC * * @min 0 - * @max 31 + * @max 63 * @bit 0 GPS (with QZSS) * @bit 1 SBAS * @bit 2 Galileo * @bit 3 BeiDou * @bit 4 GLONASS + * @bit 5 NAVIC * * @reboot_required true * @group GPS From b308c4fbcc308e715de8ccddd97c64fe48d305e3 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Mon, 12 Feb 2024 16:06:55 -0700 Subject: [PATCH 174/652] boards: ark rtk gps safety led open drain --- boards/ark/can-rtk-gps/src/board_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/ark/can-rtk-gps/src/board_config.h b/boards/ark/can-rtk-gps/src/board_config.h index 2263956bae0f..2d5f582075f1 100644 --- a/boards/ark/can-rtk-gps/src/board_config.h +++ b/boards/ark/can-rtk-gps/src/board_config.h @@ -47,7 +47,7 @@ #define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15) /* Safety LED */ -#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1) +#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1) /* Tone alarm output. */ #define TONE_ALARM_TIMER 2 /* timer 2 */ From e79993a316162f170cb28f444b875decc8f73e2d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 27 Mar 2024 17:12:30 +1300 Subject: [PATCH 175/652] gps: split enum after rebase Signed-off-by: Julian Oes --- src/drivers/gps/gps.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index fe6f82ec7fbc..ce46883c9cf4 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -939,7 +939,8 @@ GPS::run() set_device_type(DRV_GPS_DEVTYPE_UBX_9); break; - case GPSDriverUBX::Board::u_blox9_F9P: + case GPSDriverUBX::Board::u_blox9_F9P_L1L2: + case GPSDriverUBX::Board::u_blox9_F9P_L1L5: set_device_type(DRV_GPS_DEVTYPE_UBX_F9P); break; From 33234f4dc0fc881e9559bbb71a4af2ac6dd6a94d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 14:31:10 -0400 Subject: [PATCH 176/652] drivers/ins/vectornav: add missing sensor_gps velocity magnitude --- src/drivers/ins/vectornav/VectorNav.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/ins/vectornav/VectorNav.cpp b/src/drivers/ins/vectornav/VectorNav.cpp index 369e56298ead..991b1262958f 100644 --- a/src/drivers/ins/vectornav/VectorNav.cpp +++ b/src/drivers/ins/vectornav/VectorNav.cpp @@ -441,10 +441,11 @@ void VectorNav::sensorCallback(VnUartPacket *packet) sensor_gps.altitude_msl_m = positionGpsLla.c[2]; sensor_gps.altitude_ellipsoid_m = sensor_gps.altitude_msl_m; - sensor_gps.vel_ned_valid = true; + sensor_gps.vel_m_s = matrix::Vector3f(velocityGpsNed.c).length(); sensor_gps.vel_n_m_s = velocityGpsNed.c[0]; sensor_gps.vel_e_m_s = velocityGpsNed.c[1]; sensor_gps.vel_d_m_s = velocityGpsNed.c[2]; + sensor_gps.vel_ned_valid = true; sensor_gps.hdop = dop.hDOP; sensor_gps.vdop = dop.vDOP; From a3e1dcce4ba0902251e778bd3b01dba090758536 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 16 Apr 2024 07:37:47 -0700 Subject: [PATCH 177/652] NuttX with imxrt_sd-preflight backport --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index cc880bbecd21..4be592dd2114 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit cc880bbecd215f5541e4b6d922123fc46f8ccb72 +Subproject commit 4be592dd2114d2c07505b143493a3cfa6dc9c239 From c13e3bae1237ded25fa91e97176b86fed34896a0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 16 Apr 2024 07:38:53 -0700 Subject: [PATCH 178/652] px4_fmu-v6xrt:Support_MMCSD_MULTIBLOCK with preflight --- boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index 98431d0420b0..fe4f46860b8e 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -185,7 +185,6 @@ CONFIG_LPUART8_TXDMA=y CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y -CONFIG_MMCSD_MULTIBLOCK_LIMIT=1 CONFIG_MMCSD_SDIO=y CONFIG_MTD=y CONFIG_MTD_BYTE_WRITE=y From c64104e9f18906fcfa4fbfdb463ef9e33ee355f0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 19:05:13 -0400 Subject: [PATCH 179/652] sensors/vehicle_angular_velocity: silence gyro selection fallback warning (PX4_WARN -> PX4_DEBUG) - this warning was to catch any potential errors in sensor selection relative to what's actually available, we don't need to complain about initial selection before the EKF selector is available --- .../vehicle_angular_velocity/VehicleAngularVelocity.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp b/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp index b1eac451529a..01750b42598b 100644 --- a/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp +++ b/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp @@ -277,7 +277,7 @@ bool VehicleAngularVelocity::SensorSelectionUpdate(const hrt_abstime &time_now_u // if no gyro was selected use the first valid sensor_gyro_fifo if (!device_id_valid) { device_id = sensor_gyro_fifo_sub.get().device_id; - PX4_WARN("no gyro selected, using sensor_gyro_fifo:%" PRIu8 " %" PRIu32, i, sensor_gyro_fifo_sub.get().device_id); + PX4_DEBUG("no gyro selected, using sensor_gyro_fifo:%" PRIu8 " %" PRIu32, i, sensor_gyro_fifo_sub.get().device_id); } if (sensor_gyro_fifo_sub.get().device_id == device_id) { @@ -319,7 +319,7 @@ bool VehicleAngularVelocity::SensorSelectionUpdate(const hrt_abstime &time_now_u // if no gyro was selected use the first valid sensor_gyro if (!device_id_valid) { device_id = sensor_gyro_sub.get().device_id; - PX4_WARN("no gyro selected, using sensor_gyro:%" PRIu8 " %" PRIu32, i, sensor_gyro_sub.get().device_id); + PX4_DEBUG("no gyro selected, using sensor_gyro:%" PRIu8 " %" PRIu32, i, sensor_gyro_sub.get().device_id); } if (sensor_gyro_sub.get().device_id == device_id) { From f382e585e8966326af9c9c6d1eb7745a42d86e8e Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Tue, 30 Apr 2024 13:37:22 +0200 Subject: [PATCH 180/652] sd_bench: Add U option for forcing byte aligned Co-authored-by: David Sidrane --- src/systemcmds/sd_bench/sd_bench.cpp | 57 ++++++++++++++++++++++------ 1 file changed, 45 insertions(+), 12 deletions(-) diff --git a/src/systemcmds/sd_bench/sd_bench.cpp b/src/systemcmds/sd_bench/sd_bench.cpp index edfaff4f5062..6912c5a3368c 100644 --- a/src/systemcmds/sd_bench/sd_bench.cpp +++ b/src/systemcmds/sd_bench/sd_bench.cpp @@ -56,7 +56,7 @@ typedef struct sdb_config { int num_runs; ///< number of runs int run_duration; ///< duration of a single run [ms] bool synchronized; ///< call fsync after each block? - bool aligned; + int unaligned; unsigned int total_blocks_written; } sdb_config_t; @@ -85,6 +85,7 @@ static void usage() PRINT_MODULE_USAGE_PARAM_FLAG('k', "Keep the test file", true); PRINT_MODULE_USAGE_PARAM_FLAG('s', "Call fsync after each block (default=at end of each run)", true); PRINT_MODULE_USAGE_PARAM_FLAG('u', "Test performance with unaligned data", true); + PRINT_MODULE_USAGE_PARAM_FLAG('U', "Test performance with forced byte unaligned data", true); PRINT_MODULE_USAGE_PARAM_FLAG('v', "Verify data and block number", true); } @@ -100,10 +101,11 @@ extern "C" __EXPORT int sd_bench_main(int argc, char *argv[]) cfg.synchronized = false; cfg.num_runs = 5; cfg.run_duration = 2000; - cfg.aligned = true; + cfg.unaligned = 0; uint8_t *block = nullptr; + uint8_t *block_alloc = nullptr; - while ((ch = px4_getopt(argc, argv, "b:r:d:ksuv", &myoptind, &myoptarg)) != EOF) { + while ((ch = px4_getopt(argc, argv, "b:r:d:ksuUv", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'b': block_size = strtol(myoptarg, nullptr, 0); @@ -126,7 +128,11 @@ extern "C" __EXPORT int sd_bench_main(int argc, char *argv[]) break; case 'u': - cfg.aligned = false; + cfg.unaligned = 2; + break; + + case 'U': + cfg.unaligned = 1; break; case 'v': @@ -153,11 +159,24 @@ extern "C" __EXPORT int sd_bench_main(int argc, char *argv[]) } //create some data block - if (cfg.aligned) { - block = (uint8_t *)px4_cache_aligned_alloc(block_size); + if (cfg.unaligned == 0) { + block_alloc = (uint8_t *)px4_cache_aligned_alloc(block_size); + block = block_alloc; } else { - block = (uint8_t *)malloc(block_size); + block_alloc = (uint8_t *)malloc(block_size + 4); + + if (block_alloc) { + // Force odd byte alignment + if (cfg.unaligned == 1 && ((uintptr_t)block_alloc % 0x1) == 0) { + block = block_alloc + 1; + + } else { + block = block_alloc; + } + } + + printf("Block ptr %p\n", block); } if (!block) { @@ -179,7 +198,7 @@ extern "C" __EXPORT int sd_bench_main(int argc, char *argv[]) read_test(bench_fd, &cfg, block, block_size); } - free(block); + free(block_alloc); close(bench_fd); if (!keep) { @@ -259,15 +278,29 @@ void write_test(int fd, sdb_config_t *cfg, uint8_t *block, int block_size) int read_test(int fd, sdb_config_t *cfg, uint8_t *block, int block_size) { uint8_t *read_block = nullptr; + uint8_t *block_alloc = nullptr; PX4_INFO(""); PX4_INFO("Testing Sequential Read Speed of %d blocks", cfg->total_blocks_written); - if (cfg->aligned) { - read_block = (uint8_t *)px4_cache_aligned_alloc(block_size); + if (cfg->unaligned == 0) { + block_alloc = (uint8_t *)px4_cache_aligned_alloc(block_size); + read_block = block_alloc; } else { - read_block = (uint8_t *)malloc(block_size); + block_alloc = (uint8_t *)malloc(block_size + 4); + + if (block_alloc) { + // Force odd byte alignment + if (cfg->unaligned == 1 && ((uintptr_t)block_alloc % 0x1) == 0) { + read_block = block_alloc + 1; + + } else { + read_block = block_alloc; + } + } + + printf("Read Block ptr %p\n", read_block); } if (!read_block) { @@ -331,6 +364,6 @@ int read_test(int fd, sdb_config_t *cfg, uint8_t *block, int block_size) PX4_INFO(" Avg : %8.2lf KB/s %d blocks read and verified", (double)block_size * total_blocks / total_elapsed / 1024., total_blocks); - free(read_block); + free(block_alloc); return 0; } From b5d1e87368af7f7e1edfc49146d3e4dcfc0c0b32 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 13:56:03 -0400 Subject: [PATCH 181/652] ekf2: move EV files to aid_sources/external_vision --- src/modules/ekf2/CMakeLists.txt | 10 +++++----- src/modules/ekf2/EKF/CMakeLists.txt | 10 +++++----- .../{ => aid_sources/external_vision}/ev_control.cpp | 0 .../external_vision}/ev_height_control.cpp | 0 .../external_vision}/ev_pos_control.cpp | 0 .../external_vision}/ev_vel_control.cpp | 0 .../external_vision}/ev_yaw_control.cpp | 0 7 files changed, 10 insertions(+), 10 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/external_vision}/ev_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/external_vision}/ev_height_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/external_vision}/ev_pos_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/external_vision}/ev_vel_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/external_vision}/ev_yaw_control.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 9d42a6e2423b..7b80faa97309 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -160,11 +160,11 @@ endif() if(CONFIG_EKF2_EXTERNAL_VISION) list(APPEND EKF_SRCS - EKF/ev_control.cpp - EKF/ev_height_control.cpp - EKF/ev_pos_control.cpp - EKF/ev_vel_control.cpp - EKF/ev_yaw_control.cpp + EKF/aid_sources/external_vision/ev_control.cpp + EKF/aid_sources/external_vision/ev_height_control.cpp + EKF/aid_sources/external_vision/ev_pos_control.cpp + EKF/aid_sources/external_vision/ev_vel_control.cpp + EKF/aid_sources/external_vision/ev_yaw_control.cpp ) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 69d4edd146c9..45a627fd897a 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -78,11 +78,11 @@ endif() if(CONFIG_EKF2_EXTERNAL_VISION) list(APPEND EKF_SRCS - ev_control.cpp - ev_height_control.cpp - ev_pos_control.cpp - ev_vel_control.cpp - ev_yaw_control.cpp + aid_sources/external_vision/ev_control.cpp + aid_sources/external_vision/ev_height_control.cpp + aid_sources/external_vision/ev_pos_control.cpp + aid_sources/external_vision/ev_vel_control.cpp + aid_sources/external_vision/ev_yaw_control.cpp ) endif() diff --git a/src/modules/ekf2/EKF/ev_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/ev_control.cpp rename to src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp diff --git a/src/modules/ekf2/EKF/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/ev_height_control.cpp rename to src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp diff --git a/src/modules/ekf2/EKF/ev_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/ev_pos_control.cpp rename to src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp diff --git a/src/modules/ekf2/EKF/ev_vel_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/ev_vel_control.cpp rename to src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp diff --git a/src/modules/ekf2/EKF/ev_yaw_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/ev_yaw_control.cpp rename to src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp From c3fb0b10908cf9615da042453b8ef6ce84066f40 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 13:57:20 -0400 Subject: [PATCH 182/652] ekf2: move auxvel file to aid_sources/auxvel --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/{ => aid_sources/auxvel}/auxvel_fusion.cpp | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/auxvel}/auxvel_fusion.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 7b80faa97309..f8abff448cfa 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -145,7 +145,7 @@ if(CONFIG_EKF2_AUX_GLOBAL_POSITION) endif() if(CONFIG_EKF2_AUXVEL) - list(APPEND EKF_SRCS EKF/auxvel_fusion.cpp) + list(APPEND EKF_SRCS EKF/aid_sources/auxvel/auxvel_fusion.cpp) endif() if(CONFIG_EKF2_BAROMETER) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 45a627fd897a..ffaada28d292 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -63,7 +63,7 @@ if(CONFIG_EKF2_AUX_GLOBAL_POSITION) endif() if(CONFIG_EKF2_AUXVEL) - list(APPEND EKF_SRCS auxvel_fusion.cpp) + list(APPEND EKF_SRCS aid_sources/auxvel/auxvel_fusion.cpp) endif() if(CONFIG_EKF2_BAROMETER) diff --git a/src/modules/ekf2/EKF/auxvel_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/auxvel_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp From 31ae5b77fe29003e29eed0dae42345d670d9ed4e Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 13:58:58 -0400 Subject: [PATCH 183/652] ekf2: move drag_fusion file to aid_sources/drag --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/{ => aid_sources/drag}/drag_fusion.cpp | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/drag}/drag_fusion.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index f8abff448cfa..72d5a71d885a 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -155,7 +155,7 @@ if(CONFIG_EKF2_BAROMETER) endif() if(CONFIG_EKF2_DRAG_FUSION) - list(APPEND EKF_SRCS EKF/drag_fusion.cpp) + list(APPEND EKF_SRCS EKF/aid_sources/drag/drag_fusion.cpp) endif() if(CONFIG_EKF2_EXTERNAL_VISION) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index ffaada28d292..5f33106b9a02 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -73,7 +73,7 @@ if(CONFIG_EKF2_BAROMETER) endif() if(CONFIG_EKF2_DRAG_FUSION) - list(APPEND EKF_SRCS drag_fusion.cpp) + list(APPEND EKF_SRCS aid_sources/drag/drag_fusion.cpp) endif() if(CONFIG_EKF2_EXTERNAL_VISION) diff --git a/src/modules/ekf2/EKF/drag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/drag_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp From fcf94e76708b032f09e6b34f54cd46a23817c5b2 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 14:00:47 -0400 Subject: [PATCH 184/652] ekf2: move GNSS files to aid_sources/gnss --- src/modules/ekf2/CMakeLists.txt | 16 +++++++--------- src/modules/ekf2/EKF/CMakeLists.txt | 14 +++++++------- .../gnss}/gnss_height_control.cpp | 0 .../EKF/{ => aid_sources/gnss}/gps_checks.cpp | 0 .../EKF/{ => aid_sources/gnss}/gps_control.cpp | 0 .../{ => aid_sources/gnss}/gps_yaw_fusion.cpp | 0 6 files changed, 14 insertions(+), 16 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/gnss}/gnss_height_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/gnss}/gps_checks.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/gnss}/gps_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/gnss}/gps_yaw_fusion.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 72d5a71d885a..c202aa07e001 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -170,16 +170,16 @@ endif() if(CONFIG_EKF2_GNSS) list(APPEND EKF_SRCS - EKF/gnss_height_control.cpp - EKF/gps_checks.cpp - EKF/gps_control.cpp + EKF/aid_sources/gnss/gnss_height_control.cpp + EKF/aid_sources/gnss/gps_checks.cpp + EKF/aid_sources/gnss/gps_control.cpp ) - list(APPEND EKF_LIBS yaw_estimator) -endif() + if(CONFIG_EKF2_GNSS_YAW) + list(APPEND EKF_SRCS EKF/aid_sources/gnss/gps_yaw_fusion.cpp) + endif() -if(CONFIG_EKF2_GNSS_YAW) - list(APPEND EKF_SRCS EKF/gps_yaw_fusion.cpp) + list(APPEND EKF_LIBS yaw_estimator) endif() if(CONFIG_EKF2_GRAVITY_FUSION) @@ -219,8 +219,6 @@ endif() add_subdirectory(EKF) - - px4_add_module( MODULE modules__ekf2 MAIN ekf2 diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 5f33106b9a02..e5d2e9f4d8c2 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -88,19 +88,19 @@ endif() if(CONFIG_EKF2_GNSS) list(APPEND EKF_SRCS - gnss_height_control.cpp - gps_checks.cpp - gps_control.cpp + aid_sources/gnss/gnss_height_control.cpp + aid_sources/gnss/gps_checks.cpp + aid_sources/gnss/gps_control.cpp ) + if(CONFIG_EKF2_GNSS_YAW) + list(APPEND EKF_SRCS aid_sources/gnss/gps_yaw_fusion.cpp) + endif() + add_subdirectory(yaw_estimator) list(APPEND EKF_LIBS yaw_estimator) endif() -if(CONFIG_EKF2_GNSS_YAW) - list(APPEND EKF_SRCS gps_yaw_fusion.cpp) -endif() - if(CONFIG_EKF2_GRAVITY_FUSION) list(APPEND EKF_SRCS gravity_fusion.cpp) endif() diff --git a/src/modules/ekf2/EKF/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/gnss_height_control.cpp rename to src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp diff --git a/src/modules/ekf2/EKF/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp similarity index 100% rename from src/modules/ekf2/EKF/gps_checks.cpp rename to src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/gps_control.cpp rename to src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp diff --git a/src/modules/ekf2/EKF/gps_yaw_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/gps_yaw_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp From 78f2ccbb6003a2f8bfb34c3851d0236b7ac12237 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 14:03:22 -0400 Subject: [PATCH 185/652] ekf2: move optical flow files to aid_sources/optical_flow --- src/modules/ekf2/CMakeLists.txt | 4 ++-- src/modules/ekf2/EKF/CMakeLists.txt | 4 ++-- .../{ => aid_sources/optical_flow}/optical_flow_control.cpp | 0 .../optical_flow/optical_flow_fusion.cpp} | 0 4 files changed, 4 insertions(+), 4 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/optical_flow}/optical_flow_control.cpp (100%) rename src/modules/ekf2/EKF/{optflow_fusion.cpp => aid_sources/optical_flow/optical_flow_fusion.cpp} (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index c202aa07e001..53d188af51de 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -196,8 +196,8 @@ endif() if(CONFIG_EKF2_OPTICAL_FLOW) list(APPEND EKF_SRCS - EKF/optical_flow_control.cpp - EKF/optflow_fusion.cpp + EKF/aid_sources/optical_flow/optical_flow_control.cpp + EKF/aid_sources/optical_flow/optical_flow_fusion.cpp ) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index e5d2e9f4d8c2..efe8a97fa1cf 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -115,8 +115,8 @@ endif() if(CONFIG_EKF2_OPTICAL_FLOW) list(APPEND EKF_SRCS - optical_flow_control.cpp - optflow_fusion.cpp + aid_sources/optical_flow/optical_flow_control.cpp + aid_sources/optical_flow/optical_flow_fusion.cpp ) endif() diff --git a/src/modules/ekf2/EKF/optical_flow_control.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/optical_flow_control.cpp rename to src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp diff --git a/src/modules/ekf2/EKF/optflow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/optflow_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp From de178b1435fc0a0d1e3c73e9177259320df73b36 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 14:04:13 -0400 Subject: [PATCH 186/652] ekf2: move gravity fusion file to aid_sources/gravity --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../ekf2/EKF/{ => aid_sources/gravity}/gravity_fusion.cpp | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/gravity}/gravity_fusion.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 53d188af51de..4c7f3a991e1f 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -183,7 +183,7 @@ if(CONFIG_EKF2_GNSS) endif() if(CONFIG_EKF2_GRAVITY_FUSION) - list(APPEND EKF_SRCS EKF/gravity_fusion.cpp) + list(APPEND EKF_SRCS EKF/aid_sources/gravity/gravity_fusion.cpp) endif() if(CONFIG_EKF2_MAGNETOMETER) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index efe8a97fa1cf..45cbc262410e 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -102,7 +102,7 @@ if(CONFIG_EKF2_GNSS) endif() if(CONFIG_EKF2_GRAVITY_FUSION) - list(APPEND EKF_SRCS gravity_fusion.cpp) + list(APPEND EKF_SRCS aid_sources/gravity/gravity_fusion.cpp) endif() if(CONFIG_EKF2_MAGNETOMETER) diff --git a/src/modules/ekf2/EKF/gravity_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/gravity_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp From eb8ee7406662fcac04c640b824545a5325ecd013 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 14:05:13 -0400 Subject: [PATCH 187/652] ekf2: move baro height file to aid_sources/barometer --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../EKF/{ => aid_sources/barometer}/baro_height_control.cpp | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/barometer}/baro_height_control.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 4c7f3a991e1f..1ab6700348e7 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -150,7 +150,7 @@ endif() if(CONFIG_EKF2_BAROMETER) list(APPEND EKF_SRCS - EKF/baro_height_control.cpp + EKF/aid_sources/barometer/baro_height_control.cpp ) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 45cbc262410e..a0ff48037743 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -68,7 +68,7 @@ endif() if(CONFIG_EKF2_BAROMETER) list(APPEND EKF_SRCS - baro_height_control.cpp + aid_sources/barometer/baro_height_control.cpp ) endif() diff --git a/src/modules/ekf2/EKF/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/baro_height_control.cpp rename to src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp From 789b2b3d8a6ef1fe30b3a801b5425f95716ebc9a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 14:07:14 -0400 Subject: [PATCH 188/652] ekf2: move sideslip fusion file to aid_sources/sideslip --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../ekf2/EKF/{ => aid_sources/sideslip}/sideslip_fusion.cpp | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/sideslip}/sideslip_fusion.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 1ab6700348e7..b22ba7b1310b 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -210,7 +210,7 @@ if(CONFIG_EKF2_RANGE_FINDER) endif() if(CONFIG_EKF2_SIDESLIP) - list(APPEND EKF_SRCS EKF/sideslip_fusion.cpp) + list(APPEND EKF_SRCS EKF/aid_sources/sideslip/sideslip_fusion.cpp) endif() if(CONFIG_EKF2_TERRAIN) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index a0ff48037743..1c2fd181218b 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -129,7 +129,7 @@ if(CONFIG_EKF2_RANGE_FINDER) endif() if(CONFIG_EKF2_SIDESLIP) - list(APPEND EKF_SRCS sideslip_fusion.cpp) + list(APPEND EKF_SRCS aid_sources/sideslip/sideslip_fusion.cpp) endif() if(CONFIG_EKF2_TERRAIN) diff --git a/src/modules/ekf2/EKF/sideslip_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/sideslip_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp From 3dbd3f8a1abc86f3e81f18029724f625e1f94ee1 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 14:09:01 -0400 Subject: [PATCH 189/652] ekf2: move airspeed fusion file to aid_sources/airspeed --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../ekf2/EKF/{ => aid_sources/airspeed}/airspeed_fusion.cpp | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/airspeed}/airspeed_fusion.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index b22ba7b1310b..4d59bcffd7c1 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -137,7 +137,7 @@ list(APPEND EKF_SRCS ) if(CONFIG_EKF2_AIRSPEED) - list(APPEND EKF_SRCS EKF/airspeed_fusion.cpp) + list(APPEND EKF_SRCS EKF/aid_sources/airspeed/airspeed_fusion.cpp) endif() if(CONFIG_EKF2_AUX_GLOBAL_POSITION) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 1c2fd181218b..8dc8c0fad43c 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -55,7 +55,7 @@ list(APPEND EKF_SRCS ) if(CONFIG_EKF2_AIRSPEED) - list(APPEND EKF_SRCS airspeed_fusion.cpp) + list(APPEND EKF_SRCS aid_sources/airspeed/airspeed_fusion.cpp) endif() if(CONFIG_EKF2_AUX_GLOBAL_POSITION) diff --git a/src/modules/ekf2/EKF/airspeed_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/airspeed_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp From 24fdd696cbb98a9870b605e6410246b06ac4288c Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 4 Apr 2024 14:21:56 -0400 Subject: [PATCH 190/652] ekf2: move range finder files to aid_sources/range_finder --- src/modules/ekf2/CMakeLists.txt | 6 ++--- src/modules/ekf2/EKF/CMakeLists.txt | 6 ++--- .../{ => aid_sources/range_finder}/Sensor.hpp | 2 +- .../range_finder_consistency_check.cpp | 13 +++++++---- .../range_finder_consistency_check.hpp | 0 .../range_finder}/range_height_control.cpp | 23 +++++++++++++------ .../range_finder}/sensor_range_finder.cpp | 10 ++++---- .../range_finder}/sensor_range_finder.hpp | 9 ++++++++ src/modules/ekf2/EKF/common.h | 7 ------ src/modules/ekf2/EKF/estimator_interface.cpp | 6 ++--- src/modules/ekf2/EKF/estimator_interface.h | 10 ++++---- src/modules/ekf2/EKF2.cpp | 4 ++-- .../ekf2/test/sensor_simulator/range_finder.h | 2 +- .../ekf2/test/test_SensorRangeFinder.cpp | 4 ++-- 14 files changed, 59 insertions(+), 43 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/range_finder}/Sensor.hpp (99%) rename src/modules/ekf2/EKF/{ => aid_sources/range_finder}/range_finder_consistency_check.cpp (88%) rename src/modules/ekf2/EKF/{ => aid_sources/range_finder}/range_finder_consistency_check.hpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/range_finder}/range_height_control.cpp (93%) rename src/modules/ekf2/EKF/{ => aid_sources/range_finder}/sensor_range_finder.cpp (94%) rename src/modules/ekf2/EKF/{ => aid_sources/range_finder}/sensor_range_finder.hpp (93%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 4d59bcffd7c1..c5f9c05fcf17 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -203,9 +203,9 @@ endif() if(CONFIG_EKF2_RANGE_FINDER) list(APPEND EKF_SRCS - EKF/range_finder_consistency_check.cpp - EKF/range_height_control.cpp - EKF/sensor_range_finder.cpp + EKF/aid_sources/range_finder/range_finder_consistency_check.cpp + EKF/aid_sources/range_finder/range_height_control.cpp + EKF/aid_sources/range_finder/sensor_range_finder.cpp ) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 8dc8c0fad43c..a22e3816de6d 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -122,9 +122,9 @@ endif() if(CONFIG_EKF2_RANGE_FINDER) list(APPEND EKF_SRCS - range_finder_consistency_check.cpp - range_height_control.cpp - sensor_range_finder.cpp + aid_sources/range_finder/range_finder_consistency_check.cpp + aid_sources/range_finder/range_height_control.cpp + aid_sources/range_finder/sensor_range_finder.cpp ) endif() diff --git a/src/modules/ekf2/EKF/Sensor.hpp b/src/modules/ekf2/EKF/aid_sources/range_finder/Sensor.hpp similarity index 99% rename from src/modules/ekf2/EKF/Sensor.hpp rename to src/modules/ekf2/EKF/aid_sources/range_finder/Sensor.hpp index e1b83e708b4d..8134418fabf2 100644 --- a/src/modules/ekf2/EKF/Sensor.hpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/Sensor.hpp @@ -42,7 +42,7 @@ #ifndef EKF_SENSOR_HPP #define EKF_SENSOR_HPP -#include "common.h" +#include namespace estimator { diff --git a/src/modules/ekf2/EKF/range_finder_consistency_check.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp similarity index 88% rename from src/modules/ekf2/EKF/range_finder_consistency_check.cpp rename to src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp index 453da560b421..918ab523c0d6 100644 --- a/src/modules/ekf2/EKF/range_finder_consistency_check.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp @@ -35,9 +35,10 @@ * @file range_finder_consistency_check.cpp */ -#include "range_finder_consistency_check.hpp" +#include -void RangeFinderConsistencyCheck::update(float dist_bottom, float dist_bottom_var, float vz, float vz_var, bool horizontal_motion, uint64_t time_us) +void RangeFinderConsistencyCheck::update(float dist_bottom, float dist_bottom_var, float vz, float vz_var, + bool horizontal_motion, uint64_t time_us) { if (horizontal_motion) { _time_last_horizontal_motion = time_us; @@ -55,7 +56,8 @@ void RangeFinderConsistencyCheck::update(float dist_bottom, float dist_bottom_va const float vel_bottom = (dist_bottom - _dist_bottom_prev) / dt; _innov = -vel_bottom - vz; // vel_bottom is +up while vz is +down - const float var = 2.f * dist_bottom_var / (dt * dt); // Variance of the time derivative of a random variable: var(dz/dt) = 2*var(z) / dt^2 + // Variance of the time derivative of a random variable: var(dz/dt) = 2*var(z) / dt^2 + const float var = 2.f * dist_bottom_var / (dt * dt); _innov_var = var + vz_var; const float normalized_innov_sq = (_innov * _innov) / _innov_var; @@ -84,8 +86,9 @@ void RangeFinderConsistencyCheck::updateConsistency(float vz, uint64_t time_us) } } else { - if (_test_ratio < 1.f - && ((time_us - _time_last_inconsistent_us) > _consistency_hyst_time_us)) { + if ((_test_ratio < 1.f) + && ((time_us - _time_last_inconsistent_us) > _consistency_hyst_time_us) + ) { _is_kinematically_consistent = true; } } diff --git a/src/modules/ekf2/EKF/range_finder_consistency_check.hpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.hpp similarity index 100% rename from src/modules/ekf2/EKF/range_finder_consistency_check.hpp rename to src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.hpp diff --git a/src/modules/ekf2/EKF/range_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp similarity index 93% rename from src/modules/ekf2/EKF/range_height_control.cpp rename to src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp index 8fede499e5a2..8b4b96712d47 100644 --- a/src/modules/ekf2/EKF/range_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp @@ -64,13 +64,14 @@ void Ekf::controlRangeHeightFusion() if (_control_status.flags.in_air) { const bool horizontal_motion = _control_status.flags.fixed_wing - || (sq(_state.vel(0)) + sq(_state.vel(1)) > fmaxf(P.trace<2>(State::vel.idx), 0.1f)); + || (sq(_state.vel(0)) + sq(_state.vel(1)) > fmaxf(P.trace<2>(State::vel.idx), 0.1f)); const float dist_dependant_var = sq(_params.range_noise_scaler * _range_sensor.getDistBottom()); const float var = sq(_params.range_noise) + dist_dependant_var; _rng_consistency_check.setGate(_params.range_kin_consistency_gate); - _rng_consistency_check.update(_range_sensor.getDistBottom(), math::max(var, 0.001f), _state.vel(2), P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, _time_delayed_us); + _rng_consistency_check.update(_range_sensor.getDistBottom(), math::max(var, 0.001f), _state.vel(2), + P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, _time_delayed_us); } } else { @@ -121,13 +122,15 @@ void Ekf::controlRangeHeightFusion() } // determine if we should use height aiding - const bool do_conditional_range_aid = (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) && isConditionalRangeAidSuitable(); + const bool do_conditional_range_aid = (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) + && isConditionalRangeAidSuitable(); + const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast(RngCtrl::ENABLED)) || do_conditional_range_aid) && measurement_valid && _range_sensor.isDataHealthy(); const bool starting_conditions_passing = continuing_conditions_passing - && isNewestSampleRecent(_time_last_range_buffer_push, 2 * RNG_MAX_INTERVAL) + && isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL) && _range_sensor.isRegularlySendingData(); if (_control_status.flags.rng_hgt) { @@ -165,13 +168,17 @@ void Ekf::controlRangeHeightFusion() } else { if (starting_conditions_passing) { - if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL))) { + if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) + && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) + ) { // Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference. ECL_INFO("starting conditional %s height fusion", HGT_SRC_NAME); _height_sensor_ref = HeightSensor::RANGE; bias_est.setBias(_state.pos(2) + measurement); - } else if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) && (_params.rng_ctrl != static_cast(RngCtrl::CONDITIONAL))) { + } else if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) + && (_params.rng_ctrl != static_cast(RngCtrl::CONDITIONAL)) + ) { // Range finder is the primary height source, the ground is now the datum used // to compute the local vertical position ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME); @@ -193,7 +200,7 @@ void Ekf::controlRangeHeightFusion() } } else if (_control_status.flags.rng_hgt - && !isNewestSampleRecent(_time_last_range_buffer_push, 2 * RNG_MAX_INTERVAL)) { + && !isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME); stopRngHgtFusion(); @@ -203,6 +210,7 @@ void Ekf::controlRangeHeightFusion() bool Ekf::isConditionalRangeAidSuitable() { #if defined(CONFIG_EKF2_TERRAIN) + if (_control_status.flags.in_air && _range_sensor.isHealthy() && isTerrainEstimateValid()) { @@ -236,6 +244,7 @@ bool Ekf::isConditionalRangeAidSuitable() return is_in_range && is_hagl_stable && is_below_max_speed; } + #endif // CONFIG_EKF2_TERRAIN return false; diff --git a/src/modules/ekf2/EKF/sensor_range_finder.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp similarity index 94% rename from src/modules/ekf2/EKF/sensor_range_finder.cpp rename to src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp index c47cf0f74d00..359d10ca5242 100644 --- a/src/modules/ekf2/EKF/sensor_range_finder.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp @@ -38,20 +38,22 @@ * */ -#include "sensor_range_finder.hpp" +#include + +#include namespace estimator { namespace sensor { -void SensorRangeFinder::runChecks(const uint64_t current_time_us, const Dcmf &R_to_earth) +void SensorRangeFinder::runChecks(const uint64_t current_time_us, const matrix::Dcmf &R_to_earth) { updateSensorToEarthRotation(R_to_earth); updateValidity(current_time_us); } -void SensorRangeFinder::updateSensorToEarthRotation(const Dcmf &R_to_earth) +void SensorRangeFinder::updateSensorToEarthRotation(const matrix::Dcmf &R_to_earth) { // calculate 2,2 element of rotation matrix from sensor frame to earth frame // this is required for use of range finder and flow data @@ -114,7 +116,7 @@ inline bool SensorRangeFinder::isDataInRange() const void SensorRangeFinder::updateStuckCheck() { - if(!isStuckDetectorEnabled()){ + if (!isStuckDetectorEnabled()) { // Stuck detector disabled _is_stuck = false; return; diff --git a/src/modules/ekf2/EKF/sensor_range_finder.hpp b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp similarity index 93% rename from src/modules/ekf2/EKF/sensor_range_finder.hpp rename to src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp index ec642f8e98eb..dbfbd96b1006 100644 --- a/src/modules/ekf2/EKF/sensor_range_finder.hpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp @@ -42,6 +42,7 @@ #define EKF_SENSOR_RANGE_FINDER_HPP #include "Sensor.hpp" + #include namespace estimator @@ -49,6 +50,14 @@ namespace estimator namespace sensor { +struct rangeSample { + uint64_t time_us{}; ///< timestamp of the measurement (uSec) + float rng{}; ///< range (distance to ground) measurement (m) + int8_t quality{}; ///< Signal quality in percent (0...100%), where 0 = invalid signal, 100 = perfect signal, and -1 = unknown signal quality. +}; + +static constexpr uint64_t RNG_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between range finder measurements (uSec) + class SensorRangeFinder : public Sensor { public: diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index e760bfbd9d4a..8624501cb261 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -70,7 +70,6 @@ static constexpr uint64_t BARO_MAX_INTERVAL = 200e3; ///< Maximum allowable static constexpr uint64_t EV_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between external vision system measurements (uSec) static constexpr uint64_t GNSS_MAX_INTERVAL = 500e3; ///< Maximum allowable time interval between GNSS measurements (uSec) static constexpr uint64_t GNSS_YAW_MAX_INTERVAL = 1500e3; ///< Maximum allowable time interval between GNSS yaw measurements (uSec) -static constexpr uint64_t RNG_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between range finder measurements (uSec) static constexpr uint64_t MAG_MAX_INTERVAL = 500e3; ///< Maximum allowable time interval between magnetic field measurements (uSec) // bad accelerometer detection and mitigation @@ -197,12 +196,6 @@ struct baroSample { bool reset{false}; }; -struct rangeSample { - uint64_t time_us{}; ///< timestamp of the measurement (uSec) - float rng{}; ///< range (distance to ground) measurement (m) - int8_t quality{}; ///< Signal quality in percent (0...100%), where 0 = invalid signal, 100 = perfect signal, and -1 = unknown signal quality. -}; - struct airspeedSample { uint64_t time_us{}; ///< timestamp of the measurement (uSec) float true_airspeed{}; ///< true airspeed measurement (m/sec) diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index 980328f82083..8bc021feedc3 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -266,7 +266,7 @@ void EstimatorInterface::setAirspeedData(const airspeedSample &airspeed_sample) #endif // CONFIG_EKF2_AIRSPEED #if defined(CONFIG_EKF2_RANGE_FINDER) -void EstimatorInterface::setRangeData(const rangeSample &range_sample) +void EstimatorInterface::setRangeData(const sensor::rangeSample &range_sample) { if (!_initialised) { return; @@ -274,7 +274,7 @@ void EstimatorInterface::setRangeData(const rangeSample &range_sample) // Allocate the required buffer size if not previously done if (_range_buffer == nullptr) { - _range_buffer = new RingBuffer(_obs_buffer_length); + _range_buffer = new RingBuffer(_obs_buffer_length); if (_range_buffer == nullptr || !_range_buffer->valid()) { delete _range_buffer; @@ -291,7 +291,7 @@ void EstimatorInterface::setRangeData(const rangeSample &range_sample) // limit data rate to prevent data being lost if (time_us >= static_cast(_range_buffer->get_newest().time_us + _min_obs_interval_us)) { - rangeSample range_sample_new{range_sample}; + sensor::rangeSample range_sample_new{range_sample}; range_sample_new.time_us = time_us; _range_buffer->push(range_sample_new); diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index e94d14b5e6cb..5c757f721438 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -67,8 +67,8 @@ #include "output_predictor.h" #if defined(CONFIG_EKF2_RANGE_FINDER) -# include "range_finder_consistency_check.hpp" -# include "sensor_range_finder.hpp" +# include "aid_sources/range_finder/range_finder_consistency_check.hpp" +# include "aid_sources/range_finder/sensor_range_finder.hpp" #endif // CONFIG_EKF2_RANGE_FINDER #include @@ -107,7 +107,7 @@ class EstimatorInterface #endif // CONFIG_EKF2_AIRSPEED #if defined(CONFIG_EKF2_RANGE_FINDER) - void setRangeData(const rangeSample &range_sample); + void setRangeData(const estimator::sensor::rangeSample &range_sample); // set sensor limitations reported by the rangefinder void set_rangefinder_limits(float min_distance, float max_distance) @@ -115,7 +115,7 @@ class EstimatorInterface _range_sensor.setLimits(min_distance, max_distance); } - const rangeSample &get_rng_sample_delayed() { return *(_range_sensor.getSampleAddress()); } + const estimator::sensor::rangeSample &get_rng_sample_delayed() { return *(_range_sensor.getSampleAddress()); } #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_OPTICAL_FLOW) @@ -356,7 +356,7 @@ class EstimatorInterface #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_RANGE_FINDER) - RingBuffer *_range_buffer{nullptr}; + RingBuffer *_range_buffer{nullptr}; uint64_t _time_last_range_buffer_push{0}; sensor::SensorRangeFinder _range_sensor{}; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index f531d99ce7ae..7cfefd9d2c26 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2368,7 +2368,7 @@ bool EKF2::UpdateFlowSample(ekf2_timestamps_s &ekf2_timestamps) int8_t quality = static_cast(optical_flow.quality) / static_cast(UINT8_MAX) * 100.f; - rangeSample range_sample { + estimator::sensor::rangeSample range_sample { .time_us = optical_flow.timestamp_sample, .rng = optical_flow.distance_m, .quality = quality, @@ -2507,7 +2507,7 @@ void EKF2::UpdateRangeSample(ekf2_timestamps_s &ekf2_timestamps) if (_distance_sensor_selected >= 0 && _distance_sensor_subs[_distance_sensor_selected].update(&distance_sensor)) { // EKF range sample if (distance_sensor.orientation == distance_sensor_s::ROTATION_DOWNWARD_FACING) { - rangeSample range_sample { + estimator::sensor::rangeSample range_sample { .time_us = distance_sensor.timestamp, .rng = distance_sensor.current_distance, .quality = distance_sensor.signal_quality, diff --git a/src/modules/ekf2/test/sensor_simulator/range_finder.h b/src/modules/ekf2/test/sensor_simulator/range_finder.h index 0dcd068232e7..c4910ed57c43 100644 --- a/src/modules/ekf2/test/sensor_simulator/range_finder.h +++ b/src/modules/ekf2/test/sensor_simulator/range_finder.h @@ -55,7 +55,7 @@ class RangeFinder: public Sensor void setLimits(float min_distance_m, float max_distance_m); private: - rangeSample _range_sample{}; + estimator::sensor::rangeSample _range_sample{}; float _min_distance{0.2f}; float _max_distance{20.0f}; diff --git a/src/modules/ekf2/test/test_SensorRangeFinder.cpp b/src/modules/ekf2/test/test_SensorRangeFinder.cpp index 4a3b3c2b5255..fc515a875768 100644 --- a/src/modules/ekf2/test/test_SensorRangeFinder.cpp +++ b/src/modules/ekf2/test/test_SensorRangeFinder.cpp @@ -34,10 +34,10 @@ #include #include #include "EKF/common.h" -#include "EKF/sensor_range_finder.hpp" +#include "EKF/aid_sources/range_finder/sensor_range_finder.hpp" #include -using estimator::rangeSample; +using estimator::sensor::rangeSample; using matrix::Dcmf; using matrix::Eulerf; using namespace estimator::sensor; From 3f6c3e0649048691b56d99bae2990e6eaf3afb79 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 21:38:03 -0400 Subject: [PATCH 191/652] ekf2: move output predictor to output_predictor/ --- src/modules/ekf2/CMakeLists.txt | 3 +- src/modules/ekf2/EKF/CMakeLists.txt | 4 +- src/modules/ekf2/EKF/estimator_interface.h | 2 +- .../ekf2/EKF/output_predictor/CMakeLists.txt | 39 +++++++++++++++++++ .../output_predictor.cpp | 2 +- .../{ => output_predictor}/output_predictor.h | 5 +-- 6 files changed, 48 insertions(+), 7 deletions(-) create mode 100644 src/modules/ekf2/EKF/output_predictor/CMakeLists.txt rename src/modules/ekf2/EKF/{ => output_predictor}/output_predictor.cpp (99%) rename src/modules/ekf2/EKF/{ => output_predictor}/output_predictor.h (98%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index c5f9c05fcf17..de5390d3b1aa 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -126,7 +126,6 @@ list(APPEND EKF_SRCS EKF/fake_pos_control.cpp EKF/height_control.cpp EKF/imu_down_sampler.cpp - EKF/output_predictor.cpp EKF/velocity_fusion.cpp EKF/position_fusion.cpp EKF/yaw_fusion.cpp @@ -258,7 +257,9 @@ px4_add_module( EKF2Utility px4_work_queue world_magnetic_model + ${EKF_LIBS} + output_predictor UNITY_BUILD ) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index a22e3816de6d..107f9ff4c2d6 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -31,6 +31,8 @@ # ############################################################################ +add_subdirectory(output_predictor) + set(EKF_LIBS) set(EKF_SRCS) list(APPEND EKF_SRCS @@ -44,7 +46,6 @@ list(APPEND EKF_SRCS fake_pos_control.cpp height_control.cpp imu_down_sampler.cpp - output_predictor.cpp velocity_fusion.cpp position_fusion.cpp yaw_fusion.cpp @@ -147,6 +148,7 @@ target_include_directories(ecl_EKF PUBLIC ${EKF_GENERATED_DERIVATION_INCLUDE_PAT target_link_libraries(ecl_EKF PRIVATE geo + output_predictor world_magnetic_model ${EKF_LIBS} ) diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 5c757f721438..81f2dc48f3a1 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -64,7 +64,7 @@ #include "common.h" #include "RingBuffer.h" #include "imu_down_sampler.hpp" -#include "output_predictor.h" +#include "output_predictor/output_predictor.h" #if defined(CONFIG_EKF2_RANGE_FINDER) # include "aid_sources/range_finder/range_finder_consistency_check.hpp" diff --git a/src/modules/ekf2/EKF/output_predictor/CMakeLists.txt b/src/modules/ekf2/EKF/output_predictor/CMakeLists.txt new file mode 100644 index 000000000000..701a5cb13f65 --- /dev/null +++ b/src/modules/ekf2/EKF/output_predictor/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. +# +############################################################################ + +add_library(output_predictor + output_predictor.cpp + output_predictor.h +) + +add_dependencies(output_predictor prebuild_targets) diff --git a/src/modules/ekf2/EKF/output_predictor.cpp b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp similarity index 99% rename from src/modules/ekf2/EKF/output_predictor.cpp rename to src/modules/ekf2/EKF/output_predictor/output_predictor.cpp index 93086dc7e6b6..826717d7b82e 100644 --- a/src/modules/ekf2/EKF/output_predictor.cpp +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4. All rights reserved. + * Copyright (c) 2022-2024 PX4. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/ekf2/EKF/output_predictor.h b/src/modules/ekf2/EKF/output_predictor/output_predictor.h similarity index 98% rename from src/modules/ekf2/EKF/output_predictor.h rename to src/modules/ekf2/EKF/output_predictor/output_predictor.h index ee5cc0f7105b..fee4fdff644c 100644 --- a/src/modules/ekf2/EKF/output_predictor.h +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4. All rights reserved. + * Copyright (c) 2022-2024 PX4. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -36,8 +36,7 @@ #include -#include "common.h" -#include "RingBuffer.h" +#include "../RingBuffer.h" #include From b8d46e60a584785403c499e51aec708499392dab Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 21:41:03 -0400 Subject: [PATCH 192/652] ekf2: move mag fusion to aid_sources/magnetometer --- src/modules/ekf2/CMakeLists.txt | 6 +++--- src/modules/ekf2/EKF/CMakeLists.txt | 6 +++--- .../EKF/{ => aid_sources/magnetometer}/mag_3d_control.cpp | 0 .../ekf2/EKF/{ => aid_sources/magnetometer}/mag_control.cpp | 0 .../ekf2/EKF/{ => aid_sources/magnetometer}/mag_fusion.cpp | 0 5 files changed, 6 insertions(+), 6 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/magnetometer}/mag_3d_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/magnetometer}/mag_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources/magnetometer}/mag_fusion.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index de5390d3b1aa..9363e218a393 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -187,9 +187,9 @@ endif() if(CONFIG_EKF2_MAGNETOMETER) list(APPEND EKF_SRCS - EKF/mag_3d_control.cpp - EKF/mag_control.cpp - EKF/mag_fusion.cpp + EKF/aid_sources/magnetometer/mag_3d_control.cpp + EKF/aid_sources/magnetometer/mag_control.cpp + EKF/aid_sources/magnetometer/mag_fusion.cpp ) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 107f9ff4c2d6..ac00234dc886 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -108,9 +108,9 @@ endif() if(CONFIG_EKF2_MAGNETOMETER) list(APPEND EKF_SRCS - mag_3d_control.cpp - mag_control.cpp - mag_fusion.cpp + aid_sources/magnetometer/mag_3d_control.cpp + aid_sources/magnetometer/mag_control.cpp + aid_sources/magnetometer/mag_fusion.cpp ) endif() diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/mag_3d_control.cpp rename to src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp diff --git a/src/modules/ekf2/EKF/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/mag_control.cpp rename to src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp diff --git a/src/modules/ekf2/EKF/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp similarity index 100% rename from src/modules/ekf2/EKF/mag_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp From e262fde4dcf419a3b8b4280e88d846d99629d4aa Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 21:43:48 -0400 Subject: [PATCH 193/652] ekf2: move aux global position fusion to aid_sources/aux_global_position --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../aux_global_position}/aux_global_position.cpp | 2 +- .../aux_global_position}/aux_global_position.hpp | 4 ++-- src/modules/ekf2/EKF/ekf.h | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources/aux_global_position}/aux_global_position.cpp (98%) rename src/modules/ekf2/EKF/{ => aid_sources/aux_global_position}/aux_global_position.hpp (98%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 9363e218a393..d24a654f329d 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -140,7 +140,7 @@ if(CONFIG_EKF2_AIRSPEED) endif() if(CONFIG_EKF2_AUX_GLOBAL_POSITION) - list(APPEND EKF_SRCS EKF/aux_global_position.cpp) + list(APPEND EKF_SRCS EKF/aid_sources/aux_global_position/aux_global_position.cpp) endif() if(CONFIG_EKF2_AUXVEL) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index ac00234dc886..a98eaedcae14 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -60,7 +60,7 @@ if(CONFIG_EKF2_AIRSPEED) endif() if(CONFIG_EKF2_AUX_GLOBAL_POSITION) - list(APPEND EKF_SRCS aux_global_position.cpp) + list(APPEND EKF_SRCS aid_sources/aux_global_position/aux_global_position.cpp) endif() if(CONFIG_EKF2_AUXVEL) diff --git a/src/modules/ekf2/EKF/aux_global_position.cpp b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp similarity index 98% rename from src/modules/ekf2/EKF/aux_global_position.cpp rename to src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp index f64a990bae84..a0bee2b0a3ba 100644 --- a/src/modules/ekf2/EKF/aux_global_position.cpp +++ b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp @@ -33,7 +33,7 @@ #include "ekf.h" -#include "aux_global_position.hpp" +#include "aid_sources/aux_global_position/aux_global_position.hpp" #if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME) diff --git a/src/modules/ekf2/EKF/aux_global_position.hpp b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp similarity index 98% rename from src/modules/ekf2/EKF/aux_global_position.hpp rename to src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp index 4246477350aa..056840c033c7 100644 --- a/src/modules/ekf2/EKF/aux_global_position.hpp +++ b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp @@ -42,8 +42,8 @@ // WelfordMean for init? // WelfordMean for rate -#include "common.h" -#include "RingBuffer.h" +#include "../../common.h" +#include "../../RingBuffer.h" #if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index fd3cdbd18cfb..1afdd559a427 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -63,7 +63,7 @@ #include "aid_sources/ZeroVelocityUpdate.hpp" #if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) -# include "aux_global_position.hpp" +# include "aid_sources/aux_global_position/aux_global_position.hpp" #endif // CONFIG_EKF2_AUX_GLOBAL_POSITION enum class Likelihood { LOW, MEDIUM, HIGH }; From 49c782bad9edacf9e4b5d42b081ac3349a9078b9 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 21:50:07 -0400 Subject: [PATCH 194/652] ekf2: move bias estimators to bias_estimtor/ --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 3 +- .../ekf2/EKF/bias_estimator/CMakeLists.txt | 41 +++++++++++++++++++ .../{ => bias_estimator}/bias_estimator.cpp | 0 .../{ => bias_estimator}/bias_estimator.hpp | 0 .../height_bias_estimator.hpp | 2 +- .../position_bias_estimator.hpp | 1 - src/modules/ekf2/EKF/ekf.h | 6 +-- 8 files changed, 48 insertions(+), 7 deletions(-) create mode 100644 src/modules/ekf2/EKF/bias_estimator/CMakeLists.txt rename src/modules/ekf2/EKF/{ => bias_estimator}/bias_estimator.cpp (100%) rename src/modules/ekf2/EKF/{ => bias_estimator}/bias_estimator.hpp (100%) rename src/modules/ekf2/EKF/{ => bias_estimator}/height_bias_estimator.hpp (99%) rename src/modules/ekf2/EKF/{ => bias_estimator}/position_bias_estimator.hpp (99%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index d24a654f329d..f65a5f1e284f 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -116,7 +116,6 @@ endif() set(EKF_LIBS) set(EKF_SRCS) list(APPEND EKF_SRCS - EKF/bias_estimator.cpp EKF/control.cpp EKF/covariance.cpp EKF/ekf.cpp @@ -259,6 +258,7 @@ px4_add_module( world_magnetic_model ${EKF_LIBS} + bias_estimator output_predictor UNITY_BUILD ) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index a98eaedcae14..1680967dfc63 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -31,12 +31,12 @@ # ############################################################################ +add_subdirectory(bias_estimator) add_subdirectory(output_predictor) set(EKF_LIBS) set(EKF_SRCS) list(APPEND EKF_SRCS - bias_estimator.cpp control.cpp covariance.cpp ekf.cpp @@ -147,6 +147,7 @@ target_include_directories(ecl_EKF PUBLIC ${EKF_GENERATED_DERIVATION_INCLUDE_PAT target_link_libraries(ecl_EKF PRIVATE + bias_estimator geo output_predictor world_magnetic_model diff --git a/src/modules/ekf2/EKF/bias_estimator/CMakeLists.txt b/src/modules/ekf2/EKF/bias_estimator/CMakeLists.txt new file mode 100644 index 000000000000..b2346919e15a --- /dev/null +++ b/src/modules/ekf2/EKF/bias_estimator/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. +# +############################################################################ + +add_library(bias_estimator + bias_estimator.cpp + bias_estimator.hpp + height_bias_estimator.hpp + position_bias_estimator.hpp +) + +add_dependencies(bias_estimator prebuild_targets) diff --git a/src/modules/ekf2/EKF/bias_estimator.cpp b/src/modules/ekf2/EKF/bias_estimator/bias_estimator.cpp similarity index 100% rename from src/modules/ekf2/EKF/bias_estimator.cpp rename to src/modules/ekf2/EKF/bias_estimator/bias_estimator.cpp diff --git a/src/modules/ekf2/EKF/bias_estimator.hpp b/src/modules/ekf2/EKF/bias_estimator/bias_estimator.hpp similarity index 100% rename from src/modules/ekf2/EKF/bias_estimator.hpp rename to src/modules/ekf2/EKF/bias_estimator/bias_estimator.hpp diff --git a/src/modules/ekf2/EKF/height_bias_estimator.hpp b/src/modules/ekf2/EKF/bias_estimator/height_bias_estimator.hpp similarity index 99% rename from src/modules/ekf2/EKF/height_bias_estimator.hpp rename to src/modules/ekf2/EKF/bias_estimator/height_bias_estimator.hpp index 5cb03cbfdd13..9fe1ee7dacfc 100644 --- a/src/modules/ekf2/EKF/height_bias_estimator.hpp +++ b/src/modules/ekf2/EKF/bias_estimator/height_bias_estimator.hpp @@ -39,7 +39,7 @@ #define EKF_HEIGHT_BIAS_ESTIMATOR_HPP #include "bias_estimator.hpp" -#include "common.h" +#include "../common.h" class HeightBiasEstimator: public BiasEstimator { diff --git a/src/modules/ekf2/EKF/position_bias_estimator.hpp b/src/modules/ekf2/EKF/bias_estimator/position_bias_estimator.hpp similarity index 99% rename from src/modules/ekf2/EKF/position_bias_estimator.hpp rename to src/modules/ekf2/EKF/bias_estimator/position_bias_estimator.hpp index 0cba8fcd996b..629bb538a143 100644 --- a/src/modules/ekf2/EKF/position_bias_estimator.hpp +++ b/src/modules/ekf2/EKF/bias_estimator/position_bias_estimator.hpp @@ -39,7 +39,6 @@ #define EKF_POSITION_BIAS_ESTIMATOR_HPP #include "bias_estimator.hpp" -#include "common.h" class PositionBiasEstimator { diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 1afdd559a427..3aca5c93c77f 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -49,9 +49,9 @@ # include "yaw_estimator/EKFGSF_yaw.h" #endif // CONFIG_EKF2_GNSS -#include "bias_estimator.hpp" -#include "height_bias_estimator.hpp" -#include "position_bias_estimator.hpp" +#include "bias_estimator/bias_estimator.hpp" +#include "bias_estimator/height_bias_estimator.hpp" +#include "bias_estimator/position_bias_estimator.hpp" #include From 58de8cbb77e1af2bf3631f75f7d8f4950912139f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 21:53:08 -0400 Subject: [PATCH 195/652] ekf2: move fake_height, fake_pos, zero_innovation_heading to aid_sources/ --- src/modules/ekf2/CMakeLists.txt | 6 +++--- src/modules/ekf2/EKF/CMakeLists.txt | 6 +++--- .../ekf2/EKF/{ => aid_sources}/fake_height_control.cpp | 0 src/modules/ekf2/EKF/{ => aid_sources}/fake_pos_control.cpp | 0 .../{ => aid_sources}/zero_innovation_heading_update.cpp | 0 5 files changed, 6 insertions(+), 6 deletions(-) rename src/modules/ekf2/EKF/{ => aid_sources}/fake_height_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources}/fake_pos_control.cpp (100%) rename src/modules/ekf2/EKF/{ => aid_sources}/zero_innovation_heading_update.cpp (100%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index f65a5f1e284f..66f2f915cd8c 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -121,17 +121,17 @@ list(APPEND EKF_SRCS EKF/ekf.cpp EKF/ekf_helper.cpp EKF/estimator_interface.cpp - EKF/fake_height_control.cpp - EKF/fake_pos_control.cpp EKF/height_control.cpp EKF/imu_down_sampler.cpp EKF/velocity_fusion.cpp EKF/position_fusion.cpp EKF/yaw_fusion.cpp - EKF/zero_innovation_heading_update.cpp + EKF/aid_sources/fake_height_control.cpp + EKF/aid_sources/fake_pos_control.cpp EKF/aid_sources/ZeroGyroUpdate.cpp EKF/aid_sources/ZeroVelocityUpdate.cpp + EKF/aid_sources/zero_innovation_heading_update.cpp ) if(CONFIG_EKF2_AIRSPEED) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 1680967dfc63..5cb9a37cea7f 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -42,17 +42,17 @@ list(APPEND EKF_SRCS ekf.cpp ekf_helper.cpp estimator_interface.cpp - fake_height_control.cpp - fake_pos_control.cpp height_control.cpp imu_down_sampler.cpp velocity_fusion.cpp position_fusion.cpp yaw_fusion.cpp - zero_innovation_heading_update.cpp + aid_sources/fake_height_control.cpp + aid_sources/fake_pos_control.cpp aid_sources/ZeroGyroUpdate.cpp aid_sources/ZeroVelocityUpdate.cpp + aid_sources/zero_innovation_heading_update.cpp ) if(CONFIG_EKF2_AIRSPEED) diff --git a/src/modules/ekf2/EKF/fake_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/fake_height_control.cpp rename to src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp diff --git a/src/modules/ekf2/EKF/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp similarity index 100% rename from src/modules/ekf2/EKF/fake_pos_control.cpp rename to src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp diff --git a/src/modules/ekf2/EKF/zero_innovation_heading_update.cpp b/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp similarity index 100% rename from src/modules/ekf2/EKF/zero_innovation_heading_update.cpp rename to src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp From 58637d3825d99afffff845e988175a7344d5cb91 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 21:58:09 -0400 Subject: [PATCH 196/652] ekf2: move terrain estimator and derivation to terrain_estimator/ --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../derivation}/derivation_terrain_estimator.py | 13 +++++++++---- .../terr_est_compute_flow_xy_innov_var_and_hx.h | 0 .../terr_est_compute_flow_y_innov_var_and_h.h | 0 .../{ => terrain_estimator}/terrain_estimator.cpp | 4 ++-- 6 files changed, 13 insertions(+), 8 deletions(-) rename src/modules/ekf2/EKF/{python/ekf_derivation => terrain_estimator/derivation}/derivation_terrain_estimator.py (85%) rename src/modules/ekf2/EKF/{python/ekf_derivation => terrain_estimator/derivation}/generated/terr_est_compute_flow_xy_innov_var_and_hx.h (100%) rename src/modules/ekf2/EKF/{python/ekf_derivation => terrain_estimator/derivation}/generated/terr_est_compute_flow_y_innov_var_and_h.h (100%) rename src/modules/ekf2/EKF/{ => terrain_estimator}/terrain_estimator.cpp (98%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 66f2f915cd8c..0ea258ea2b8a 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -212,7 +212,7 @@ if(CONFIG_EKF2_SIDESLIP) endif() if(CONFIG_EKF2_TERRAIN) - list(APPEND EKF_SRCS EKF/terrain_estimator.cpp) + list(APPEND EKF_SRCS EKF/terrain_estimator/terrain_estimator.cpp) endif() add_subdirectory(EKF) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 5cb9a37cea7f..269a525acc32 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -134,7 +134,7 @@ if(CONFIG_EKF2_SIDESLIP) endif() if(CONFIG_EKF2_TERRAIN) - list(APPEND EKF_SRCS terrain_estimator.cpp) + list(APPEND EKF_SRCS terrain_estimator/terrain_estimator.cpp) endif() include_directories(${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_terrain_estimator.py b/src/modules/ekf2/EKF/terrain_estimator/derivation/derivation_terrain_estimator.py similarity index 85% rename from src/modules/ekf2/EKF/python/ekf_derivation/derivation_terrain_estimator.py rename to src/modules/ekf2/EKF/terrain_estimator/derivation/derivation_terrain_estimator.py index 14914f30c1ce..8ecba2c03ebd 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_terrain_estimator.py +++ b/src/modules/ekf2/EKF/terrain_estimator/derivation/derivation_terrain_estimator.py @@ -37,7 +37,12 @@ symforce.set_epsilon_to_symbol() import symforce.symbolic as sf -from utils.derivation_utils import * + +# generate_px4_function from derivation_utils in EKF/ekf_derivation/utils +import os, sys +derivation_utils_dir = os.path.dirname(os.path.abspath(__file__)) + "/../../python/ekf_derivation/utils" +sys.path.append(derivation_utils_dir) +import derivation_utils def predict_opt_flow( terrain_vpos: sf.Scalar, @@ -49,7 +54,7 @@ def predict_opt_flow( R_to_earth = sf.Rot3(sf.Quaternion(xyz=q_att[1:4], w=q_att[0])).to_rotation_matrix() flow_pred = sf.V2() dist = - (pos_z - terrain_vpos) - dist = add_epsilon_sign(dist, dist, epsilon) + dist = derivation_utils.add_epsilon_sign(dist, dist, epsilon) flow_pred[0] = -v[1] / dist * R_to_earth[2, 2] flow_pred[1] = v[0] / dist * R_to_earth[2, 2] return flow_pred @@ -90,5 +95,5 @@ def terr_est_compute_flow_y_innov_var_and_h( return (innov_var, Hy[0, 0]) print("Derive terrain estimator equations...") -generate_px4_function(terr_est_compute_flow_xy_innov_var_and_hx, output_names=["innov_var", "H"]) -generate_px4_function(terr_est_compute_flow_y_innov_var_and_h, output_names=["innov_var", "H"]) +derivation_utils.generate_px4_function(terr_est_compute_flow_xy_innov_var_and_hx, output_names=["innov_var", "H"]) +derivation_utils.generate_px4_function(terr_est_compute_flow_y_innov_var_and_h, output_names=["innov_var", "H"]) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h b/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h similarity index 100% rename from src/modules/ekf2/EKF/python/ekf_derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h rename to src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h b/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h similarity index 100% rename from src/modules/ekf2/EKF/python/ekf_derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h rename to src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h diff --git a/src/modules/ekf2/EKF/terrain_estimator.cpp b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp similarity index 98% rename from src/modules/ekf2/EKF/terrain_estimator.cpp rename to src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp index 7e450f125314..64890cd14fa5 100644 --- a/src/modules/ekf2/EKF/terrain_estimator.cpp +++ b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp @@ -38,8 +38,8 @@ */ #include "ekf.h" -#include "python/ekf_derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h" -#include "python/ekf_derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h" +#include "terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h" +#include "terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h" #include From 4f0eb72fc968e517e5a9ca765c7bdef8d8a1259a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 1 May 2024 22:00:55 -0400 Subject: [PATCH 197/652] ekf2: move IMU down sampler to imu_down_sampler/ --- src/modules/ekf2/CMakeLists.txt | 3 ++- src/modules/ekf2/EKF/CMakeLists.txt | 3 ++- src/modules/ekf2/EKF/estimator_interface.h | 2 +- .../ekf2/EKF/{ => imu_down_sampler}/imu_down_sampler.cpp | 2 +- .../ekf2/EKF/{ => imu_down_sampler}/imu_down_sampler.hpp | 2 +- src/modules/ekf2/test/test_EKF_imuSampling.cpp | 2 +- 6 files changed, 8 insertions(+), 6 deletions(-) rename src/modules/ekf2/EKF/{ => imu_down_sampler}/imu_down_sampler.cpp (98%) rename src/modules/ekf2/EKF/{ => imu_down_sampler}/imu_down_sampler.hpp (99%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 0ea258ea2b8a..7e9fcb7abf88 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -122,11 +122,12 @@ list(APPEND EKF_SRCS EKF/ekf_helper.cpp EKF/estimator_interface.cpp EKF/height_control.cpp - EKF/imu_down_sampler.cpp EKF/velocity_fusion.cpp EKF/position_fusion.cpp EKF/yaw_fusion.cpp + EKF/imu_down_sampler/imu_down_sampler.cpp + EKF/aid_sources/fake_height_control.cpp EKF/aid_sources/fake_pos_control.cpp EKF/aid_sources/ZeroGyroUpdate.cpp diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 269a525acc32..03c9a481667b 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -43,11 +43,12 @@ list(APPEND EKF_SRCS ekf_helper.cpp estimator_interface.cpp height_control.cpp - imu_down_sampler.cpp velocity_fusion.cpp position_fusion.cpp yaw_fusion.cpp + imu_down_sampler/imu_down_sampler.cpp + aid_sources/fake_height_control.cpp aid_sources/fake_pos_control.cpp aid_sources/ZeroGyroUpdate.cpp diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 81f2dc48f3a1..b19936ff1ae8 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -63,7 +63,7 @@ #include "common.h" #include "RingBuffer.h" -#include "imu_down_sampler.hpp" +#include "imu_down_sampler/imu_down_sampler.hpp" #include "output_predictor/output_predictor.h" #if defined(CONFIG_EKF2_RANGE_FINDER) diff --git a/src/modules/ekf2/EKF/imu_down_sampler.cpp b/src/modules/ekf2/EKF/imu_down_sampler/imu_down_sampler.cpp similarity index 98% rename from src/modules/ekf2/EKF/imu_down_sampler.cpp rename to src/modules/ekf2/EKF/imu_down_sampler/imu_down_sampler.cpp index 02f43a12f54c..0054f917f3b4 100644 --- a/src/modules/ekf2/EKF/imu_down_sampler.cpp +++ b/src/modules/ekf2/EKF/imu_down_sampler/imu_down_sampler.cpp @@ -1,4 +1,4 @@ -#include "imu_down_sampler.hpp" +#include "imu_down_sampler/imu_down_sampler.hpp" #include diff --git a/src/modules/ekf2/EKF/imu_down_sampler.hpp b/src/modules/ekf2/EKF/imu_down_sampler/imu_down_sampler.hpp similarity index 99% rename from src/modules/ekf2/EKF/imu_down_sampler.hpp rename to src/modules/ekf2/EKF/imu_down_sampler/imu_down_sampler.hpp index 29732bd584c6..8f0c4211bedf 100644 --- a/src/modules/ekf2/EKF/imu_down_sampler.hpp +++ b/src/modules/ekf2/EKF/imu_down_sampler/imu_down_sampler.hpp @@ -41,7 +41,7 @@ #include #include -#include "common.h" +#include "../common.h" using namespace estimator; diff --git a/src/modules/ekf2/test/test_EKF_imuSampling.cpp b/src/modules/ekf2/test/test_EKF_imuSampling.cpp index bd300c538557..5ba380d2c079 100644 --- a/src/modules/ekf2/test/test_EKF_imuSampling.cpp +++ b/src/modules/ekf2/test/test_EKF_imuSampling.cpp @@ -34,7 +34,7 @@ #include #include #include "EKF/ekf.h" -#include "EKF/imu_down_sampler.hpp" +#include "EKF/imu_down_sampler/imu_down_sampler.hpp" class EkfImuSamplingTest : public ::testing::TestWithParam> { From 6b3b66619bd122e5f7013a846d9d77a243e79a6e Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 2 May 2024 14:08:32 -0400 Subject: [PATCH 198/652] ekf2: move baro dynamic pressure compensation to aid_sources/barometer --- .../barometer/baro_height_control.cpp | 36 +++++++++++++++++++ src/modules/ekf2/EKF/ekf.h | 9 ++--- src/modules/ekf2/EKF/ekf_helper.cpp | 36 ------------------- 3 files changed, 41 insertions(+), 40 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index def9a885f348..f8786c60f974 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -196,3 +196,39 @@ void Ekf::stopBaroHgtFusion() _control_status.flags.baro_hgt = false; } } + +#if defined(CONFIG_EKF2_BARO_COMPENSATION) +float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const +{ + if (_control_status.flags.wind && local_position_is_valid()) { + // calculate static pressure error = Pmeas - Ptruth + // model position error sensitivity as a body fixed ellipse with a different scale in the positive and + // negative X and Y directions. Used to correct baro data for positional errors + + // Calculate airspeed in body frame + const Vector3f vel_imu_rel_body_ned = _R_to_earth * (_ang_rate_delayed_raw % _params.imu_pos_body); + const Vector3f velocity_earth = _state.vel - vel_imu_rel_body_ned; + + const Vector3f wind_velocity_earth(_state.wind_vel(0), _state.wind_vel(1), 0.0f); + + const Vector3f airspeed_earth = velocity_earth - wind_velocity_earth; + + const Vector3f airspeed_body = _state.quat_nominal.rotateVectorInverse(airspeed_earth); + + const Vector3f K_pstatic_coef( + airspeed_body(0) >= 0.f ? _params.static_pressure_coef_xp : _params.static_pressure_coef_xn, + airspeed_body(1) >= 0.f ? _params.static_pressure_coef_yp : _params.static_pressure_coef_yn, + _params.static_pressure_coef_z); + + const Vector3f airspeed_squared = matrix::min(airspeed_body.emult(airspeed_body), sq(_params.max_correction_airspeed)); + + const float pstatic_err = 0.5f * _air_density * (airspeed_squared.dot(K_pstatic_coef)); + + // correct baro measurement using pressure error estimate and assuming sea level gravity + return baro_alt_uncompensated + pstatic_err / (_air_density * CONSTANTS_ONE_G); + } + + // otherwise return the uncorrected baro measurement + return baro_alt_uncompensated; +} +#endif // CONFIG_EKF2_BARO_COMPENSATION diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 3aca5c93c77f..88dd3cb508d4 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -947,10 +947,6 @@ class Ekf final : public EstimatorInterface // and a scalar innovation value void fuse(const VectorState &K, float innovation); -#if defined(CONFIG_EKF2_BARO_COMPENSATION) - float compensateBaroForDynamicPressure(float baro_alt_uncompensated) const; -#endif // CONFIG_EKF2_BARO_COMPENSATION - // calculate the earth rotation vector from a given latitude Vector3f calcEarthRateNED(float lat_rad) const; @@ -1079,6 +1075,11 @@ class Ekf final : public EstimatorInterface void stopBaroHgtFusion(); void updateGroundEffect(); + +# if defined(CONFIG_EKF2_BARO_COMPENSATION) + float compensateBaroForDynamicPressure(float baro_alt_uncompensated) const; +# endif // CONFIG_EKF2_BARO_COMPENSATION + #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_GRAVITY_FUSION) diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index afff6dc0ca48..1b3a7126b461 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -56,42 +56,6 @@ bool Ekf::isHeightResetRequired() const return (continuous_bad_accel_hgt || hgt_fusion_timeout); } -#if defined(CONFIG_EKF2_BARO_COMPENSATION) -float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const -{ - if (_control_status.flags.wind && local_position_is_valid()) { - // calculate static pressure error = Pmeas - Ptruth - // model position error sensitivity as a body fixed ellipse with a different scale in the positive and - // negative X and Y directions. Used to correct baro data for positional errors - - // Calculate airspeed in body frame - const Vector3f vel_imu_rel_body_ned = _R_to_earth * (_ang_rate_delayed_raw % _params.imu_pos_body); - const Vector3f velocity_earth = _state.vel - vel_imu_rel_body_ned; - - const Vector3f wind_velocity_earth(_state.wind_vel(0), _state.wind_vel(1), 0.0f); - - const Vector3f airspeed_earth = velocity_earth - wind_velocity_earth; - - const Vector3f airspeed_body = _state.quat_nominal.rotateVectorInverse(airspeed_earth); - - const Vector3f K_pstatic_coef( - airspeed_body(0) >= 0.f ? _params.static_pressure_coef_xp : _params.static_pressure_coef_xn, - airspeed_body(1) >= 0.f ? _params.static_pressure_coef_yp : _params.static_pressure_coef_yn, - _params.static_pressure_coef_z); - - const Vector3f airspeed_squared = matrix::min(airspeed_body.emult(airspeed_body), sq(_params.max_correction_airspeed)); - - const float pstatic_err = 0.5f * _air_density * (airspeed_squared.dot(K_pstatic_coef)); - - // correct baro measurement using pressure error estimate and assuming sea level gravity - return baro_alt_uncompensated + pstatic_err / (_air_density * CONSTANTS_ONE_G); - } - - // otherwise return the uncorrected baro measurement - return baro_alt_uncompensated; -} -#endif // CONFIG_EKF2_BARO_COMPENSATION - // calculate the earth rotation vector Vector3f Ekf::calcEarthRateNED(float lat_rad) const { From 1ca4056b6a294d518ba940d9b94f090a739479db Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 2 May 2024 14:13:06 -0400 Subject: [PATCH 199/652] ekf2: delete unused Ekf::resetImuBias() --- src/modules/ekf2/EKF/ekf.h | 3 --- src/modules/ekf2/EKF/ekf_helper.cpp | 6 ------ 2 files changed, 9 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 88dd3cb508d4..b40d067c0dae 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -268,9 +268,6 @@ class Ekf final : public EstimatorInterface // get the vehicle control limits required by the estimator to keep within sensor limitations void get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, float *hagl_max) const; - // Reset all IMU bias states and covariances to initial alignment values. - void resetImuBias(); - void resetGyroBias(); void resetGyroBiasCov(); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 1b3a7126b461..63e6dcbdd45e 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -294,12 +294,6 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl #endif // CONFIG_EKF2_RANGE_FINDER } -void Ekf::resetImuBias() -{ - resetGyroBias(); - resetAccelBias(); -} - void Ekf::resetGyroBias() { // Zero the gyro bias states From 63c2ea33c10ac5a812d52b28d505541f6727e029 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 2 May 2024 14:15:23 -0400 Subject: [PATCH 200/652] ekf2: move Ekf::resetQuatStateYaw() to yaw_fusion.cpp --- src/modules/ekf2/EKF/ekf_helper.cpp | 47 ----------------------------- src/modules/ekf2/EKF/yaw_fusion.cpp | 47 +++++++++++++++++++++++++++++ 2 files changed, 47 insertions(+), 47 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 63e6dcbdd45e..b3c036445c0c 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -652,53 +652,6 @@ void Ekf::updateGroundEffect() } #endif // CONFIG_EKF2_BAROMETER -void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) -{ - // save a copy of the quaternion state for later use in calculating the amount of reset change - const Quatf quat_before_reset = _state.quat_nominal; - - // update the yaw angle variance - if (PX4_ISFINITE(yaw_variance) && (yaw_variance > FLT_EPSILON)) { - P.uncorrelateCovarianceSetVariance<1>(2, yaw_variance); - } - - // update transformation matrix from body to world frame using the current estimate - // update the rotation matrix using the new yaw value - _R_to_earth = updateYawInRotMat(yaw, Dcmf(_state.quat_nominal)); - - // calculate the amount that the quaternion has changed by - const Quatf quat_after_reset(_R_to_earth); - const Quatf q_error((quat_after_reset * quat_before_reset.inversed()).normalized()); - - // update quaternion states - _state.quat_nominal = quat_after_reset; - - // add the reset amount to the output observer buffered data - _output_predictor.resetQuaternion(q_error); - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - // update EV attitude error filter - if (_ev_q_error_initialized) { - const Quatf ev_q_error_updated = (q_error * _ev_q_error_filt.getState()).normalized(); - _ev_q_error_filt.reset(ev_q_error_updated); - } -#endif // CONFIG_EKF2_EXTERNAL_VISION - - // record the state change - if (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) { - _state_reset_status.quat_change = q_error; - - } else { - // there's already a reset this update, accumulate total delta - _state_reset_status.quat_change = q_error * _state_reset_status.quat_change; - _state_reset_status.quat_change.normalize(); - } - - _state_reset_status.reset_count.quat++; - - _time_last_heading_fuse = _time_delayed_us; -} - #if defined(CONFIG_EKF2_WIND) void Ekf::resetWind() { diff --git a/src/modules/ekf2/EKF/yaw_fusion.cpp b/src/modules/ekf2/EKF/yaw_fusion.cpp index 80ce35210b14..e843f782ea6e 100644 --- a/src/modules/ekf2/EKF/yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/yaw_fusion.cpp @@ -136,3 +136,50 @@ void Ekf::computeYawInnovVarAndH(float variance, float &innovation_variance, Vec { sym::ComputeYawInnovVarAndH(_state.vector(), P, variance, &innovation_variance, &H_YAW); } + +void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) +{ + // save a copy of the quaternion state for later use in calculating the amount of reset change + const Quatf quat_before_reset = _state.quat_nominal; + + // update the yaw angle variance + if (PX4_ISFINITE(yaw_variance) && (yaw_variance > FLT_EPSILON)) { + P.uncorrelateCovarianceSetVariance<1>(2, yaw_variance); + } + + // update transformation matrix from body to world frame using the current estimate + // update the rotation matrix using the new yaw value + _R_to_earth = updateYawInRotMat(yaw, Dcmf(_state.quat_nominal)); + + // calculate the amount that the quaternion has changed by + const Quatf quat_after_reset(_R_to_earth); + const Quatf q_error((quat_after_reset * quat_before_reset.inversed()).normalized()); + + // update quaternion states + _state.quat_nominal = quat_after_reset; + + // add the reset amount to the output observer buffered data + _output_predictor.resetQuaternion(q_error); + +#if defined(CONFIG_EKF2_EXTERNAL_VISION) + // update EV attitude error filter + if (_ev_q_error_initialized) { + const Quatf ev_q_error_updated = (q_error * _ev_q_error_filt.getState()).normalized(); + _ev_q_error_filt.reset(ev_q_error_updated); + } +#endif // CONFIG_EKF2_EXTERNAL_VISION + + // record the state change + if (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) { + _state_reset_status.quat_change = q_error; + + } else { + // there's already a reset this update, accumulate total delta + _state_reset_status.quat_change = q_error * _state_reset_status.quat_change; + _state_reset_status.quat_change.normalize(); + } + + _state_reset_status.reset_count.quat++; + + _time_last_heading_fuse = _time_delayed_us; +} From c1fc893ccad5f771edd495dcbec98a099bc0549b Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 2 May 2024 14:22:16 -0400 Subject: [PATCH 201/652] ekf2: move gyro/accel/wind covariance reset helpers to covariance.cpp --- src/modules/ekf2/EKF/covariance.cpp | 26 ++++++++++++++++++++++++-- src/modules/ekf2/EKF/ekf_helper.cpp | 19 ------------------- 2 files changed, 24 insertions(+), 21 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 055feef795e9..5190ad12139d 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -282,6 +282,25 @@ void Ekf::resetQuatCov(const Vector3f &rot_var_ned) P.uncorrelateCovarianceSetVariance(State::quat_nominal.idx, rot_var_ned); } +void Ekf::resetGyroBiasCov() +{ + // Zero the corresponding covariances and set + // variances to the values use for initial alignment + P.uncorrelateCovarianceSetVariance(State::gyro_bias.idx, sq(_params.switch_on_gyro_bias)); +} + +void Ekf::resetGyroBiasZCov() +{ + P.uncorrelateCovarianceSetVariance<1>(State::gyro_bias.idx + 2, sq(_params.switch_on_gyro_bias)); +} + +void Ekf::resetAccelBiasCov() +{ + // Zero the corresponding covariances and set + // variances to the values use for initial alignment + P.uncorrelateCovarianceSetVariance(State::accel_bias.idx, sq(_params.switch_on_accel_bias)); +} + #if defined(CONFIG_EKF2_MAGNETOMETER) void Ekf::resetMagCov() { @@ -295,7 +314,10 @@ void Ekf::resetMagCov() } #endif // CONFIG_EKF2_MAGNETOMETER -void Ekf::resetGyroBiasZCov() +#if defined(CONFIG_EKF2_WIND) +void Ekf::resetWindCov() { - P.uncorrelateCovarianceSetVariance<1>(State::gyro_bias.idx + 2, sq(_params.switch_on_gyro_bias)); + // start with a small initial uncertainty to improve the initial estimate + P.uncorrelateCovarianceSetVariance(State::wind_vel.idx, sq(_params.initial_wind_uncertainty)); } +#endif // CONFIG_EKF2_WIND diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index b3c036445c0c..483da288a247 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -302,13 +302,6 @@ void Ekf::resetGyroBias() resetGyroBiasCov(); } -void Ekf::resetGyroBiasCov() -{ - // Zero the corresponding covariances and set - // variances to the values use for initial alignment - P.uncorrelateCovarianceSetVariance(State::gyro_bias.idx, sq(_params.switch_on_gyro_bias)); -} - void Ekf::resetAccelBias() { // Zero the accel bias states @@ -317,13 +310,6 @@ void Ekf::resetAccelBias() resetAccelBiasCov(); } -void Ekf::resetAccelBiasCov() -{ - // Zero the corresponding covariances and set - // variances to the values use for initial alignment - P.uncorrelateCovarianceSetVariance(State::accel_bias.idx, sq(_params.switch_on_accel_bias)); -} - // get EKF innovation consistency check status information comprising of: // status - a bitmask integer containing the pass/fail status for each EKF measurement innovation consistency check // Innovation Test Ratios - these are the ratio of the innovation to the acceptance threshold. @@ -675,11 +661,6 @@ void Ekf::resetWindToZero() resetWindCov(); } -void Ekf::resetWindCov() -{ - // start with a small initial uncertainty to improve the initial estimate - P.uncorrelateCovarianceSetVariance(State::wind_vel.idx, sq(_params.initial_wind_uncertainty)); -} #endif // CONFIG_EKF2_WIND void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed) From 224d6f2fa7df6352183cfc55a65961735fc6cacd Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 2 May 2024 14:32:18 -0400 Subject: [PATCH 202/652] ekf2: ekf_helper.cpp remove duplicate method comments (comment on declaration only, not definition) --- src/modules/ekf2/EKF/ekf.h | 8 ++++++-- src/modules/ekf2/EKF/ekf_helper.cpp | 15 --------------- 2 files changed, 6 insertions(+), 17 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index b40d067c0dae..77ddfc721422 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -265,7 +265,11 @@ class Ekf final : public EstimatorInterface // get the 1-sigma horizontal and vertical velocity uncertainty void get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const; - // get the vehicle control limits required by the estimator to keep within sensor limitations + // Returns the following vehicle control limits required by the estimator to keep within sensor limitations. + // vxy_max : Maximum ground relative horizontal speed (meters/sec). NaN when limiting is not needed. + // vz_max : Maximum ground relative vertical speed (meters/sec). NaN when limiting is not needed. + // hagl_min : Minimum height above ground (meters). NaN when limiting is not needed. + // hagl_max : Maximum height above ground (meters). NaN when limiting is not needed. void get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, float *hagl_max) const; void resetGyroBias(); @@ -387,7 +391,7 @@ class Ekf final : public EstimatorInterface void get_innovation_test_status(uint16_t &status, float &mag, float &vel, float &pos, float &hgt, float &tas, float &hagl, float &beta) const; - // return a bitmask integer that describes which state estimates can be used for flight control + // return a bitmask integer that describes which state estimates are valid void get_ekf_soln_status(uint16_t *status) const; HeightSensor getHeightSensorRef() const { return _height_sensor_ref; } diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 483da288a247..40b6a4239d40 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -56,7 +56,6 @@ bool Ekf::isHeightResetRequired() const return (continuous_bad_accel_hgt || hgt_fusion_timeout); } -// calculate the earth rotation vector Vector3f Ekf::calcEarthRateNED(float lat_rad) const { return Vector3f(CONSTANTS_EARTH_SPIN_RATE * cosf(lat_rad), @@ -199,7 +198,6 @@ void Ekf::get_ekf_lpos_accuracy(float *ekf_eph, float *ekf_epv) const *ekf_epv = sqrtf(P(State::pos.idx + 2, State::pos.idx + 2)); } -// get the 1-sigma horizontal and vertical velocity uncertainty void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const { float hvel_err = sqrtf(P.trace<2>(State::vel.idx)); @@ -240,13 +238,6 @@ void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const *ekf_evv = sqrtf(P(State::vel.idx + 2, State::vel.idx + 2)); } -/* -Returns the following vehicle control limits required by the estimator to keep within sensor limitations. -vxy_max : Maximum ground relative horizontal speed (meters/sec). NaN when limiting is not needed. -vz_max : Maximum ground relative vertical speed (meters/sec). NaN when limiting is not needed. -hagl_min : Minimum height above ground (meters). NaN when limiting is not needed. -hagl_max : Maximum height above ground (meters). NaN when limiting is not needed. -*/ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, float *hagl_max) const { // Do not require limiting by default @@ -310,11 +301,6 @@ void Ekf::resetAccelBias() resetAccelBiasCov(); } -// get EKF innovation consistency check status information comprising of: -// status - a bitmask integer containing the pass/fail status for each EKF measurement innovation consistency check -// Innovation Test Ratios - these are the ratio of the innovation to the acceptance threshold. -// A value > 1 indicates that the sensor measurement has exceeded the maximum acceptable level and has been rejected by the EKF -// Where a measurement type is a vector quantity, eg magnetometer, GPS position, etc, the maximum value is returned. void Ekf::get_innovation_test_status(uint16_t &status, float &mag, float &vel, float &pos, float &hgt, float &tas, float &hagl, float &beta) const { @@ -442,7 +428,6 @@ void Ekf::get_innovation_test_status(uint16_t &status, float &mag, float &vel, f #endif // CONFIG_EKF2_SIDESLIP } -// return a bitmask integer that describes which state estimates are valid void Ekf::get_ekf_soln_status(uint16_t *status) const { ekf_solution_status_u soln_status{}; From 36ea872e72b6429a900516f71b3ee1fddfc701bf Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Thu, 2 May 2024 14:52:26 -0700 Subject: [PATCH 203/652] drivers: adis16507 reschedule reset after failed self test --- src/drivers/imu/analog_devices/adis16507/ADIS16507.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/imu/analog_devices/adis16507/ADIS16507.cpp b/src/drivers/imu/analog_devices/adis16507/ADIS16507.cpp index c12e8d356d34..dff2c7f4f8a2 100644 --- a/src/drivers/imu/analog_devices/adis16507/ADIS16507.cpp +++ b/src/drivers/imu/analog_devices/adis16507/ADIS16507.cpp @@ -172,7 +172,9 @@ void ADIS16507::RunImpl() const uint16_t DIAG_STAT = RegisterRead(Register::DIAG_STAT); if (DIAG_STAT != 0) { - PX4_ERR("DIAG_STAT: %#X", DIAG_STAT); + PX4_ERR("self test failed, resetting. DIAG_STAT: %#X", DIAG_STAT); + _state = STATE::RESET; + ScheduleDelayed(3_s); } else { PX4_DEBUG("self test passed"); From 9e6dcb1f60d052452e7ce2c00792111314ae1efc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 29 Apr 2024 10:33:11 +0200 Subject: [PATCH 204/652] fix mavlink: cmd_logging_{start,stop}_acknowledgement flags were not reset Regression from https://github.com/PX4/PX4-Autopilot/pull/23043 Also avoids a race condition by making sure the command ack is handled before sending out the mavlink message (in case an external component reacts immediately to the mavlink message). --- src/modules/mavlink/mavlink_main.cpp | 52 ++++++++++++---------------- src/modules/mavlink/mavlink_main.h | 2 +- 2 files changed, 24 insertions(+), 30 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 727360df8ff5..722c1254f65c 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2255,9 +2255,6 @@ Mavlink::task_main(int argc, char *argv[]) _task_running.store(true); - bool cmd_logging_start_acknowledgement = false; - bool cmd_logging_stop_acknowledgement = false; - while (!should_exit()) { /* main loop */ px4_usleep(_main_loop_delay); @@ -2266,7 +2263,7 @@ Mavlink::task_main(int argc, char *argv[]) check_requested_subscriptions(); handleStatus(); handleCommands(); - handleAndGetCurrentCommandAck(cmd_logging_start_acknowledgement, cmd_logging_stop_acknowledgement); + handleAndGetCurrentCommandAck(); continue; } @@ -2291,7 +2288,7 @@ Mavlink::task_main(int argc, char *argv[]) handleStatus(); handleCommands(); - handleAndGetCurrentCommandAck(cmd_logging_start_acknowledgement, cmd_logging_stop_acknowledgement); + handleAndGetCurrentCommandAck(); /* check for shell output */ if (_mavlink_shell && _mavlink_shell->available() > 0) { @@ -2330,25 +2327,15 @@ Mavlink::task_main(int argc, char *argv[]) /* check for ulog streaming messages */ if (_mavlink_ulog) { - if (cmd_logging_stop_acknowledgement) { - _mavlink_ulog->stop(); - _mavlink_ulog = nullptr; + const int ret = _mavlink_ulog->handle_update(get_channel()); - } else { - if (cmd_logging_start_acknowledgement) { - _mavlink_ulog->start_ack_received(); + if (ret < 0) { // abort the streaming on error + if (ret != -1) { + PX4_WARN("mavlink ulog stream update failed, stopping (%i)", ret); } - int ret = _mavlink_ulog->handle_update(get_channel()); - - if (ret < 0) { //abort the streaming on error - if (ret != -1) { - PX4_WARN("mavlink ulog stream update failed, stopping (%i)", ret); - } - - _mavlink_ulog->stop(); - _mavlink_ulog = nullptr; - } + _mavlink_ulog->stop(); + _mavlink_ulog = nullptr; } } @@ -2571,7 +2558,7 @@ void Mavlink::handleCommands() } } -void Mavlink::handleAndGetCurrentCommandAck(bool &logging_start_ack, bool &logging_stop_ack) +void Mavlink::handleAndGetCurrentCommandAck() { if (_vehicle_command_ack_sub.updated()) { static constexpr size_t COMMAND_ACK_TOTAL_LEN = MAVLINK_MSG_ID_COMMAND_ACK_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; @@ -2601,6 +2588,20 @@ void Mavlink::handleAndGetCurrentCommandAck(bool &logging_start_ack, bool &loggi msg.target_system = command_ack.target_system; msg.target_component = command_ack.target_component; + // Handle logging acks before sending out the mavlink message to prevent a race condition + if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) { + if (_mavlink_ulog) { + _mavlink_ulog->start_ack_received(); + } + + } else if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP + && command_ack.result == vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) { + if (_mavlink_ulog) { + _mavlink_ulog->stop(); + _mavlink_ulog = nullptr; + } + } + if (_mode == MAVLINK_MODE_IRIDIUM) { if (command_ack.from_external) { // for MAVLINK_MODE_IRIDIUM send only if external @@ -2611,13 +2612,6 @@ void Mavlink::handleAndGetCurrentCommandAck(bool &logging_start_ack, bool &loggi mavlink_msg_command_ack_send_struct(get_channel(), &msg); } - if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) { - logging_start_ack = true; - - } else if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP - && command_ack.result == vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) { - logging_stop_ack = true; - } } } } diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 5bf47913274b..9444b8058a48 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -710,7 +710,7 @@ class Mavlink final : public ModuleParams void handleCommands(); - void handleAndGetCurrentCommandAck(bool &logging_start_ack, bool &logging_stop_ack); + void handleAndGetCurrentCommandAck(); void handleStatus(); From f04d17d1604a9753db06091dc723a0739da38329 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 May 2024 17:04:04 +1200 Subject: [PATCH 205/652] Tools: skip submodule check in CLion Same as what's required for VSCode. Signed-off-by: Julian Oes --- Tools/check_submodules.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 8082491ee204..1931deb9a31d 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -6,7 +6,7 @@ function check_git_submodule { if [[ -f $1"/.git" || -d $1"/.git" ]]; then # always update within CI environment or configuring withing VSCode CMake where you can't interact - if [ "$CI" == "true" ] || [ -n "${VSCODE_PID+set}" ]; then + if [ "$CI" == "true" ] || [ -n "${VSCODE_PID+set}" ] || [ -n "${CLION_IDE+set}" ]; then git submodule --quiet sync --recursive -- $1 git submodule --quiet update --init --recursive --jobs=8 -- $1 || true git submodule --quiet sync --recursive -- $1 From f16115d8be21fa89ee2bb6a96f8eb4ded972bc2c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 5 Apr 2024 09:17:49 +0200 Subject: [PATCH 206/652] mavlink_ftp: handle relative paths correctly by ensuring there's a '/' in between when concatenating the path with _root_dir. --- src/modules/mavlink/mavlink_ftp.cpp | 57 ++++++++++++----------------- src/modules/mavlink/mavlink_ftp.h | 5 +++ 2 files changed, 29 insertions(+), 33 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 9d078b16b090..b85ea93b3d74 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -344,15 +344,27 @@ MavlinkFTP::_reply(mavlink_file_transfer_protocol_t *ftp_req) #endif } +void MavlinkFTP::_constructPath(char *dst, int dst_len, const char *path) const +{ + strncpy(dst, _root_dir, dst_len); + int root_dir_len = _root_dir_len; + + // If neither the root ends nor the given path starts with a '/', add a separating '/' in between + if (dst[0] != '\0' && dst[strlen(dst) - 1] != '/' && path[0] != '/') { + strncat(dst, "/", dst_len); + ++root_dir_len; + } + + strncpy(dst + root_dir_len, path, dst_len - root_dir_len); + // Ensure termination + dst[dst_len - 1] = '\0'; +} /// @brief Responds to a List command MavlinkFTP::ErrorCode MavlinkFTP::_workList(PayloadHeader *payload) { - strncpy(_work_buffer1, _root_dir, _work_buffer1_len); - strncpy(_work_buffer1 + _root_dir_len, _data_as_cstring(payload), _work_buffer1_len - _root_dir_len); - // ensure termination - _work_buffer1[_work_buffer1_len - 1] = '\0'; + _constructPath(_work_buffer1, _work_buffer1_len, _data_as_cstring(payload)); ErrorCode errorCode = kErrNone; unsigned offset = 0; @@ -506,8 +518,7 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag) return kErrNoSessionsAvailable; } - strncpy(_work_buffer1, _root_dir, _work_buffer1_len); - strncpy(_work_buffer1 + _root_dir_len, _data_as_cstring(payload), _work_buffer1_len - _root_dir_len); + _constructPath(_work_buffer1, _work_buffer1_len, _data_as_cstring(payload)); PX4_DEBUG("FTP: open '%s'", _work_buffer1); @@ -649,10 +660,7 @@ MavlinkFTP::_workWrite(PayloadHeader *payload) MavlinkFTP::ErrorCode MavlinkFTP::_workRemoveFile(PayloadHeader *payload) { - strncpy(_work_buffer1, _root_dir, _work_buffer1_len); - strncpy(_work_buffer1 + _root_dir_len, _data_as_cstring(payload), _work_buffer1_len - _root_dir_len); - // ensure termination - _work_buffer1[_work_buffer1_len - 1] = '\0'; + _constructPath(_work_buffer1, _work_buffer1_len, _data_as_cstring(payload)); if (!_validatePathIsWritable(_work_buffer1)) { return kErrFailFileProtected; @@ -675,10 +683,7 @@ MavlinkFTP::_workRemoveFile(PayloadHeader *payload) MavlinkFTP::ErrorCode MavlinkFTP::_workTruncateFile(PayloadHeader *payload) { - strncpy(_work_buffer1, _root_dir, _work_buffer1_len); - strncpy(_work_buffer1 + _root_dir_len, _data_as_cstring(payload), _work_buffer1_len - _root_dir_len); - // ensure termination - _work_buffer1[_work_buffer1_len - 1] = '\0'; + _constructPath(_work_buffer1, _work_buffer1_len, _data_as_cstring(payload)); payload->size = 0; if (!_validatePathIsWritable(_work_buffer1)) { @@ -839,13 +844,8 @@ MavlinkFTP::_workRename(PayloadHeader *payload) return kErrFailErrno; } - strncpy(_work_buffer1, _root_dir, _work_buffer1_len); - strncpy(_work_buffer1 + _root_dir_len, ptr, _work_buffer1_len - _root_dir_len); - _work_buffer1[_work_buffer1_len - 1] = '\0'; // ensure termination - - strncpy(_work_buffer2, _root_dir, _work_buffer2_len); - strncpy(_work_buffer2 + _root_dir_len, ptr + oldpath_sz + 1, _work_buffer2_len - _root_dir_len); - _work_buffer2[_work_buffer2_len - 1] = '\0'; // ensure termination + _constructPath(_work_buffer1, _work_buffer1_len, ptr); + _constructPath(_work_buffer2, _work_buffer2_len, ptr + oldpath_sz + 1); if (!_validatePathIsWritable(_work_buffer2)) { return kErrFailFileProtected; @@ -868,10 +868,7 @@ MavlinkFTP::_workRename(PayloadHeader *payload) MavlinkFTP::ErrorCode MavlinkFTP::_workRemoveDirectory(PayloadHeader *payload) { - strncpy(_work_buffer1, _root_dir, _work_buffer1_len); - strncpy(_work_buffer1 + _root_dir_len, _data_as_cstring(payload), _work_buffer1_len - _root_dir_len); - // ensure termination - _work_buffer1[_work_buffer1_len - 1] = '\0'; + _constructPath(_work_buffer1, _work_buffer1_len, _data_as_cstring(payload)); if (!_validatePathIsWritable(_work_buffer1)) { return kErrFailFileProtected; @@ -894,10 +891,7 @@ MavlinkFTP::_workRemoveDirectory(PayloadHeader *payload) MavlinkFTP::ErrorCode MavlinkFTP::_workCreateDirectory(PayloadHeader *payload) { - strncpy(_work_buffer1, _root_dir, _work_buffer1_len); - strncpy(_work_buffer1 + _root_dir_len, _data_as_cstring(payload), _work_buffer1_len - _root_dir_len); - // ensure termination - _work_buffer1[_work_buffer1_len - 1] = '\0'; + _constructPath(_work_buffer1, _work_buffer1_len, _data_as_cstring(payload)); if (!_validatePathIsWritable(_work_buffer1)) { return kErrFailFileProtected; @@ -922,10 +916,7 @@ MavlinkFTP::_workCalcFileCRC32(PayloadHeader *payload) { uint32_t checksum = 0; ssize_t bytes_read; - strncpy(_work_buffer2, _root_dir, _work_buffer2_len); - strncpy(_work_buffer2 + _root_dir_len, _data_as_cstring(payload), _work_buffer2_len - _root_dir_len); - // ensure termination - _work_buffer2[_work_buffer2_len - 1] = '\0'; + _constructPath(_work_buffer2, _work_buffer2_len, _data_as_cstring(payload)); int fd = ::open(_work_buffer2, O_RDONLY); diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h index 4372033043d0..d6727d58b99a 100644 --- a/src/modules/mavlink/mavlink_ftp.h +++ b/src/modules/mavlink/mavlink_ftp.h @@ -155,6 +155,11 @@ class MavlinkFTP uint8_t _getServerComponentId(void); uint8_t _getServerChannel(void); + /** + * Construct local path by appending `path` to `_root_dir` and storing the result in `dst`. + */ + void _constructPath(char *dst, int dst_len, const char *path) const; + bool _validatePathIsWritable(const char *path); /** From f002b08e6ab76c38d8c223ac94e566bbb023d549 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 5 Apr 2024 09:24:55 +0200 Subject: [PATCH 207/652] mavlink_ftp: ensure there's enough space for the 2. path in _workRename Prevents accessing invalid memory when reading ptr + oldpath_sz + 1 and oldpath_sz fills out the whole or N-1 bytes of the payload. --- src/modules/mavlink/mavlink_ftp.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index b85ea93b3d74..74ec0762ff6f 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -838,7 +838,7 @@ MavlinkFTP::_workRename(PayloadHeader *payload) char *ptr = _data_as_cstring(payload); size_t oldpath_sz = strlen(ptr); - if (oldpath_sz == payload->size) { + if (oldpath_sz + 2 >= payload->size) { // no newpath errno = EINVAL; return kErrFailErrno; From e17faece3dbf516e8b220ca61a3b6f7fca74b390 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 5 Apr 2024 10:14:32 +0200 Subject: [PATCH 208/652] mavlink_ftp: do not store reply on kErrNoSessionsAvailable This would interfere with an existing ongoing session --- src/modules/mavlink/mavlink_ftp.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 74ec0762ff6f..566c2ce38e14 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -326,7 +326,7 @@ MavlinkFTP::_reply(mavlink_file_transfer_protocol_t *ftp_req) // we can simply resend the response. // we only keep small responses to reduce RAM usage and avoid large memcpy's. The larger responses are all data // retrievals without side-effects, meaning it's ok to reexecute them if a response gets lost - if (payload->size <= sizeof(uint32_t)) { + if (payload->size <= sizeof(uint32_t) && payload->data[0] != kErrNoSessionsAvailable) { _last_reply_valid = true; memcpy(_last_reply, ftp_req, sizeof(_last_reply)); } @@ -514,7 +514,7 @@ MavlinkFTP::ErrorCode MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag) { if (_session_info.fd >= 0) { - PX4_ERR("FTP: Open failed - out of sessions\n"); + PX4_ERR("FTP: Open failed - out of sessions"); return kErrNoSessionsAvailable; } From 6a789b54c6dbc064744b775a9d8db813b3ca9086 Mon Sep 17 00:00:00 2001 From: Konrad Date: Mon, 20 Nov 2023 20:42:30 +0100 Subject: [PATCH 209/652] TECS: allow for fast descend up to maximum airspeed. Use pitch control loop to control max airspeed while giving minimal throttle. --- src/lib/tecs/TECS.cpp | 58 ++++++++++++++++--- src/lib/tecs/TECS.hpp | 30 ++++++++-- .../FixedwingPositionControl.cpp | 2 + .../FixedwingPositionControl.hpp | 1 + .../fw_path_navigation_params.c | 9 +++ 5 files changed, 85 insertions(+), 15 deletions(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index b3148c4a7c17..d25821b94921 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -394,6 +394,10 @@ TECSControl::SpecificEnergyWeighting TECSControl::_updateSpeedAltitudeWeights(co } else if (!flag.airspeed_enabled) { pitch_speed_weight = 0.0f; + } else if (param.fast_descend > FLT_EPSILON) { + // pitch loop controls the airspeed to max + pitch_speed_weight = 1.f + param.fast_descend; + } // don't allow any weight to be larger than one, as it has the same effect as reducing the control @@ -405,8 +409,7 @@ TECSControl::SpecificEnergyWeighting TECSControl::_updateSpeedAltitudeWeights(co } void TECSControl::_calcPitchControl(float dt, const Input &input, const SpecificEnergyRates &specific_energy_rates, - const Param ¶m, - const Flag &flag) + const Param ¶m, const Flag &flag) { const SpecificEnergyWeighting weight{_updateSpeedAltitudeWeights(param, flag)}; ControlValues seb_rate{_calcPitchControlSebRate(weight, specific_energy_rates)}; @@ -514,10 +517,17 @@ void TECSControl::_calcThrottleControl(float dt, const SpecificEnergyRates &spec const float STE_rate_estimate_raw = specific_energy_rates.spe_rate.estimate + specific_energy_rates.ske_rate.estimate; _ste_rate_estimate_filter.setParameters(dt, param.ste_rate_time_const); _ste_rate_estimate_filter.update(STE_rate_estimate_raw); - ControlValues ste_rate{_calcThrottleControlSteRate(limit, specific_energy_rates, param)}; - _calcThrottleControlUpdate(dt, limit, ste_rate, param, flag); - float throttle_setpoint{_calcThrottleControlOutput(limit, ste_rate, param, flag)}; + float throttle_setpoint{param.throttle_min}; + + if (1.f - param.fast_descend < FLT_EPSILON) { + // During fast descend, we control airspeed over the pitch control loop and give minimal thrust. + throttle_setpoint = param.throttle_min; + + } else { + _calcThrottleControlUpdate(dt, limit, ste_rate, param, flag); + throttle_setpoint = _calcThrottleControlOutput(limit, ste_rate, param, flag); + } // Rate limit the throttle demand if (fabsf(param.throttle_slewrate) > FLT_EPSILON) { @@ -651,6 +661,7 @@ void TECS::initControlParams(float target_climbrate, float target_sinkrate, floa _reference_param.target_sinkrate = target_sinkrate; // Control _control_param.tas_min = eas_to_tas * _equivalent_airspeed_min; + _control_param.tas_max = eas_to_tas * _equivalent_airspeed_max; _control_param.pitch_max = pitch_limit_max; _control_param.pitch_min = pitch_limit_min; _control_param.throttle_trim = throttle_trim; @@ -705,6 +716,11 @@ void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_set initialize(altitude, hgt_rate, equivalent_airspeed, eas_to_tas); } else { + /* Check if we want to fast descend. On fast descend, we set the throttle to min, and use the altitude control + loop to control the speed to the maximum airspeed. */ + _setFastDescend(hgt_setpoint, altitude); + _control_param.fast_descend = _fast_descend; + // Update airspeedfilter submodule const TECSAirspeedFilter::Input airspeed_input{ .equivalent_airspeed = equivalent_airspeed, .equivalent_airspeed_rate = speed_deriv_forward / eas_to_tas}; @@ -712,15 +728,25 @@ void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_set _airspeed_filter.update(dt, airspeed_input, _airspeed_filter_param, _control_flag.airspeed_enabled); // Update Reference model submodule - const TECSAltitudeReferenceModel::AltitudeReferenceState setpoint{ .alt = hgt_setpoint, - .alt_rate = hgt_rate_sp}; + if (1.f - _fast_descend < FLT_EPSILON) { + // Reset the altitude reference model, while we are in fast descend. + const TECSAltitudeReferenceModel::AltitudeReferenceState init_state{ + .alt = altitude, + .alt_rate = hgt_rate}; + _altitude_reference_model.initialize(init_state); + + } else { + const TECSAltitudeReferenceModel::AltitudeReferenceState setpoint{ .alt = hgt_setpoint, + .alt_rate = hgt_rate_sp}; - _altitude_reference_model.update(dt, setpoint, altitude, hgt_rate, _reference_param); + _altitude_reference_model.update(dt, setpoint, altitude, hgt_rate, _reference_param); + } TECSControl::Setpoint control_setpoint; control_setpoint.altitude_reference = _altitude_reference_model.getAltitudeReference(); control_setpoint.altitude_rate_setpoint_direct = _altitude_reference_model.getHeightRateSetpointDirect(); - control_setpoint.tas_setpoint = eas_to_tas * EAS_setpoint; + control_setpoint.tas_setpoint = _control_param.tas_max * _fast_descend + (1 - _fast_descend) * eas_to_tas * + EAS_setpoint; const TECSControl::Input control_input{ .altitude = altitude, .altitude_rate = hgt_rate, @@ -740,3 +766,17 @@ void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_set _update_timestamp = now; } +void TECS::_setFastDescend(const float alt_setpoint, const float alt) +{ + if (_control_flag.airspeed_enabled && (_fast_descend_alt_err > FLT_EPSILON) + && ((alt_setpoint + _fast_descend_alt_err) < alt)) { + _fast_descend = 1.f; + + } else if ((_fast_descend > FLT_EPSILON) && (_fast_descend_alt_err > FLT_EPSILON)) { + // Were in fast descend, scale it down. up until 5m above target altitude + _fast_descend = constrain((alt - alt_setpoint - 5.f) / _fast_descend_alt_err, 0.f, 1.f); + + } else { + _fast_descend = 0.f; + } +} diff --git a/src/lib/tecs/TECS.hpp b/src/lib/tecs/TECS.hpp index 8749ac0a21af..64881fb17f31 100644 --- a/src/lib/tecs/TECS.hpp +++ b/src/lib/tecs/TECS.hpp @@ -202,6 +202,7 @@ class TECSControl float vert_accel_limit; ///< Magnitude of the maximum vertical acceleration allowed [m/s²]. float equivalent_airspeed_trim; ///< Equivalent cruise airspeed for airspeed less mode [m/s]. float tas_min; ///< True airspeed demand lower limit [m/s]. + float tas_max; ///< True airspeed demand upper limit [m/s]. float pitch_max; ///< Maximum pitch angle allowed in [rad]. float pitch_min; ///< Minimal pitch angle allowed in [rad]. float throttle_trim; ///< Normalized throttle required to fly level at calibrated airspeed setpoint [0,1] @@ -233,6 +234,8 @@ class TECSControl float load_factor_correction; ///< Gain from normal load factor increase to total energy rate demand [m²/s³]. float load_factor; ///< Additional normal load factor. + + float fast_descend; }; /** @@ -393,7 +396,7 @@ class TECSControl * @brief calculate airspeed control proportional output. * * @param setpoint is the control setpoints. - * @param input is the current input measurment of the UAS. + * @param input is the current input measurement of the UAS. * @param param is the control parameters. * @param flag is the control flags. * @return controlled airspeed rate setpoint in [m/s²]. @@ -404,7 +407,7 @@ class TECSControl * @brief calculate altitude control proportional output. * * @param setpoint is the control setpoints. - * @param input is the current input measurment of the UAS. + * @param input is the current input measurement of the UAS. * @param param is the control parameters. * @return controlled altitude rate setpoint in [m/s]. */ @@ -413,14 +416,14 @@ class TECSControl * @brief Calculate specific energy rates. * * @param control_setpoint is the controlles altitude and airspeed rate setpoints. - * @param input is the current input measurment of the UAS. + * @param input is the current input measurement of the UAS. * @return Specific energy rates in [m²/s³]. */ SpecificEnergyRates _calcSpecificEnergyRates(const AltitudePitchControl &control_setpoint, const Input &input) const; /** * @brief Detect underspeed. * - * @param input is the current input measurment of the UAS. + * @param input is the current input measurement of the UAS. * @param param is the control parameters. * @param flag is the control flags. */ @@ -602,9 +605,11 @@ class TECS void set_max_climb_rate(float climb_rate) { _control_param.max_climb_rate = climb_rate; _reference_param.max_climb_rate = climb_rate; }; void set_altitude_rate_ff(float altitude_rate_ff) { _control_param.altitude_setpoint_gain_ff = altitude_rate_ff; }; - void set_altitude_error_time_constant(float time_const) { _control_param.altitude_error_gain = 1.0f / math::max(time_const, 0.1f);; }; + void set_altitude_error_time_constant(float time_const) { _control_param.altitude_error_gain = 1.0f / math::max(time_const, 0.1f); }; + void set_fast_descend_altitude_error(float altitude_error) { _fast_descend_alt_err = altitude_error; }; void set_equivalent_airspeed_min(float airspeed) { _equivalent_airspeed_min = airspeed; } + void set_equivalent_airspeed_max(float airspeed) { _equivalent_airspeed_max = airspeed; } void set_equivalent_airspeed_trim(float airspeed) { _control_param.equivalent_airspeed_trim = airspeed; _airspeed_filter_param.equivalent_airspeed_trim = airspeed; } void set_pitch_damping(float damping) { _control_param.pitch_damping_gain = damping; } @@ -665,7 +670,10 @@ class TECS hrt_abstime _update_timestamp{0}; ///< last timestamp of the update function call. - float _equivalent_airspeed_min{3.0f}; ///< equivalent airspeed demand lower limit (m/sec) + float _equivalent_airspeed_min{10.0f}; ///< equivalent airspeed demand lower limit (m/sec) + float _equivalent_airspeed_max{20.0f}; ///< equivalent airspeed demand upper limit (m/sec) + float _fast_descend_alt_err{-1.f}; ///< Altitude difference between current altitude to altitude setpoint needed to descend with higher airspeed [m]. + float _fast_descend{0.f}; ///< Value for fast descend in [0,1]. continuous value used to flatten the high speed value out when close to target altitude. static constexpr float DT_MIN = 0.001f; ///< minimum allowed value of _dt (sec) static constexpr float DT_MAX = 1.0f; ///< max value of _dt allowed before a filter state reset is performed (sec) @@ -697,6 +705,7 @@ class TECS .vert_accel_limit = 0.0f, .equivalent_airspeed_trim = 15.0f, .tas_min = 10.0f, + .tas_max = 20.0f, .pitch_max = 0.5f, .pitch_min = -0.5f, .throttle_trim = 0.0f, @@ -716,11 +725,20 @@ class TECS .throttle_slewrate = 0.0f, .load_factor_correction = 0.0f, .load_factor = 1.0f, + .fast_descend = 0.f }; TECSControl::Flag _control_flag{ .airspeed_enabled = false, .detect_underspeed_enabled = false, }; + + /** + * @brief Set fast descend value + * + * @param alt_setpoint is the altitude setpoint + * @param alt is the current altitude + */ + void _setFastDescend(float alt_setpoint, float alt); }; diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index c4ce648381ad..a1286db40252 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -129,6 +129,7 @@ FixedwingPositionControl::parameters_update() _tecs.set_speed_weight(_param_fw_t_spdweight.get()); _tecs.set_equivalent_airspeed_trim(_performance_model.getCalibratedTrimAirspeed()); _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); + _tecs.set_equivalent_airspeed_max(_performance_model.getMaximumCalibratedAirspeed()); _tecs.set_throttle_damp(_param_fw_t_thr_damping.get()); _tecs.set_integrator_gain_throttle(_param_fw_t_thr_integ.get()); _tecs.set_integrator_gain_pitch(_param_fw_t_I_gain_pit.get()); @@ -137,6 +138,7 @@ FixedwingPositionControl::parameters_update() _tecs.set_roll_throttle_compensation(_param_fw_t_rll2thr.get()); _tecs.set_pitch_damping(_param_fw_t_ptch_damp.get()); _tecs.set_altitude_error_time_constant(_param_fw_t_h_error_tc.get()); + _tecs.set_fast_descend_altitude_error(_param_fw_t_fast_alt_err.get()); _tecs.set_altitude_rate_ff(_param_fw_t_hrate_ff.get()); _tecs.set_airspeed_error_time_constant(_param_fw_t_tas_error_tc.get()); _tecs.set_ste_rate_time_const(_param_ste_rate_time_const.get()); diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index 5089021685da..eb4216048367 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -964,6 +964,7 @@ class FixedwingPositionControl final : public ModuleBase) _param_fw_t_hrate_ff, (ParamFloat) _param_fw_t_h_error_tc, + (ParamFloat) _param_fw_t_fast_alt_err, (ParamFloat) _param_fw_t_thr_integ, (ParamFloat) _param_fw_t_I_gain_pit, (ParamFloat) _param_fw_t_ptch_damp, diff --git a/src/modules/fw_pos_control/fw_path_navigation_params.c b/src/modules/fw_pos_control/fw_path_navigation_params.c index a636d8d75768..33ee50a8df8a 100644 --- a/src/modules/fw_pos_control/fw_path_navigation_params.c +++ b/src/modules/fw_pos_control/fw_path_navigation_params.c @@ -633,6 +633,15 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f); */ PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f); +/** + * Minimum altitude error needed to descend with max airspeed. A negative value disables fast descend. + * + * @min -1.0 + * @decimal 0 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_F_ALT_ERR, -1.0f); + /** * Height rate feed forward * From f8a20e1964632d16e6a33af0a48408604a78affd Mon Sep 17 00:00:00 2001 From: Konrad Date: Tue, 13 Feb 2024 14:52:43 +0100 Subject: [PATCH 210/652] TECS: increase airspeed control limit for fast descend --- src/lib/tecs/TECS.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index d25821b94921..082cc1234768 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -320,9 +320,11 @@ float TECSControl::_calcAirspeedControlOutput(const Setpoint &setpoint, const In // if airspeed measurement is not enabled then always set the rate setpoint to zero in order to avoid constant rate setpoints if (flag.airspeed_enabled) { // Calculate limits for the demanded rate of change of speed based on physical performance limits - // with a 50% margin to allow the total energy controller to correct for errors. - const float max_tas_rate_sp = 0.5f * limit.STE_rate_max / math::max(input.tas, FLT_EPSILON); - const float min_tas_rate_sp = 0.5f * limit.STE_rate_min / math::max(input.tas, FLT_EPSILON); + // with a 50% margin to allow the total energy controller to correct for errors. Increase it in case of fast descend + const float max_tas_rate_sp = (param.fast_descend * 0.5f + 0.5f) * limit.STE_rate_max / math::max(input.tas, + FLT_EPSILON); + const float min_tas_rate_sp = (param.fast_descend * 0.5f + 0.5f) * limit.STE_rate_min / math::max(input.tas, + FLT_EPSILON); airspeed_rate_output = constrain((setpoint.tas_setpoint - input.tas) * param.airspeed_error_gain, min_tas_rate_sp, max_tas_rate_sp); } From f56f4c7033540bf3e3df102e9c59d9b2de7a25c4 Mon Sep 17 00:00:00 2001 From: Konrad Date: Tue, 13 Feb 2024 08:49:39 +0100 Subject: [PATCH 211/652] TECS: enable specific energy weights to have a value up to 2 --- src/lib/tecs/TECS.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index 082cc1234768..b6ac0d8fcad5 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -402,10 +402,8 @@ TECSControl::SpecificEnergyWeighting TECSControl::_updateSpeedAltitudeWeights(co } - // don't allow any weight to be larger than one, as it has the same effect as reducing the control - // loop time constant and therefore can lead to a destabilization of that control loop - weight.spe_weighting = constrain(2.0f - pitch_speed_weight, 0.f, 1.f); - weight.ske_weighting = constrain(pitch_speed_weight, 0.f, 1.f); + weight.spe_weighting = constrain(2.0f - pitch_speed_weight, 0.f, 2.f); + weight.ske_weighting = constrain(pitch_speed_weight, 0.f, 2.f); return weight; } From 6984e6da7f770971fcb16779014a5452416df811 Mon Sep 17 00:00:00 2001 From: Konrad Date: Tue, 13 Feb 2024 14:57:08 +0100 Subject: [PATCH 212/652] TECS:use tas_setpoint instead of measured tas for specific kinetic energy calculation --- src/lib/tecs/TECS.cpp | 5 ++++- src/lib/tecs/TECS.hpp | 1 + 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index b6ac0d8fcad5..0c264706831d 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -231,6 +231,8 @@ void TECSControl::initialize(const Setpoint &setpoint, const Input &input, Param AltitudePitchControl control_setpoint; + control_setpoint.tas_setpoint = setpoint.tas_setpoint; + control_setpoint.tas_rate_setpoint = _calcAirspeedControlOutput(setpoint, input, param, flag); control_setpoint.altitude_rate_setpoint = _calcAltitudeControlOutput(setpoint, input, param); @@ -274,6 +276,7 @@ void TECSControl::update(const float dt, const Setpoint &setpoint, const Input & AltitudePitchControl control_setpoint; + control_setpoint.tas_setpoint = setpoint.tas_setpoint; control_setpoint.tas_rate_setpoint = _calcAirspeedControlOutput(setpoint, input, param, flag); if (PX4_ISFINITE(setpoint.altitude_rate_setpoint_direct)) { @@ -350,7 +353,7 @@ TECSControl::SpecificEnergyRates TECSControl::_calcSpecificEnergyRates(const Alt // Calculate specific energy rate demands in units of (m**2/sec**3) specific_energy_rates.spe_rate.setpoint = control_setpoint.altitude_rate_setpoint * CONSTANTS_ONE_G; // potential energy rate of change - specific_energy_rates.ske_rate.setpoint = input.tas * + specific_energy_rates.ske_rate.setpoint = control_setpoint.tas_setpoint * control_setpoint.tas_rate_setpoint; // kinetic energy rate of change // Calculate specific energy rates in units of (m**2/sec**3) diff --git a/src/lib/tecs/TECS.hpp b/src/lib/tecs/TECS.hpp index 64881fb17f31..3c16b97066e8 100644 --- a/src/lib/tecs/TECS.hpp +++ b/src/lib/tecs/TECS.hpp @@ -366,6 +366,7 @@ class TECSControl struct AltitudePitchControl { float altitude_rate_setpoint; ///< Controlled altitude rate setpoint [m/s]. float tas_rate_setpoint; ///< Controlled true airspeed rate setpoint [m/s²]. + float tas_setpoint; ///< Controller true airspeed setpoint [m/s] }; /** From b5467d88f7d4698880552c87487632e78c388406 Mon Sep 17 00:00:00 2001 From: muramura Date: Mon, 29 Apr 2024 19:41:44 +0900 Subject: [PATCH 213/652] gps: Change the IF statement to a SWITCH statement --- src/drivers/gps/gps.cpp | 23 +++++++++++++++++------ 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index ce46883c9cf4..5cfe9eaaaf9e 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -728,7 +728,8 @@ GPS::run() int32_t gps_ubx_mode = 0; param_get(handle, &gps_ubx_mode); - if (gps_ubx_mode == 1) { // heading + switch (gps_ubx_mode) { + case 1: // heading if (_instance == Instance::Main) { ubx_mode = GPSDriverUBX::UBXMode::RoverWithMovingBase; @@ -736,10 +737,13 @@ GPS::run() ubx_mode = GPSDriverUBX::UBXMode::MovingBase; } - } else if (gps_ubx_mode == 2) { + break; + + case 2: ubx_mode = GPSDriverUBX::UBXMode::MovingBase; + break; - } else if (gps_ubx_mode == 3) { + case 3: if (_instance == Instance::Main) { ubx_mode = GPSDriverUBX::UBXMode::RoverWithMovingBaseUART1; @@ -747,11 +751,18 @@ GPS::run() ubx_mode = GPSDriverUBX::UBXMode::MovingBaseUART1; } - } else if (gps_ubx_mode == 4) { + break; + + case 4: ubx_mode = GPSDriverUBX::UBXMode::MovingBaseUART1; + break; - } else if (gps_ubx_mode == 5) { // rover with static base on Uart2 + case 5: // rover with static base on Uart2 ubx_mode = GPSDriverUBX::UBXMode::RoverWithStaticBaseUart2; + break; + + default: + break; } } @@ -1561,4 +1572,4 @@ int gps_main(int argc, char *argv[]) { return GPS::main(argc, argv); -} \ No newline at end of file +} From ca9cb2214f2a5d290e0c5a0ace1c6ce4264fa16f Mon Sep 17 00:00:00 2001 From: RomanBapst Date: Thu, 2 May 2024 14:44:35 +0200 Subject: [PATCH 214/652] quadchute: fixed sign for handling altitude resets Signed-off-by: RomanBapst --- src/modules/vtol_att_control/vtol_type.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/vtol_att_control/vtol_type.cpp b/src/modules/vtol_att_control/vtol_type.cpp index 808c9c03c2a9..1d6f5b667a5c 100644 --- a/src/modules/vtol_att_control/vtol_type.cpp +++ b/src/modules/vtol_att_control/vtol_type.cpp @@ -324,7 +324,7 @@ void VtolType::handleEkfResets() _altitude_reset_counter = _local_pos->z_reset_counter; if (PX4_ISFINITE(_quadchute_ref_alt)) { - _quadchute_ref_alt += _local_pos->delta_z; + _quadchute_ref_alt -= _local_pos->delta_z; } } From b9a696d025e9cbd2cdaa08a7e94ec2d91275d9a0 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Tue, 7 May 2024 11:17:20 -0600 Subject: [PATCH 215/652] boards: ark septentrio gps add iis2mdc --- boards/ark/septentrio-gps/default.px4board | 2 +- boards/ark/septentrio-gps/init/rc.board_sensors | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/boards/ark/septentrio-gps/default.px4board b/boards/ark/septentrio-gps/default.px4board index b62a95d689d5..7600200577e1 100644 --- a/boards/ark/septentrio-gps/default.px4board +++ b/boards/ark/septentrio-gps/default.px4board @@ -1,13 +1,13 @@ CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" CONFIG_BOARD_ARCHITECTURE="cortex-m4" CONFIG_BOARD_ROMFSROOT="cannode" -CONFIG_BOARD_NO_HELP=y CONFIG_BOARD_CONSTRAINED_MEMORY=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_BOOTLOADERS=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y +CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_TONE_ALARM=y CONFIG_BOARD_UAVCAN_INTERFACES=1 diff --git a/boards/ark/septentrio-gps/init/rc.board_sensors b/boards/ark/septentrio-gps/init/rc.board_sensors index 43e4e6c506cc..a41dd7b070ec 100644 --- a/boards/ark/septentrio-gps/init/rc.board_sensors +++ b/boards/ark/septentrio-gps/init/rc.board_sensors @@ -8,4 +8,7 @@ icm42688p -R 0 -s start bmp388 -I -b 1 start -bmm150 -I -b 1 start +if ! iis2mdc -R 4 -I -b 1 start +then + bmm150 -I -b 1 start +fi From 5d025e6d3d7a3b6e75f414338da0d3572300d9fd Mon Sep 17 00:00:00 2001 From: Benjamin Philipp Ketterer Date: Mon, 6 May 2024 10:44:52 +0200 Subject: [PATCH 216/652] increased uxrce-dds stack size to prevent overflow --- src/modules/uxrce_dds_client/uxrce_dds_client.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp index 1412414b6300..20428c691ebb 100644 --- a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp +++ b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp @@ -831,7 +831,7 @@ int UxrceddsClient::task_spawn(int argc, char *argv[]) _task_id = px4_task_spawn_cmd("uxrce_dds_client", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - PX4_STACK_ADJUSTED(10000), + PX4_STACK_ADJUSTED(12000), (px4_main_t)&run_trampoline, (char *const *)argv); From b1b9c8fd99f3e40bb05c4c1c7acffdf9ca5c7c7d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 6 May 2024 16:04:24 +1200 Subject: [PATCH 217/652] gps: add note to param This notes the reference yaw angle for the Septentrio Mosaic-H. It's unfortunately a bit tricky in that Unicore has the main antenna in front by default while Septentrio decided to put the aux antenna in front. Signed-off-by: Julian Oes --- src/drivers/gps/params.c | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/drivers/gps/params.c b/src/drivers/gps/params.c index de58e9e90795..e00048ea065d 100644 --- a/src/drivers/gps/params.c +++ b/src/drivers/gps/params.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2016 PX4 Development Team. All rights reserved. + * Copyright (c) 2016-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 @@ -152,8 +152,9 @@ PARAM_DEFINE_INT32(GPS_UBX_CFG_INTF, 0); * * The offset angle increases clockwise. * - * Set this to 90 if the rover (or Unicore primary) antenna is placed on the - * right side of the vehicle and the moving base antenna is on the left side. + * Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux) + * antenna is placed on the right side of the vehicle and the moving base + * antenna is on the left side. * * (Note: the Unicore primary antenna is the one connected on the right as seen * from the top). From 57898036654da32d6a80f228f79f9543ad8cb1f0 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 8 May 2024 10:39:33 +0200 Subject: [PATCH 218/652] fmu-v6xrt: Enable debug features for more verbose hardfault output --- boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig | 3 +++ 1 file changed, 3 insertions(+) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index fe4f46860b8e..d3e1891c058f 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -46,7 +46,10 @@ CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 CONFIG_CDCACM_VENDORID=0x3643 CONFIG_CDCACM_VENDORSTR="Dronecode Project, Inc." +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_FEATURES=y CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y CONFIG_DEBUG_SYMBOLS=y CONFIG_DEBUG_TCBINFO=y CONFIG_DEV_FIFO_SIZE=0 From 253208fdd4d3b415ef9ce019d7b5475a3e103a8a Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Tue, 7 May 2024 18:47:44 +0200 Subject: [PATCH 219/652] fmu-v6xrt: Add I2C driver launcher --- boards/px4/fmu-v6xrt/default.px4board | 2 ++ boards/px4/fmu-v6xrt/init/rc.board_defaults | 4 ++- boards/px4/fmu-v6xrt/init/rc.board_sensors | 25 +++++++++++++++++++ .../px4/fmu-v6xrt/nuttx-config/nsh/defconfig | 2 +- 4 files changed, 31 insertions(+), 2 deletions(-) diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index f9961fd7bbfb..029462aa4806 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -33,6 +33,7 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y CONFIG_DRIVERS_RC_INPUT=y @@ -84,6 +85,7 @@ CONFIG_SYSTEMCMDS_BSONDUMP=y CONFIG_SYSTEMCMDS_DMESG=y CONFIG_SYSTEMCMDS_DUMPFILE=y CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y CONFIG_SYSTEMCMDS_I2CDETECT=y CONFIG_SYSTEMCMDS_IO_BYPASS_CONTROL=y CONFIG_SYSTEMCMDS_LED_CONTROL=y diff --git a/boards/px4/fmu-v6xrt/init/rc.board_defaults b/boards/px4/fmu-v6xrt/init/rc.board_defaults index 45282796efde..a5a3dc10162c 100644 --- a/boards/px4/fmu-v6xrt/init/rc.board_defaults +++ b/boards/px4/fmu-v6xrt/init/rc.board_defaults @@ -12,9 +12,11 @@ param set-default MAV_2_RATE 100000 param set-default MAV_2_REMOTE_PRT 14550 param set-default MAV_2_UDP_PRT 14550 +# By disabling all 3 INA modules, we use the +# i2c_launcher instead. param set-default SENS_EN_INA238 0 param set-default SENS_EN_INA228 0 -param set-default SENS_EN_INA226 1 +param set-default SENS_EN_INA226 0 safety_button start diff --git a/boards/px4/fmu-v6xrt/init/rc.board_sensors b/boards/px4/fmu-v6xrt/init/rc.board_sensors index 64779648a4b2..8582c617a477 100644 --- a/boards/px4/fmu-v6xrt/init/rc.board_sensors +++ b/boards/px4/fmu-v6xrt/init/rc.board_sensors @@ -17,6 +17,7 @@ #------------------------------------------------------------------------------ set HAVE_PM2 yes +set INA_CONFIGURED no if mft query -q -k MFT -s MFT_PM2 -v 0 then @@ -39,6 +40,8 @@ then then ina226 -X -b 2 -t 2 -k start fi + + set INA_CONFIGURED yes fi if param compare SENS_EN_INA228 1 @@ -49,6 +52,8 @@ then then ina228 -X -b 2 -t 2 -k start fi + + set INA_CONFIGURED yes fi if param compare SENS_EN_INA238 1 @@ -59,6 +64,25 @@ then then ina238 -X -b 2 -t 2 -k start fi + + set INA_CONFIGURED yes +fi + +#Start Auterion Power Module selector for Skynode boards +if ver hwbasecmp 009 010 +then + pm_selector_auterion start +else + if [ $INA_CONFIGURED = no ] + then + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] + then + i2c_launcher start -b 2 + fi + fi +fi fi # Internal SPI bus ICM42686p (hard-mounted) @@ -88,4 +112,5 @@ fi bmp388 -X -b 2 start +unset INA_CONFIGURED unset HAVE_PM2 diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index d3e1891c058f..e541c5effe90 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -260,7 +260,6 @@ CONFIG_SCHED_INSTRUMENTATION_SWITCH=y CONFIG_SCHED_LPWORK=y CONFIG_SCHED_LPWORKPRIORITY=50 CONFIG_SCHED_LPWORKSTACKSIZE=2032 -CONFIG_SCHED_WAITPID=y CONFIG_SDIO_BLOCKSETUP=y CONFIG_SEM_PREALLOCHOLDERS=32 CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y @@ -279,6 +278,7 @@ CONFIG_SYSTEM_CLE=y CONFIG_SYSTEM_DHCPC_RENEW=y CONFIG_SYSTEM_NSH=y CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y CONFIG_TASK_NAME_SIZE=24 CONFIG_USBDEV=y CONFIG_USBDEV_BUSPOWERED=y From 839f5bbb125eef41e154f2c251cc13b281a70eef Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Mon, 13 May 2024 15:01:43 -0700 Subject: [PATCH 220/652] Removed obsolete voxl 2 board default parameter setting --- boards/modalai/voxl2/scripts/install-voxl.sh | 1 - boards/modalai/voxl2/target/voxl-px4 | 6 - .../voxl-px4-set-default-parameters.config | 192 ------------------ 3 files changed, 199 deletions(-) delete mode 100755 boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config diff --git a/boards/modalai/voxl2/scripts/install-voxl.sh b/boards/modalai/voxl2/scripts/install-voxl.sh index 4a88a7a56f80..a908b0a83576 100755 --- a/boards/modalai/voxl2/scripts/install-voxl.sh +++ b/boards/modalai/voxl2/scripts/install-voxl.sh @@ -20,7 +20,6 @@ adb shell chmod a+x /usr/bin/voxl-px4-hitl-start # Push configuration file adb shell mkdir -p /etc/modalai -adb push boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config /etc/modalai adb push boards/modalai/voxl2/target/voxl-px4-fake-imu-calibration.config /etc/modalai adb push boards/modalai/voxl2/target/voxl-px4-hitl-set-default-parameters.config /etc/modalai diff --git a/boards/modalai/voxl2/target/voxl-px4 b/boards/modalai/voxl2/target/voxl-px4 index 3ce4309ee2ba..bf1b62e981aa 100755 --- a/boards/modalai/voxl2/target/voxl-px4 +++ b/boards/modalai/voxl2/target/voxl-px4 @@ -129,12 +129,6 @@ else DAEMON="-d" fi -if [ ! -f /data/px4/param/parameters ]; then - echo "[INFO] Setting default parameters for PX4 on voxl" - px4 $DAEMON -s /etc/modalai/voxl-px4-set-default-parameters.config - /bin/sync -fi - if [ $SENSOR_CAL == "FAKE" ]; then /bin/echo "[INFO] Setting up fake sensor calibration values" px4 $DAEMON -s /etc/modalai/voxl-px4-fake-imu-calibration.config diff --git a/boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config b/boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config deleted file mode 100755 index bb4045b39734..000000000000 --- a/boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config +++ /dev/null @@ -1,192 +0,0 @@ -#!/bin/sh -# PX4 commands need the 'px4-' prefix in bash. -# (px4-alias.sh is expected to be in the PATH) -. px4-alias.sh - -param select /data/px4/param/parameters - -# Make sure we are running at 800Hz on IMU -param set IMU_GYRO_RATEMAX 800 - -# EKF2 Parameters -param set EKF2_IMU_POS_X 0.027 -param set EKF2_IMU_POS_Y 0.009 -param set EKF2_IMU_POS_Z -0.019 -param set EKF2_EV_DELAY 5 -param set EKF2_AID_MASK 280 -param set EKF2_ABL_LIM 0.8 -param set EKF2_TAU_POS 0.25 -param set EKF2_TAU_VEL 0.25 - -param set MC_AIRMODE 0 - -param set MC_YAW_P 2.0 -param set MC_YAWRATE_P 0.15 -param set MC_YAWRATE_I 0.1 -param set MC_YAWRATE_D 0.0 -param set MC_YAWRATE_K 1.0 - -param set MC_PITCH_P 5.5 -param set MC_PITCHRATE_P 0.08 -param set MC_PITCHRATE_I 0.2 -param set MC_PITCHRATE_D 0.0013 -param set MC_PITCHRATE_K 1.0 - -param set MC_ROLL_P 5.5 -param set MC_ROLLRATE_P 0.08 -param set MC_ROLLRATE_I 0.2 -param set MC_ROLLRATE_D 0.0013 -param set MC_ROLLRATE_K 1.0 - -param set MPC_VELD_LP 5.0 - -# tweak MPC_THR_MIN to prevent roll/pitch losing control -# authority under rapid downward acceleration -param set MPC_THR_MAX 0.75 -param set MPC_THR_MIN 0.08 -param set MPC_THR_HOVER 0.42 -param set MPC_MANTHR_MIN 0.05 - -# default position mode with a little expo, smooth mode is terrible -param set MPC_POS_MODE 0 -param set MPC_YAW_EXPO 0.20 -param set MPC_XY_MAN_EXPO 0.20 -param set MPC_Z_MAN_EXPO 0.20 - -# max velocities -param set MPC_VEL_MANUAL 5.0 -param set MPC_XY_VEL_MAX 5.0 -param set MPC_XY_CRUISE 5.0 -param set MPC_Z_VEL_MAX_DN 1.5 -param set MPC_Z_VEL_MAX_UP 4.0 -param set MPC_LAND_SPEED 1.0 - -# Horizontal position PID -param set MPC_XY_P 0.95 -param set MPC_XY_VEL_P_ACC 3.00 -param set MPC_XY_VEL_I_ACC 0.10 -param set MPC_XY_VEL_D_ACC 0.00 - -# Vertical position PID -# PX4 Defaults -param set MPC_Z_P 1.0 -param set MPC_Z_VEL_P_ACC 8.0 -param set MPC_Z_VEL_I_ACC 2.0 -param set MPC_Z_VEL_D_ACC 0.0 - -param set MPC_TKO_RAMP_T 1.50 -param set MPC_TKO_SPEED 1.50 - -# Set the ESC outputs to function as motors -param set VOXL_ESC_FUNC1 101 -param set VOXL_ESC_FUNC2 103 -param set VOXL_ESC_FUNC3 104 -param set VOXL_ESC_FUNC4 102 - -param set VOXL_ESC_SDIR1 0 -param set VOXL_ESC_SDIR2 0 -param set VOXL_ESC_SDIR3 0 -param set VOXL_ESC_SDIR4 0 - -param set VOXL_ESC_CONFIG 1 -param set VOXL_ESC_REV 0 -param set VOXL_ESC_MODE 0 -param set VOXL_ESC_BAUD 2000000 -param set VOXL_ESC_RPM_MAX 10500 -param set VOXL_ESC_RPM_MIN 1000 - -# Set the Voxl2 IO outputs to function as motors -param set VOXL2_IO_FUNC1 101 -param set VOXL2_IO_FUNC2 102 -param set VOXL2_IO_FUNC3 103 -param set VOXL2_IO_FUNC4 104 - -param set VOXL2_IO_BAUD 921600 -param set VOXL2_IO_MIN 1000 -param set VOXL2_IO_MAX 2000 - -# Some parameters for control allocation -param set CA_ROTOR_COUNT 4 -param set CA_R_REV 0 -param set CA_AIRFRAME 0 -param set CA_ROTOR_COUNT 4 -param set CA_ROTOR0_PX 0.15 -param set CA_ROTOR0_PY 0.15 -param set CA_ROTOR1_PX -0.15 -param set CA_ROTOR1_PY -0.15 -param set CA_ROTOR2_PX 0.15 -param set CA_ROTOR2_PY -0.15 -param set CA_ROTOR2_KM -0.05 -param set CA_ROTOR3_PX -0.15 -param set CA_ROTOR3_PY 0.15 -param set CA_ROTOR3_KM -0.05 - -# Some parameter settings to disable / ignore certain preflight checks - -# No GPS driver yet so disable it -param set SYS_HAS_GPS 0 - -# Allow arming wihtout a magnetometer (Need magnetometer driver) -param set SYS_HAS_MAG 0 -param set EKF2_MAG_TYPE 5 - -# Allow arming without battery check (Need voxlpm driver) -param set CBRK_SUPPLY_CHK 894281 - -# Allow arming without an SD card -param set COM_ARM_SDCARD 0 - -# Allow arming wihtout CPU load information -param set COM_CPU_MAX 0.0 - -# Disable auto disarm. This is number of seconds to wait for takeoff -# after arming. If no takeoff happens then it will disarm. A negative -# value disables this. -param set COM_DISARM_PRFLT -1 - -# This parameter doesn't exist anymore. Need to see what the new method is. -# param set MAV_BROADCAST 0 - -# Doesn't work without setting this to Quadcopter -param set MAV_TYPE 2 - -# Parameters that we don't use but QGC complains about if they aren't there -param set SYS_AUTOSTART 4001 - -# Default RC channel mappings -param set RC_MAP_ACRO_SW 0 -param set RC_MAP_ARM_SW 0 -param set RC_MAP_AUX1 0 -param set RC_MAP_AUX2 0 -param set RC_MAP_AUX3 0 -param set RC_MAP_AUX4 0 -param set RC_MAP_AUX5 0 -param set RC_MAP_AUX6 0 -param set RC_MAP_FAILSAFE 0 -param set RC_MAP_FLAPS 0 -param set RC_MAP_FLTMODE 6 -param set RC_MAP_GEAR_SW 0 -param set RC_MAP_KILL_SW 7 -param set RC_MAP_LOITER_SW 0 -param set RC_MAP_MAN_SW 0 -param set RC_MAP_MODE_SW 0 -param set RC_MAP_OFFB_SW 0 -param set RC_MAP_PARAM1 0 -param set RC_MAP_PARAM2 0 -param set RC_MAP_PARAM3 0 -param set RC_MAP_PITCH 2 -param set RC_MAP_POSCTL_SW 0 -param set RC_MAP_RATT_SW 0 -param set RC_MAP_RETURN_SW 0 -param set RC_MAP_ROLL 1 -param set RC_MAP_STAB_SW 0 -param set RC_MAP_THROTTLE 3 -param set RC_MAP_TRANS_SW 0 -param set RC_MAP_YAW 4 - -param save - -sleep 2 - -# Need px4-shutdown otherwise Linux system shutdown is called -px4-shutdown From 293389abf3f531300cdb7315bf686e5eff323150 Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Mon, 13 May 2024 11:48:08 -0700 Subject: [PATCH 221/652] Minor updates to the VOXL 2 board README file --- boards/modalai/voxl2/README.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/boards/modalai/voxl2/README.md b/boards/modalai/voxl2/README.md index 02d7f6fc5ab4..ac6bd1f5f15c 100644 --- a/boards/modalai/voxl2/README.md +++ b/boards/modalai/voxl2/README.md @@ -9,7 +9,7 @@ When running PX4 directly on the QRB5165 SoC it runs partially on the Sensor Low The portion running on the DSP hosts the flight critical portions of PX4 such as the IMU, barometer, magnetometer, GPS, ESC, and power management drivers, and the state estimation. The DSP acts as the real time portion of the system. Non flight -critical applications such as Mavlink, logging, and commander are running on the +critical applications such as Mavlink, and logging are running on the ARM CPU cluster (aka apps proc). The DSP and ARM CPU cluster communicate via a Qualcomm proprietary shared memory interface. @@ -27,6 +27,7 @@ The full instructions are available here: ``` px4$ boards/modalai/voxl2/scripts/run-docker.sh root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/clean.sh +root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-deps.sh root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-apps.sh root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-slpi.sh root@9373fa1401b8:/usr/local/workspace# exit @@ -69,16 +70,15 @@ pxh> ## Notes You cannot cleanly shutdown PX4 with the shutdown command on VOXL 2. You have -to power cycle the board and restart everything. +to power cycle the board and restart everything. Starting with SDK 1.3.0 it is possible +to cleanly shutdown PX4 on VOXL 2. ## Tips -Start with a VOXL 2 that only has the system image installed, not the SDK - -Run the command ```voxl-px4 -s``` on target to run the self-test +Always use the latest SDK release In order to see DSP specific debug messages the mini-dm tool in the Hexagon SDK -can be used: +can be used (Most messages are passed to the apps proc but certain low level messages are not): ``` modalai@modalai-XPS-15-9570:/local/mnt/workspace/Qualcomm/Hexagon_SDK/4.1.0.4/tools/debug/mini-dm/Ubuntu18$ sudo ./mini-dm [sudo] password for modalai: From 17916b7fdc91822f7414f1f2da748ab8bd622cad Mon Sep 17 00:00:00 2001 From: Konrad Date: Tue, 14 May 2024 13:37:54 +0200 Subject: [PATCH 222/652] uxcre_dds_client: use topic name as defined in the dds_topics.yaml to register stream --- src/modules/uxrce_dds_client/dds_topics.h.em | 6 ++++-- src/modules/uxrce_dds_client/utilities.hpp | 18 +++++++++++------- 2 files changed, 15 insertions(+), 9 deletions(-) diff --git a/src/modules/uxrce_dds_client/dds_topics.h.em b/src/modules/uxrce_dds_client/dds_topics.h.em index cade47b5fdce..3c4311e6c333 100644 --- a/src/modules/uxrce_dds_client/dds_topics.h.em +++ b/src/modules/uxrce_dds_client/dds_topics.h.em @@ -43,6 +43,7 @@ struct SendSubscription { const struct orb_metadata *orb_meta; uxrObjectId data_writer; const char* dds_type_name; + const char* topic; uint32_t topic_size; UcdrSerializeMethod ucdr_serialize_method; }; @@ -54,6 +55,7 @@ struct SendTopicsSubs { { ORB_ID(@(pub['topic_simple'])), uxr_object_id(0, UXR_INVALID_ID), "@(pub['dds_type'])", + "@(pub['topic'])", ucdr_topic_size_@(pub['simple_base_type'])(), &ucdr_serialize_@(pub['simple_base_type']), }, @@ -96,7 +98,7 @@ void SendTopicsSubs::update(uxrSession *session, uxrStreamId reliable_out_stream orb_copy(send_subscriptions[idx].orb_meta, fds[idx].fd, &topic_data); if (send_subscriptions[idx].data_writer.id == UXR_INVALID_ID) { // data writer not created yet - create_data_writer(session, reliable_out_stream_id, participant_id, static_cast(send_subscriptions[idx].orb_meta->o_id), client_namespace, send_subscriptions[idx].orb_meta->o_name, + create_data_writer(session, reliable_out_stream_id, participant_id, static_cast(send_subscriptions[idx].orb_meta->o_id), client_namespace, send_subscriptions[idx].topic, send_subscriptions[idx].dds_type_name, send_subscriptions[idx].data_writer); } @@ -169,7 +171,7 @@ bool RcvTopicsPubs::init(uxrSession *session, uxrStreamId reliable_out_stream_id @[ for idx, sub in enumerate(subscriptions + subscriptions_multi)]@ { uint16_t queue_depth = orb_get_queue_size(ORB_ID(@(sub['simple_base_type']))) * 2; // use a bit larger queue size than internal - create_data_reader(session, reliable_out_stream_id, best_effort_in_stream_id, participant_id, @(idx), client_namespace, "@(sub['topic_simple'])", "@(sub['dds_type'])", queue_depth); + create_data_reader(session, reliable_out_stream_id, best_effort_in_stream_id, participant_id, @(idx), client_namespace, "@(sub['topic'])", "@(sub['dds_type'])", queue_depth); } @[ end for]@ diff --git a/src/modules/uxrce_dds_client/utilities.hpp b/src/modules/uxrce_dds_client/utilities.hpp index 5c7fb2e9dc2d..70886ec795ff 100644 --- a/src/modules/uxrce_dds_client/utilities.hpp +++ b/src/modules/uxrce_dds_client/utilities.hpp @@ -23,25 +23,29 @@ uxrObjectId topic_id_from_orb(ORB_ID orb_id, uint8_t instance = 0) return uxrObjectId{}; } -static bool generate_topic_name(char *topic, const char *client_namespace, const char *direction, const char *name) +static bool generate_topic_name(char *topic_name, const char *client_namespace, const char *topic) { + if (topic[0] == '/') { + topic++; + } + if (client_namespace != nullptr) { - int ret = snprintf(topic, TOPIC_NAME_SIZE, "rt/%s/fmu/%s/%s", client_namespace, direction, name); + int ret = snprintf(topic_name, TOPIC_NAME_SIZE, "rt/%s/%s", client_namespace, topic); return (ret > 0 && ret < TOPIC_NAME_SIZE); } - int ret = snprintf(topic, TOPIC_NAME_SIZE, "rt/fmu/%s/%s", direction, name); + int ret = snprintf(topic_name, TOPIC_NAME_SIZE, "rt/%s", topic); return (ret > 0 && ret < TOPIC_NAME_SIZE); } static bool create_data_writer(uxrSession *session, uxrStreamId reliable_out_stream_id, uxrObjectId participant_id, - ORB_ID orb_id, const char *client_namespace, const char *topic_name_simple, const char *type_name, + ORB_ID orb_id, const char *client_namespace, const char *topic, const char *type_name, uxrObjectId &datawriter_id) { // topic char topic_name[TOPIC_NAME_SIZE]; - if (!generate_topic_name(topic_name, client_namespace, "out", topic_name_simple)) { + if (!generate_topic_name(topic_name, client_namespace, topic)) { PX4_ERR("topic path too long"); return false; } @@ -87,13 +91,13 @@ static bool create_data_writer(uxrSession *session, uxrStreamId reliable_out_str } static bool create_data_reader(uxrSession *session, uxrStreamId reliable_out_stream_id, uxrStreamId input_stream_id, - uxrObjectId participant_id, uint16_t index, const char *client_namespace, const char *topic_name_simple, + uxrObjectId participant_id, uint16_t index, const char *client_namespace, const char *topic, const char *type_name, uint16_t queue_depth) { // topic char topic_name[TOPIC_NAME_SIZE]; - if (!generate_topic_name(topic_name, client_namespace, "in", topic_name_simple)) { + if (!generate_topic_name(topic_name, client_namespace, topic)) { PX4_ERR("topic path too long"); return false; } From 2e7a99ac410a680a78512048b216fabe29a2aa3b Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 15 May 2024 10:52:26 +1000 Subject: [PATCH 223/652] VectorNav.cpp - fix docs link to usage guide --- src/drivers/ins/vectornav/VectorNav.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/ins/vectornav/VectorNav.cpp b/src/drivers/ins/vectornav/VectorNav.cpp index 991b1262958f..cbe7ab535257 100644 --- a/src/drivers/ins/vectornav/VectorNav.cpp +++ b/src/drivers/ins/vectornav/VectorNav.cpp @@ -832,7 +832,7 @@ Serial bus driver for the VectorNav VN-100, VN-200, VN-300. Most boards are configured to enable/start the driver on a specified UART using the SENS_VN_CFG parameter. -Setup/usage information: https://docs.px4.io/master/en/sensor/vectornav.html +Setup/usage information: https://docs.px4.io/main/en/sensor/vectornav.html ### Examples From ee2a8c9bda06425c4c78e72455059692309431b1 Mon Sep 17 00:00:00 2001 From: dirksavage88 Date: Wed, 8 May 2024 10:58:06 -0400 Subject: [PATCH 224/652] increase lp default stack to 2000 Signed-off-by: dirksavage88 --- .../px4_platform_common/px4_work_queue/WorkQueueManager.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp index 5310701eebda..761041fa0e83 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp @@ -89,7 +89,7 @@ static constexpr wq_config_t ttyS9{"wq:ttyS9", 1728, -30}; static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1728, -31}; static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1728, -32}; -static constexpr wq_config_t lp_default{"wq:lp_default", 1920, -50}; +static constexpr wq_config_t lp_default{"wq:lp_default", 2000, -50}; static constexpr wq_config_t test1{"wq:test1", 2000, 0}; static constexpr wq_config_t test2{"wq:test2", 2000, 0}; From 9fd1c54570f406fe1ea7e2d33d81a83f19422ab7 Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Mon, 13 May 2024 09:15:46 +0200 Subject: [PATCH 225/652] style(editorconfig): update newline setting The setting wasn't consistent with the one used in the Visual Studio Code settings, which caused different newline formatting depending on whether the user uses Visual Studio Code or another editor that uses EditorConfig. --- .editorconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.editorconfig b/.editorconfig index 50a87fd83923..683f0fdc5159 100644 --- a/.editorconfig +++ b/.editorconfig @@ -1,7 +1,7 @@ root = true [*] -insert_final_newline = false +insert_final_newline = true [{*.{c,cpp,cc,h,hpp},CMakeLists.txt,Kconfig}] indent_style = tab From ecf4af7cf769358709ecd61bd7d0a4224868f031 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Wed, 15 May 2024 18:12:16 -0600 Subject: [PATCH 226/652] boards: ark cannode add ADIS16507 driver --- boards/ark/cannode/default.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/ark/cannode/default.px4board b/boards/ark/cannode/default.px4board index 3141d40b3089..d875f6b8211f 100644 --- a/boards/ark/cannode/default.px4board +++ b/boards/ark/cannode/default.px4board @@ -14,6 +14,7 @@ CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_COMMON_HYGROMETERS=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y +CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IRLOCK=y From 5fe955c24354808e05e81378784265b3f0ebc62c Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Thu, 2 May 2024 19:22:19 +0000 Subject: [PATCH 227/652] mRo Control Zero Classic: Definition for GPS2 by default added --- boards/mro/ctrl-zero-classic/init/rc.board_defaults | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/mro/ctrl-zero-classic/init/rc.board_defaults b/boards/mro/ctrl-zero-classic/init/rc.board_defaults index 110c240ee8a0..0495329e1a47 100644 --- a/boards/mro/ctrl-zero-classic/init/rc.board_defaults +++ b/boards/mro/ctrl-zero-classic/init/rc.board_defaults @@ -6,4 +6,5 @@ param set-default BAT1_V_DIV 10.1 param set-default BAT1_A_PER_V 17 +param set-default GPS_2_CONFIG 202 param set-default TEL_FRSKY_CONFIG 103 From 6a966ab065d9d60d203ce0567bc18e3f24462cab Mon Sep 17 00:00:00 2001 From: fury1895 Date: Thu, 16 May 2024 15:17:35 +0200 Subject: [PATCH 228/652] px4/fmu-v6x: set mavlink dialect to development --- boards/px4/fmu-v6x/default.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 4e21f0fd0870..f197a254a09a 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -66,6 +66,7 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y From 440465702e3a6fc6afc93f2d424cb1a4e6ab838d Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 17:21:50 +0200 Subject: [PATCH 229/652] wind_est_replay: fix cov matrix format and data indexing --- src/lib/wind_estimator/python/wind_estimator_replay.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/wind_estimator/python/wind_estimator_replay.py b/src/lib/wind_estimator/python/wind_estimator_replay.py index efa19eaf0e71..a44d62db4fd1 100644 --- a/src/lib/wind_estimator/python/wind_estimator_replay.py +++ b/src/lib/wind_estimator/python/wind_estimator_replay.py @@ -103,12 +103,12 @@ def run(logfile, use_gnss): P += Q * dt - if t_true_airspeed[i_airspeed] < t_now: + if i_airspeed < len(t_true_airspeed) and t_true_airspeed[i_airspeed] < t_now: while i_airspeed < len(t_true_airspeed) and t_true_airspeed[i_airspeed] < t_now: i_airspeed += 1 i_airspeed -= 1 - (H, K, innov_var, innov) = fuse_airspeed(np.asarray(v_local[:,i]), state, P.flatten(), true_airspeed[i_airspeed], R, epsilon) + (H, K, innov_var, innov) = fuse_airspeed(np.asarray(v_local[:,i]), state, P, true_airspeed[i_airspeed], R, epsilon) state += np.array(K) * innov P -= K * H * P i_airspeed += 1 From b42799fac2868f5f33dd8312eb45509da1721ccd Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 17:21:22 +0200 Subject: [PATCH 230/652] wind_est_replay: allow setting the initial scale factor --- src/lib/wind_estimator/python/wind_estimator_replay.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/src/lib/wind_estimator/python/wind_estimator_replay.py b/src/lib/wind_estimator/python/wind_estimator_replay.py index a44d62db4fd1..0a165dfe8df4 100644 --- a/src/lib/wind_estimator/python/wind_estimator_replay.py +++ b/src/lib/wind_estimator/python/wind_estimator_replay.py @@ -54,7 +54,7 @@ def getData(log, topic_name, variable_name, instance=0): def us2s(time_ms): return time_ms * 1e-6 -def run(logfile, use_gnss): +def run(logfile, use_gnss, scale_init): log = ULog(logfile) if use_gnss: @@ -75,7 +75,10 @@ def run(logfile, use_gnss): dist_bottom = getData(log, 'vehicle_local_position', 'dist_bottom') t_dist_bottom = us2s(getData(log, 'vehicle_local_position', 'timestamp')) - state = np.array([0.0, 0.0, 1.0]) + if scale_init is None: + scale_init = 1.0 + + state = np.array([0.0, 0.0, scale_init]) P = np.diag([1.0, 1.0, 1e-4]) wind_nsd = 1e-2 scale_nsd = 1e-4 @@ -145,8 +148,9 @@ def run(logfile, use_gnss): parser.add_argument('logfile', help='Full ulog file path, name and extension', type=str) parser.add_argument('--gnss', help='Use GNSS velocity instead of local velocity estimate', action='store_true') + parser.add_argument('--scale_init', help='Initial airsped scale factor (1.0 if not specified)', type=float) args = parser.parse_args() logfile = os.path.abspath(args.logfile) # Convert to absolute path - run(logfile, args.gnss) + run(logfile, args.gnss, args.scale_init) From 95ae5a657d900d80ed07772ff711ed5909d6140b Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 29 Apr 2024 11:37:16 -0400 Subject: [PATCH 231/652] ekf2: merge mag_3d_control + mag_control --- src/modules/ekf2/CMakeLists.txt | 1 - src/modules/ekf2/EKF/CMakeLists.txt | 1 - .../magnetometer/mag_3d_control.cpp | 225 ------------------ .../aid_sources/magnetometer/mag_control.cpp | 205 +++++++++++++++- src/modules/ekf2/EKF/ekf.h | 1 - 5 files changed, 196 insertions(+), 237 deletions(-) delete mode 100644 src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 7e9fcb7abf88..f21ce26d1142 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -187,7 +187,6 @@ endif() if(CONFIG_EKF2_MAGNETOMETER) list(APPEND EKF_SRCS - EKF/aid_sources/magnetometer/mag_3d_control.cpp EKF/aid_sources/magnetometer/mag_control.cpp EKF/aid_sources/magnetometer/mag_fusion.cpp ) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 03c9a481667b..fa57df04c735 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -109,7 +109,6 @@ endif() if(CONFIG_EKF2_MAGNETOMETER) list(APPEND EKF_SRCS - aid_sources/magnetometer/mag_3d_control.cpp aid_sources/magnetometer/mag_control.cpp aid_sources/magnetometer/mag_fusion.cpp ) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp deleted file mode 100644 index 41192f2cbf64..000000000000 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp +++ /dev/null @@ -1,225 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mag_3d_control.cpp - * Control functions for ekf mag 3D fusion - */ - -#include "ekf.h" - -void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, - estimator_aid_source3d_s &aid_src) -{ - static constexpr const char *AID_SRC_NAME = "mag"; - - resetEstimatorAidStatus(aid_src); - - const bool wmm_updated = (_wmm_gps_time_last_set >= aid_src.time_last_fuse); // WMM update can occur on the last epoch, just after mag fusion - - // determine if we should use mag fusion - bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) - && _control_status.flags.tilt_align - && (_control_status.flags.yaw_align || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && mag_sample.mag.longerThan(0.f) - && mag_sample.mag.isAllFinite(); - - const bool starting_conditions_passing = common_starting_conditions_passing - && continuing_conditions_passing; - - // For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise - // before they are used to constrain heading drift - _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) - && _control_status.flags.mag - && _control_status.flags.mag_aligned_in_flight - && (_control_status.flags.mag_heading_consistent || !_control_status.flags.gps) - && !_control_status.flags.mag_fault - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; - - const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; - - _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) - || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) - && _control_status.flags.tilt_align - && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) - || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && !_control_status.flags.mag_fault - && !_control_status.flags.mag_field_disturbed - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; - - // TODO: allow clearing mag_fault if mag_3d is good? - - if (_control_status.flags.mag_3D && !_control_status_prev.flags.mag_3D) { - ECL_INFO("starting mag 3D fusion"); - - } else if (!_control_status.flags.mag_3D && _control_status_prev.flags.mag_3D) { - ECL_INFO("stopping mag 3D fusion"); - } - - // if we are using 3-axis magnetometer fusion, but without external NE aiding, - // then the declination must be fused as an observation to prevent long term heading drift - // fusing declination when gps aiding is available is optional. - const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; - _control_status.flags.mag_dec = (_control_status.flags.mag && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight)); - - if (_control_status.flags.mag) { - aid_src.timestamp_sample = mag_sample.time_us; - - if (continuing_conditions_passing && _control_status.flags.yaw_align) { - - if (mag_sample.reset || checkHaglYawResetReq() || wmm_updated) { - ECL_INFO("reset to %s", AID_SRC_NAME); - resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); - aid_src.time_last_fuse = _time_delayed_us; - - } else { - if (!_mag_decl_cov_reset) { - // After any magnetic field covariance reset event the earth field state - // covariances need to be corrected to incorporate knowledge of the declination - // before fusing magnetometer data to prevent rapid rotation of the earth field - // states for the first few observations. - fuseDeclination(0.02f); - _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, aid_src, false); - - } else { - // The normal sequence is to fuse the magnetometer data first before fusing - // declination angle at a higher uncertainty to allow some learning of - // declination angle over time. - const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; - const bool update_tilt = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); - - if (_control_status.flags.mag_dec) { - fuseDeclination(0.5f); - } - } - } - - const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); - - if (is_fusion_failing) { - if (_nb_mag_3d_reset_available > 0) { - // Data seems good, attempt a reset (mag states only unless mag_3D currently active) - ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); - resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); - aid_src.time_last_fuse = _time_delayed_us; - - if (_control_status.flags.in_air) { - _nb_mag_3d_reset_available--; - } - - } else if (starting_conditions_passing) { - // Data seems good, but previous reset did not fix the issue - // something else must be wrong, declare the sensor faulty and stop the fusion - //_control_status.flags.mag_fault = true; - ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); - stopMagFusion(); - - } else { - // A reset did not fix the issue but all the starting checks are not passing - // This could be a temporary issue, stop the fusion without declaring the sensor faulty - ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); - stopMagFusion(); - } - } - - } else { - // Stop fusion but do not declare it faulty - ECL_DEBUG("stopping %s fusion, continuing conditions no longer passing", AID_SRC_NAME); - stopMagFusion(); - } - - } else { - if (starting_conditions_passing) { - - _control_status.flags.mag = true; - - // activate fusion, reset mag states and initialize variance if first init or in flight reset - if (!_control_status.flags.yaw_align - || wmm_updated - || !_mag_decl_cov_reset - || !_state.mag_I.longerThan(0.f) - || (getStateVariance().min() < kMagVarianceMin) - || (getStateVariance().min() < kMagVarianceMin) - ) { - ECL_INFO("starting %s fusion, resetting states", AID_SRC_NAME); - - bool reset_heading = !_control_status.flags.yaw_align; - - resetMagStates(_mag_lpf.getState(), reset_heading); - - if (reset_heading) { - _control_status.flags.yaw_align = true; - } - - } else { - ECL_INFO("starting %s fusion", AID_SRC_NAME); - fuseMag(mag_sample.mag, aid_src, false); - } - - aid_src.time_last_fuse = _time_delayed_us; - - _nb_mag_3d_reset_available = 2; - } - } -} - -void Ekf::stopMagFusion() -{ - if (_control_status.flags.mag) { - ECL_INFO("stopping mag fusion"); - - _control_status.flags.mag = false; - _control_status.flags.mag_dec = false; - - if (_control_status.flags.mag_3D) { - ECL_INFO("stopping mag 3D fusion"); - _control_status.flags.mag_3D = false; - } - - if (_control_status.flags.mag_hdg) { - ECL_INFO("stopping mag heading fusion"); - _control_status.flags.mag_hdg = false; - _fault_status.flags.bad_hdg = false; - } - - _fault_status.flags.bad_mag_x = false; - _fault_status.flags.bad_mag_y = false; - _fault_status.flags.bad_mag_z = false; - - _fault_status.flags.bad_mag_decl = false; - } -} 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 5497d427f49f..936d141eb054 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -41,6 +41,9 @@ void Ekf::controlMagFusion() { + static constexpr const char *AID_SRC_NAME = "mag"; + estimator_aid_source3d_s &aid_src = _aid_src_mag; + // reset the flight alignment flag so that the mag fields will be // re-initialised next time we achieve flight altitude if (!_control_status_prev.flags.in_air && _control_status.flags.in_air) { @@ -65,8 +68,10 @@ void Ekf::controlMagFusion() if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) { + resetEstimatorAidStatus(aid_src); + if (mag_sample.reset || (_mag_counter == 0)) { - // sensor or calibration has changed, reset low pass filter (reset handled by controlMag3DFusion/controlMagHeadingFusion) + // sensor or calibration has changed, reset low pass filter _control_status.flags.mag_fault = false; _state.mag_B.zero(); @@ -80,13 +85,6 @@ void Ekf::controlMagFusion() _mag_counter++; } - const bool starting_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) - && checkMagField(mag_sample.mag) - && (_mag_counter > 5) // wait until we have more than a few samples through the filter - && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame - && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset - && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); - // 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) @@ -103,8 +101,166 @@ void Ekf::controlMagFusion() _control_status.flags.synthetic_mag_z = false; } + // determine if we should use mag fusion + bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) + && _control_status.flags.tilt_align + && (_control_status.flags.yaw_align || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && mag_sample.mag.longerThan(0.f) + && mag_sample.mag.isAllFinite(); + + const bool starting_conditions_passing = continuing_conditions_passing + && checkMagField(mag_sample.mag) + && (_mag_counter > 5) // wait until we have more than a few samples through the filter + && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame + && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset + && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); + + checkMagHeadingConsistency(mag_sample); - controlMag3DFusion(mag_sample, starting_conditions_passing, _aid_src_mag); + + // 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); + + + // For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise + // before they are used to constrain heading drift + _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) + && _control_status.flags.mag + && _control_status.flags.mag_aligned_in_flight + && (_control_status.flags.mag_heading_consistent || !_control_status.flags.gps) + && !_control_status.flags.mag_fault + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; + + _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) + || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) + && _control_status.flags.tilt_align + && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && !_control_status.flags.mag_fault + && !_control_status.flags.mag_field_disturbed + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + // TODO: allow clearing mag_fault if mag_3d is good? + + if (_control_status.flags.mag_3D && !_control_status_prev.flags.mag_3D) { + ECL_INFO("starting mag 3D fusion"); + + } else if (!_control_status.flags.mag_3D && _control_status_prev.flags.mag_3D) { + ECL_INFO("stopping mag 3D fusion"); + } + + // if we are using 3-axis magnetometer fusion, but without external NE aiding, + // then the declination must be fused as an observation to prevent long term heading drift + // fusing declination when gps aiding is available is optional. + const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; + _control_status.flags.mag_dec = _control_status.flags.mag + && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight); + + if (_control_status.flags.mag) { + aid_src.timestamp_sample = mag_sample.time_us; + + if (continuing_conditions_passing && _control_status.flags.yaw_align) { + + if (mag_sample.reset || checkHaglYawResetReq() || wmm_updated) { + ECL_INFO("reset to %s", AID_SRC_NAME); + resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); + aid_src.time_last_fuse = _time_delayed_us; + + } else { + if (!_mag_decl_cov_reset) { + // After any magnetic field covariance reset event the earth field state + // covariances need to be corrected to incorporate knowledge of the declination + // before fusing magnetometer data to prevent rapid rotation of the earth field + // states for the first few observations. + fuseDeclination(0.02f); + _mag_decl_cov_reset = true; + fuseMag(mag_sample.mag, aid_src, false); + + } else { + // The normal sequence is to fuse the magnetometer data first before fusing + // declination angle at a higher uncertainty to allow some learning of + // declination angle over time. + const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; + const bool update_tilt = _control_status.flags.mag_3D; + fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); + + if (_control_status.flags.mag_dec) { + fuseDeclination(0.5f); + } + } + } + + const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); + + if (is_fusion_failing) { + if (_nb_mag_3d_reset_available > 0) { + // Data seems good, attempt a reset (mag states only unless mag_3D currently active) + ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); + resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); + aid_src.time_last_fuse = _time_delayed_us; + + if (_control_status.flags.in_air) { + _nb_mag_3d_reset_available--; + } + + } else if (starting_conditions_passing) { + // Data seems good, but previous reset did not fix the issue + // something else must be wrong, declare the sensor faulty and stop the fusion + //_control_status.flags.mag_fault = true; + ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); + stopMagFusion(); + + } else { + // A reset did not fix the issue but all the starting checks are not passing + // This could be a temporary issue, stop the fusion without declaring the sensor faulty + ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); + stopMagFusion(); + } + } + + } else { + // Stop fusion but do not declare it faulty + ECL_DEBUG("stopping %s fusion, continuing conditions no longer passing", AID_SRC_NAME); + stopMagFusion(); + } + + } else { + if (starting_conditions_passing) { + + _control_status.flags.mag = true; + + // activate fusion, reset mag states and initialize variance if first init or in flight reset + if (!_control_status.flags.yaw_align + || wmm_updated + || !_mag_decl_cov_reset + || !_state.mag_I.longerThan(0.f) + || (getStateVariance().min() < kMagVarianceMin) + || (getStateVariance().min() < kMagVarianceMin) + ) { + ECL_INFO("starting %s fusion, resetting states", AID_SRC_NAME); + + bool reset_heading = !_control_status.flags.yaw_align; + + resetMagStates(_mag_lpf.getState(), reset_heading); + + if (reset_heading) { + _control_status.flags.yaw_align = true; + } + + } else { + ECL_INFO("starting %s fusion", AID_SRC_NAME); + fuseMag(mag_sample.mag, aid_src, false); + } + + aid_src.time_last_fuse = _time_delayed_us; + + _nb_mag_3d_reset_available = 2; + } + } } else if (!isNewestSampleRecent(_time_last_mag_buffer_push, 2 * MAG_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. @@ -112,9 +268,37 @@ void Ekf::controlMagFusion() } } +void Ekf::stopMagFusion() +{ + if (_control_status.flags.mag) { + ECL_INFO("stopping mag fusion"); + + _control_status.flags.mag = false; + _control_status.flags.mag_dec = false; + + if (_control_status.flags.mag_3D) { + ECL_INFO("stopping mag 3D fusion"); + _control_status.flags.mag_3D = false; + } + + if (_control_status.flags.mag_hdg) { + ECL_INFO("stopping mag heading fusion"); + _control_status.flags.mag_hdg = false; + _fault_status.flags.bad_hdg = false; + } + + _fault_status.flags.bad_mag_x = false; + _fault_status.flags.bad_mag_y = false; + _fault_status.flags.bad_mag_z = false; + + _fault_status.flags.bad_mag_decl = false; + } +} + bool Ekf::checkHaglYawResetReq() const { #if defined(CONFIG_EKF2_TERRAIN) + // We need to reset the yaw angle after climbing away from the ground to enable // recovery from ground level magnetic interference. if (_control_status.flags.in_air && _control_status.flags.yaw_align && !_control_status.flags.mag_aligned_in_flight) { @@ -124,6 +308,7 @@ bool Ekf::checkHaglYawResetReq() const const bool above_mag_anomalies = (getTerrainVPos() - _state.pos(2)) > mag_anomalies_max_hagl; return above_mag_anomalies; } + #endif // CONFIG_EKF2_TERRAIN return false; @@ -147,6 +332,7 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) // mag_B: reset #if defined(CONFIG_EKF2_GNSS) + if (isYawEmergencyEstimateAvailable()) { const Dcmf R_to_earth = updateYawInRotMat(_yawEstimator.getYaw(), _R_to_earth); @@ -159,6 +345,7 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) } else if (!reset_heading && _control_status.flags.yaw_align) { #else + if (!reset_heading && _control_status.flags.yaw_align) { #endif // mag_B: reset using WMM diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 77ddfc721422..91b4682d8262 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -1025,7 +1025,6 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // control fusion of magnetometer observations void controlMagFusion(); - void controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source3d_s &aid_src); bool checkHaglYawResetReq() const; From bfc39cf3419aaf2b6cc21ae2b44d2f866866cbb5 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 29 Apr 2024 12:15:19 -0400 Subject: [PATCH 232/652] ekf2: mag control always populate estimator aid src --- .../aid_sources/magnetometer/mag_control.cpp | 44 +++++-- .../aid_sources/magnetometer/mag_fusion.cpp | 119 +++++------------- src/modules/ekf2/EKF/ekf.h | 2 +- 3 files changed, 71 insertions(+), 94 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 936d141eb054..f6da31311229 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 + void Ekf::controlMagFusion() { static constexpr const char *AID_SRC_NAME = "mag"; @@ -68,8 +70,6 @@ void Ekf::controlMagFusion() if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) { - resetEstimatorAidStatus(aid_src); - if (mag_sample.reset || (_mag_counter == 0)) { // sensor or calibration has changed, reset low pass filter _control_status.flags.mag_fault = false; @@ -101,6 +101,37 @@ void Ekf::controlMagFusion() _control_status.flags.synthetic_mag_z = false; } + + resetEstimatorAidStatus(aid_src); + aid_src.timestamp_sample = mag_sample.time_us; + + // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations + const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); + + // calculate intermediate variables used for X axis innovation variance, observation Jacobians and Kalman gains + Vector3f mag_innov; + Vector3f innov_var; + + // Observation jacobian and Kalman gain vectors + VectorState H; + sym::ComputeMagInnovInnovVarAndHx(_state.vector(), P, mag_sample.mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); + + // do not use the synthesized measurement for the magnetomter Z component for 3D fusion + if (_control_status.flags.synthetic_mag_z) { + mag_innov(2) = 0.0f; + } + + for (int i = 0; i < 3; i++) { + aid_src.observation[i] = mag_sample.mag(i); + aid_src.observation_variance[i] = R_MAG; + aid_src.innovation[i] = mag_innov(i); + aid_src.innovation_variance[i] = innov_var(i); + } + + const float innov_gate = math::max(_params.mag_innov_gate, 1.f); + setEstimatorAidStatusTestRatio(aid_src, innov_gate); + + // determine if we should use mag fusion bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) && _control_status.flags.tilt_align @@ -136,7 +167,7 @@ void Ekf::controlMagFusion() _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) - && _control_status.flags.tilt_align + && _control_status.flags.mag && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) && !_control_status.flags.mag_fault @@ -161,7 +192,6 @@ void Ekf::controlMagFusion() && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight); if (_control_status.flags.mag) { - aid_src.timestamp_sample = mag_sample.time_us; if (continuing_conditions_passing && _control_status.flags.yaw_align) { @@ -178,7 +208,7 @@ void Ekf::controlMagFusion() // states for the first few observations. fuseDeclination(0.02f); _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, aid_src, false); + fuseMag(mag_sample.mag, H, aid_src, false); } else { // The normal sequence is to fuse the magnetometer data first before fusing @@ -186,7 +216,7 @@ void Ekf::controlMagFusion() // declination angle over time. const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; const bool update_tilt = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); + fuseMag(mag_sample.mag, H, aid_src, update_all_states, update_tilt); if (_control_status.flags.mag_dec) { fuseDeclination(0.5f); @@ -253,7 +283,7 @@ void Ekf::controlMagFusion() } else { ECL_INFO("starting %s fusion", AID_SRC_NAME); - fuseMag(mag_sample.mag, aid_src, false); + fuseMag(mag_sample.mag, H, aid_src, false); } aid_src.time_last_fuse = _time_delayed_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 1dbff8874c0f..0b79edb77fd2 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -43,7 +43,6 @@ #include "ekf.h" -#include #include #include @@ -51,39 +50,17 @@ #include -bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states, bool update_tilt) +bool Ekf::fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt) { // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); - // calculate intermediate variables used for X axis innovation variance, observation Jacobians and Kalman gains - Vector3f mag_innov; - Vector3f innov_var; - - // Observation jacobian and Kalman gain vectors - VectorState H; const auto state_vector = _state.vector(); - sym::ComputeMagInnovInnovVarAndHx(state_vector, P, mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); - - // do not use the synthesized measurement for the magnetomter Z component for 3D fusion - if (_control_status.flags.synthetic_mag_z) { - mag_innov(2) = 0.0f; - } - - for (int i = 0; i < 3; i++) { - aid_src_mag.observation[i] = mag(i) - _state.mag_B(i); - aid_src_mag.observation_variance[i] = R_MAG; - aid_src_mag.innovation[i] = mag_innov(i); - aid_src_mag.innovation_variance[i] = innov_var(i); - } - - const float innov_gate = math::max(_params.mag_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(aid_src_mag, innov_gate); if (update_all_states) { - _fault_status.flags.bad_mag_x = (aid_src_mag.innovation_variance[0] < aid_src_mag.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src_mag.innovation_variance[1] < aid_src_mag.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src_mag.innovation_variance[2] < aid_src_mag.observation_variance[2]); + _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); } else { _fault_status.flags.bad_mag_x = false; @@ -92,28 +69,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } // Perform an innovation consistency check and report the result - _innov_check_fail_status.flags.reject_mag_x = (aid_src_mag.test_ratio[0] > 1.f); - _innov_check_fail_status.flags.reject_mag_y = (aid_src_mag.test_ratio[1] > 1.f); - _innov_check_fail_status.flags.reject_mag_z = (aid_src_mag.test_ratio[2] > 1.f); - - const char *numerical_error_covariance_reset_string = "numerical error - covariance reset"; - - // check innovation variances for being badly conditioned - if (innov_var.min() < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - // we need to re-initialise covariances and abort this fusion step - if (update_all_states) { - resetQuatCov(_params.mag_heading_noise); - } - - resetMagCov(); - - ECL_ERR("mag %s", numerical_error_covariance_reset_string); - return false; - } + _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); + _innov_check_fail_status.flags.reject_mag_y = (aid_src.test_ratio[1] > 1.f); + _innov_check_fail_status.flags.reject_mag_z = (aid_src.test_ratio[2] > 1.f); // if any axis fails, abort the mag fusion - if (aid_src_mag.innovation_rejected) { + if (aid_src.innovation_rejected) { return false; } @@ -127,25 +88,10 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); + sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); - - if (aid_src_mag.innovation_variance[index] < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - _fault_status.flags.bad_mag_y = true; - - // we need to re-initialise covariances and abort this fusion step - if (update_all_states) { - resetQuatCov(_params.mag_heading_noise); - } - - resetMagCov(); - - ECL_ERR("magY %s", numerical_error_covariance_reset_string); - return false; - } + aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); } else if (index == 2) { // we do not fuse synthesized magnetomter measurements when doing 3D fusion @@ -155,28 +101,33 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); + sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); - - if (aid_src_mag.innovation_variance[index] < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - _fault_status.flags.bad_mag_z = true; + aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); + } - // we need to re-initialise covariances and abort this fusion step - if (update_all_states) { - resetQuatCov(_params.mag_heading_noise); - } + if (aid_src.innovation_variance[index] < R_MAG) { + // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned + if (update_all_states) { + _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); + } - resetMagCov(); + ECL_ERR("mag numerical error covariance reset"); - ECL_ERR("magZ %s", numerical_error_covariance_reset_string); - return false; + // we need to re-initialise covariances and abort this fusion step + if (update_all_states) { + resetQuatCov(_params.mag_heading_noise); } + + resetMagCov(); + + return false; } - VectorState Kfusion = P * H / aid_src_mag.innovation_variance[index]; + VectorState Kfusion = P * H / aid_src.innovation_variance[index]; if (!update_all_states) { // zero non-mag Kalman gains if not updating all states @@ -192,16 +143,13 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } if (!update_tilt) { - Kfusion(State::quat_nominal.idx) = 0.f; + Kfusion(State::quat_nominal.idx + 0) = 0.f; Kfusion(State::quat_nominal.idx + 1) = 0.f; } - if (measurementUpdate(Kfusion, H, aid_src_mag.observation_variance[index], aid_src_mag.innovation[index])) { + if (measurementUpdate(Kfusion, H, aid_src.observation_variance[index], aid_src.innovation[index])) { fused[index] = true; limitDeclination(); - - } else { - fused[index] = false; } } @@ -212,8 +160,8 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } if (fused[0] && fused[1] && fused[2]) { - aid_src_mag.fused = true; - aid_src_mag.time_last_fuse = _time_delayed_us; + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; if (update_all_states) { _time_last_heading_fuse = _time_delayed_us; @@ -222,7 +170,6 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo return true; } - aid_src_mag.fused = false; return false; } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 91b4682d8262..b326382d83a1 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -758,7 +758,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // ekf sequential fusion of magnetometer measurements - bool fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = true, bool update_tilt = true); + bool fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = true, bool update_tilt = true); // fuse magnetometer declination measurement // argument passed in is the declination uncertainty in radians From 5173830718f0a2a337263f786a0e0c63a1135e71 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 29 Apr 2024 12:47:55 -0400 Subject: [PATCH 233/652] ekf2: mag fusion don't update all states or tilt by default - cleanup some of the legacy mag flags --- .../aid_sources/magnetometer/mag_control.cpp | 32 ++++++++++++----- .../aid_sources/magnetometer/mag_fusion.cpp | 36 +++---------------- src/modules/ekf2/EKF/ekf.h | 2 +- 3 files changed, 30 insertions(+), 40 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 f6da31311229..a919032d8f12 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -101,6 +101,11 @@ void Ekf::controlMagFusion() _control_status.flags.synthetic_mag_z = false; } + // reset flags + _fault_status.flags.bad_mag_x = false; + _fault_status.flags.bad_mag_y = false; + _fault_status.flags.bad_mag_z = false; + resetEstimatorAidStatus(aid_src); aid_src.timestamp_sample = mag_sample.time_us; @@ -131,6 +136,10 @@ void Ekf::controlMagFusion() const float innov_gate = math::max(_params.mag_innov_gate, 1.f); setEstimatorAidStatusTestRatio(aid_src, innov_gate); + // Perform an innovation consistency check and report the result + _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); + _innov_check_fail_status.flags.reject_mag_y = (aid_src.test_ratio[1] > 1.f); + _innov_check_fail_status.flags.reject_mag_z = (aid_src.test_ratio[2] > 1.f); // determine if we should use mag fusion bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) @@ -208,7 +217,7 @@ void Ekf::controlMagFusion() // states for the first few observations. fuseDeclination(0.02f); _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, H, aid_src, false); + fuseMag(mag_sample.mag, R_MAG, H, aid_src); } else { // The normal sequence is to fuse the magnetometer data first before fusing @@ -216,7 +225,14 @@ void Ekf::controlMagFusion() // declination angle over time. const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; const bool update_tilt = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, H, aid_src, update_all_states, update_tilt); + fuseMag(mag_sample.mag, R_MAG, H, aid_src, update_all_states, update_tilt); + + // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned + if (update_all_states && update_tilt) { + _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); + } if (_control_status.flags.mag_dec) { fuseDeclination(0.5f); @@ -276,19 +292,19 @@ void Ekf::controlMagFusion() bool reset_heading = !_control_status.flags.yaw_align; resetMagStates(_mag_lpf.getState(), reset_heading); + aid_src.time_last_fuse = _time_delayed_us; + _nb_mag_3d_reset_available = 2; if (reset_heading) { _control_status.flags.yaw_align = true; } } else { - ECL_INFO("starting %s fusion", AID_SRC_NAME); - fuseMag(mag_sample.mag, H, aid_src, false); + if (fuseMag(mag_sample.mag, R_MAG, H, aid_src)) { + ECL_INFO("starting %s fusion", AID_SRC_NAME); + _nb_mag_3d_reset_available = 2; + } } - - aid_src.time_last_fuse = _time_delayed_us; - - _nb_mag_3d_reset_available = 2; } } 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 0b79edb77fd2..ad03b8533147 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -50,41 +50,22 @@ #include -bool Ekf::fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt) +bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt) { - // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations - const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); - - const auto state_vector = _state.vector(); - - if (update_all_states) { - _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); - - } else { - _fault_status.flags.bad_mag_x = false; - _fault_status.flags.bad_mag_y = false; - _fault_status.flags.bad_mag_z = false; - } - - // Perform an innovation consistency check and report the result - _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); - _innov_check_fail_status.flags.reject_mag_y = (aid_src.test_ratio[1] > 1.f); - _innov_check_fail_status.flags.reject_mag_z = (aid_src.test_ratio[2] > 1.f); - - // if any axis fails, abort the mag fusion + // if any axis failed, abort the mag fusion if (aid_src.innovation_rejected) { return false; } + const auto state_vector = _state.vector(); + bool fused[3] {false, false, false}; // update the states and covariance using sequential fusion of the magnetometer components for (uint8_t index = 0; index <= 2; index++) { // Calculate Kalman gains and observation jacobians if (index == 0) { - // everything was already computed above + // everything was already computed } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) @@ -108,13 +89,6 @@ bool Ekf::fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s } if (aid_src.innovation_variance[index] < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - if (update_all_states) { - _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); - } - ECL_ERR("mag numerical error covariance reset"); // we need to re-initialise covariances and abort this fusion step diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index b326382d83a1..95add3dec9ce 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -758,7 +758,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // ekf sequential fusion of magnetometer measurements - bool fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = true, bool update_tilt = true); + bool fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = false, bool update_tilt = false); // fuse magnetometer declination measurement // argument passed in is the declination uncertainty in radians From bb5dfc7d519fa4259253a2d46c4a66936e63a571 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 30 Apr 2024 10:12:58 -0400 Subject: [PATCH 234/652] integrationtests: mavros/mission_test.py bump yaw_error_std threshold (heading init is delayed, but not wrong) --- integrationtests/python_src/px4_it/mavros/mission_test.py | 2 +- src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/integrationtests/python_src/px4_it/mavros/mission_test.py b/integrationtests/python_src/px4_it/mavros/mission_test.py index 8d7f6e647828..a9dccf728430 100755 --- a/integrationtests/python_src/px4_it/mavros/mission_test.py +++ b/integrationtests/python_src/px4_it/mavros/mission_test.py @@ -308,7 +308,7 @@ def test_mission(self): self.assertTrue(res['pitch_error_std'] < 5.0, str(res)) # TODO: fix by excluding initial heading init and reset preflight - self.assertTrue(res['yaw_error_std'] < 10.0, str(res)) + self.assertTrue(res['yaw_error_std'] < 13.0, str(res)) if __name__ == '__main__': 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 a919032d8f12..5bf99650402c 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -150,7 +150,7 @@ void Ekf::controlMagFusion() const bool starting_conditions_passing = continuing_conditions_passing && checkMagField(mag_sample.mag) - && (_mag_counter > 5) // wait until we have more than a few samples through the filter + && (_mag_counter > 3) // wait until we have more than a few samples through the filter && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); From d7960093024a31db0c97730a4fa26bb974464e7e Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 16:32:22 +0200 Subject: [PATCH 235/652] mag_ctrl: do not fuse synthetic mag but do not zero the innovation --- .../ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 5 ----- 1 file changed, 5 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 5bf99650402c..90ed1f670458 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -121,11 +121,6 @@ void Ekf::controlMagFusion() VectorState H; sym::ComputeMagInnovInnovVarAndHx(_state.vector(), P, mag_sample.mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); - // do not use the synthesized measurement for the magnetomter Z component for 3D fusion - if (_control_status.flags.synthetic_mag_z) { - mag_innov(2) = 0.0f; - } - for (int i = 0; i < 3; i++) { aid_src.observation[i] = mag_sample.mag(i); aid_src.observation_variance[i] = R_MAG; From ea39032b45daaa5155df159f672c189aa627f8cc Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 16:33:38 +0200 Subject: [PATCH 236/652] mag_ctrl: combine common conditions for mag_hdg and mag_3d --- .../aid_sources/magnetometer/mag_control.cpp | 39 ++++++++----------- 1 file changed, 17 insertions(+), 22 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 90ed1f670458..1601178cd296 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -150,34 +150,29 @@ void Ekf::controlMagFusion() && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); - 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); - - // For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise - // before they are used to constrain heading drift - _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) - && _control_status.flags.mag - && _control_status.flags.mag_aligned_in_flight - && (_control_status.flags.mag_heading_consistent || !_control_status.flags.gps) - && !_control_status.flags.mag_fault - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; - + { const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; - - _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) - || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) - && _control_status.flags.mag - && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) - || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && !_control_status.flags.mag_fault - && !_control_status.flags.mag_field_disturbed - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; + const bool common_conditions_passing = _control_status.flags.mag + && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && !_control_status.flags.mag_fault + && !_control_status.flags.mag_field_disturbed + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + _control_status.flags.mag_3D = common_conditions_passing + && (_params.mag_fusion_type == MagFuseType::AUTO) + && _control_status.flags.mag_aligned_in_flight; + + _control_status.flags.mag_hdg = common_conditions_passing + && ((_params.mag_fusion_type == MagFuseType::HEADING) + || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)); + } // TODO: allow clearing mag_fault if mag_3d is good? From d359f6236e483bea635b76c45560160bcfe0abbf Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 17 May 2024 05:20:30 -0400 Subject: [PATCH 237/652] ekf2: symforce zero more efficiently (#23133) - increase symforce CppConfig zero_initialization_sparsity_threshold so that a Matrix setZero() call is performed instead of individually zeroing Co-authored-by: bresch --- .../generated/predict_covariance.h | 255 +----------------- .../ekf_derivation/utils/derivation_utils.py | 2 +- .../ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp | 3 +- .../derivation/derivation_yaw_estimator.py | 2 +- .../yaw_est_compute_measurement_update.h | 5 +- .../generated/yaw_est_predict_covariance.h | 35 ++- 6 files changed, 24 insertions(+), 278 deletions(-) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h index 5fa0ad1772d1..1ff79d8c7e61 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h @@ -236,57 +236,16 @@ matrix::Matrix PredictCovariance(const matrix::Matrix _res; + _res.setZero(); + _res(0, 0) = std::pow(_tmp15, Scalar(2)) * gyro_var + _tmp15 * _tmp27 + _tmp18 * _tmp26 + std::pow(_tmp23, Scalar(2)) * gyro_var + _tmp23 * _tmp25 + _tmp24 * _tmp6 + std::pow(_tmp6, Scalar(2)) * gyro_var; - _res(1, 0) = 0; - _res(2, 0) = 0; - _res(3, 0) = 0; - _res(4, 0) = 0; - _res(5, 0) = 0; - _res(6, 0) = 0; - _res(7, 0) = 0; - _res(8, 0) = 0; - _res(9, 0) = 0; - _res(10, 0) = 0; - _res(11, 0) = 0; - _res(12, 0) = 0; - _res(13, 0) = 0; - _res(14, 0) = 0; - _res(15, 0) = 0; - _res(16, 0) = 0; - _res(17, 0) = 0; - _res(18, 0) = 0; - _res(19, 0) = 0; - _res(20, 0) = 0; - _res(21, 0) = 0; - _res(22, 0) = 0; _res(0, 1) = _tmp15 * _tmp38 + _tmp18 * _tmp35 + _tmp24 * _tmp34 + _tmp25 * _tmp29 + _tmp27 * _tmp36 + _tmp29 * _tmp37 + _tmp34 * _tmp39; _res(1, 1) = _tmp18 * _tmp43 + std::pow(_tmp29, Scalar(2)) * gyro_var + _tmp29 * _tmp40 + std::pow(_tmp34, Scalar(2)) * gyro_var + _tmp34 * _tmp41 + std::pow(_tmp36, Scalar(2)) * gyro_var + _tmp36 * _tmp42; - _res(2, 1) = 0; - _res(3, 1) = 0; - _res(4, 1) = 0; - _res(5, 1) = 0; - _res(6, 1) = 0; - _res(7, 1) = 0; - _res(8, 1) = 0; - _res(9, 1) = 0; - _res(10, 1) = 0; - _res(11, 1) = 0; - _res(12, 1) = 0; - _res(13, 1) = 0; - _res(14, 1) = 0; - _res(15, 1) = 0; - _res(16, 1) = 0; - _res(17, 1) = 0; - _res(18, 1) = 0; - _res(19, 1) = 0; - _res(20, 1) = 0; - _res(21, 1) = 0; - _res(22, 1) = 0; _res(0, 2) = _tmp15 * _tmp47 * gyro_var + _tmp18 * _tmp46 + _tmp24 * _tmp44 + _tmp25 * _tmp45 + _tmp27 * _tmp47 + _tmp37 * _tmp45 + _tmp39 * _tmp44; _res(1, 2) = _tmp18 * _tmp48 + _tmp29 * _tmp45 * gyro_var + _tmp34 * _tmp44 * gyro_var + @@ -294,26 +253,6 @@ matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix& P, const if (P_new != nullptr) { matrix::Matrix& _p_new = (*P_new); + _p_new.setZero(); + _p_new(0, 0) = -P(0, 0) * _tmp9 + P(0, 0) - P(1, 0) * _tmp12; - _p_new(1, 0) = 0; - _p_new(2, 0) = 0; _p_new(0, 1) = -P(0, 1) * _tmp9 + P(0, 1) - P(1, 1) * _tmp12; _p_new(1, 1) = -P(0, 1) * _tmp10 - P(1, 1) * _tmp13 + P(1, 1); - _p_new(2, 1) = 0; _p_new(0, 2) = -P(0, 2) * _tmp9 + P(0, 2) - P(1, 2) * _tmp12; _p_new(1, 2) = -P(0, 2) * _tmp10 - P(1, 2) * _tmp13 + P(1, 2); _p_new(2, 2) = -P(0, 2) * _tmp11 - P(1, 2) * _tmp14 + P(2, 2); diff --git a/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h b/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h index 5d2c4327a55a..d3fefb61d848 100644 --- a/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h +++ b/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h @@ -24,14 +24,14 @@ namespace sym { * d_ang_var: Scalar * * Outputs: - * P_new: Matrix33 + * res: Matrix33 */ template -void YawEstPredictCovariance(const matrix::Matrix& state, - const matrix::Matrix& P, - const matrix::Matrix& d_vel, const Scalar d_vel_var, - const Scalar d_ang, const Scalar d_ang_var, - matrix::Matrix* const P_new = nullptr) { +matrix::Matrix YawEstPredictCovariance(const matrix::Matrix& state, + const matrix::Matrix& P, + const matrix::Matrix& d_vel, + const Scalar d_vel_var, const Scalar d_ang, + const Scalar d_ang_var) { // Total ops: 39 // Input arrays @@ -48,19 +48,18 @@ void YawEstPredictCovariance(const matrix::Matrix& state, const Scalar _tmp7 = std::pow(d_ang, Scalar(2)) + 1; // Output terms (1) - if (P_new != nullptr) { - matrix::Matrix& _p_new = (*P_new); + matrix::Matrix _res; - _p_new(0, 0) = P(0, 0) + P(2, 0) * _tmp2 + _tmp2 * _tmp3 + _tmp4; - _p_new(1, 0) = 0; - _p_new(2, 0) = 0; - _p_new(0, 1) = P(0, 1) + P(2, 1) * _tmp2 + _tmp3 * _tmp5; - _p_new(1, 1) = P(1, 1) + P(2, 1) * _tmp5 + _tmp4 + _tmp5 * _tmp6; - _p_new(2, 1) = 0; - _p_new(0, 2) = _tmp3 * _tmp7; - _p_new(1, 2) = _tmp6 * _tmp7; - _p_new(2, 2) = P(2, 2) * std::pow(_tmp7, Scalar(2)) + d_ang_var; - } + _res.setZero(); + + _res(0, 0) = P(0, 0) + P(2, 0) * _tmp2 + _tmp2 * _tmp3 + _tmp4; + _res(0, 1) = P(0, 1) + P(2, 1) * _tmp2 + _tmp3 * _tmp5; + _res(1, 1) = P(1, 1) + P(2, 1) * _tmp5 + _tmp4 + _tmp5 * _tmp6; + _res(0, 2) = _tmp3 * _tmp7; + _res(1, 2) = _tmp6 * _tmp7; + _res(2, 2) = P(2, 2) * std::pow(_tmp7, Scalar(2)) + d_ang_var; + + return _res; } // NOLINT(readability/fn_size) // NOLINTNEXTLINE(readability/fn_size) From 470bea9ba84ac6202a707b263bbc2ddee4305b93 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 17 May 2024 14:30:14 +0200 Subject: [PATCH 238/652] Update NuttX Fixes imxrt1170 mpu config for extra checks --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 4be592dd2114..0f401a606265 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 4be592dd2114d2c07505b143493a3cfa6dc9c239 +Subproject commit 0f401a6062653795b6355c420ea8b0e72578c204 From ebfa53286f10776308971424402e9bbb5cca3b42 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 17 May 2024 12:00:55 +0200 Subject: [PATCH 239/652] dronecan: SocketCAN driver check size before copying Avoids memory corruption if we get packets to big --- .../uavcan_drivers/socketcan/driver/src/socketcan.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp b/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp index b3a8ce183625..8df5c21b5e12 100644 --- a/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp +++ b/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp @@ -218,12 +218,22 @@ uavcan::int16_t CanIface::receive(uavcan::CanFrame &out_frame, uavcan::Monotonic if (_can_fd) { struct canfd_frame *recv_frame = (struct canfd_frame *)&_recv_frame; out_frame.id = recv_frame->can_id; + + if (recv_frame->len > CANFD_MAX_DLEN) { + return -EFAULT; + } + out_frame.dlc = recv_frame->len; memcpy(out_frame.data, &recv_frame->data, recv_frame->len); } else { struct can_frame *recv_frame = (struct can_frame *)&_recv_frame; out_frame.id = recv_frame->can_id; + + if (recv_frame->can_dlc > CAN_MAX_DLEN) { + return -EFAULT; + } + out_frame.dlc = recv_frame->can_dlc; memcpy(out_frame.data, &recv_frame->data, recv_frame->can_dlc); } From 6b0ac49daf5c49aeb625ed684359fdd59b1a287d Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 17 May 2024 14:27:40 +0200 Subject: [PATCH 240/652] hardfault_log: Add jump to 0x0 & write 0x0 faults --- src/systemcmds/hardfault_log/hardfault_log.c | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/src/systemcmds/hardfault_log/hardfault_log.c b/src/systemcmds/hardfault_log/hardfault_log.c index 0978fc653601..f8ff269ec6b8 100644 --- a/src/systemcmds/hardfault_log/hardfault_log.c +++ b/src/systemcmds/hardfault_log/hardfault_log.c @@ -141,6 +141,21 @@ static int genfault(int fault) /* This is not going to happen */ break; + case 2: + asm("BX %0" : : "r"(0x0)); + /* This is not going to happen */ + break; + + case 3: { + char buffer[128] = {0}; + void *dest = (void *)0x0; + + memcpy(dest, &buffer, 128); + /* This is not going to happen */ + } + break; + + default: break; @@ -1270,7 +1285,8 @@ static void print_usage(void) PRINT_MODULE_USAGE_COMMAND_DESCR("rearm", "Drop an uncommitted hardfault"); PRINT_MODULE_USAGE_COMMAND_DESCR("fault", "Generate a hardfault (this command crashes the system :)"); - PRINT_MODULE_USAGE_ARG("0|1", "Hardfault type: 0=divide by 0, 1=Assertion (default=0)", true); + PRINT_MODULE_USAGE_ARG("0|1|2|3", + "Hardfault type: 0=divide by 0, 1=Assertion, 2=jump to 0x0, 3=write to 0x0 (default=0)", true); PRINT_MODULE_USAGE_COMMAND_DESCR("commit", "Write uncommitted hardfault to /fs/microsd/fault_%i.txt (and rearm, but don't reset)"); From 70304fe7155a47132a4dc2a755a5a24358efb59a Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Mon, 20 May 2024 12:35:29 -0600 Subject: [PATCH 241/652] [mavlink] Parameter to always start on USB (#22234) * usb: Added parameter to enable always starting mavlink on USB. Refactored cdcacm_init into a module and added a paramter to allow always starting mavlink on USB, also added a paramter to choose the mode. The current default behavior is to wait and listen for data on USB and auto-detect the protocol (mavlink, nsh, ublox). This results in the mavlink stream not starting until something else on the mavlink network sends a packet first. The new default behavior is to always start mavlink. Added parameters MAV_USB_ENABLE -- default 1 (always start mavlink on USB) MAV_USE_MODE -- default 3 (onboard) * added 3 retries for opening serial port in mavlink, removed sleep before sercon * added DRIVERS_CDCACM_AUTOSTART to ark-v6x default.px4board * added CONFIG_DRIVERS_CDCACM_AUTOSTART=y to default.px4board for boards with CONFIG_CDCACM in their nsh/defconfig * format * remove PGA460 from COMMON_DISTANCE_SENSOR to save flash * remove LIS2MDL from COMMON_MAGNETOMETER to save flash * disable CONFIG_DRIVERS_CDCACM_AUTOSTART for fmu-v5 protected.px4board * moved and renamed parameters, removed mode logic in mavlink * changed parameter names, added mode none * remove parameters from mavlink --- ROMFS/px4fmu_common/init.d/rcS | 8 + boards/airmind/mindpx-v2/default.px4board | 1 + boards/ark/fmu-v6x/default.px4board | 2 + boards/atl/mantis-edu/default.px4board | 1 + boards/bitcraze/crazyflie/default.px4board | 1 + boards/bitcraze/crazyflie21/default.px4board | 1 + boards/cuav/nora/default.px4board | 1 + boards/cuav/x7pro/default.px4board | 1 + boards/cubepilot/cubeorange/default.px4board | 1 + .../cubepilot/cubeorangeplus/default.px4board | 1 + boards/cubepilot/cubeyellow/default.px4board | 1 + .../diatone/mamba-f405-mk2/default.px4board | 1 + boards/flywoo/gn-f405/default.px4board | 1 + boards/hkust/nxt-dual/default.px4board | 1 + boards/hkust/nxt-v1/default.px4board | 1 + boards/holybro/durandal-v1/default.px4board | 1 + boards/holybro/kakutef7/default.px4board | 1 + boards/holybro/kakuteh7/default.px4board | 1 + boards/holybro/kakuteh7mini/default.px4board | 1 + boards/holybro/kakuteh7v2/default.px4board | 1 + boards/holybro/pix32v5/default.px4board | 1 + boards/matek/h743-mini/default.px4board | 1 + boards/matek/h743-slim/default.px4board | 1 + boards/matek/h743/default.px4board | 1 + boards/modalai/fc-v1/default.px4board | 1 + boards/modalai/fc-v2/default.px4board | 1 + boards/mro/ctrl-zero-classic/default.px4board | 1 + boards/mro/ctrl-zero-f7-oem/default.px4board | 1 + boards/mro/ctrl-zero-f7/default.px4board | 1 + boards/mro/ctrl-zero-h7-oem/default.px4board | 1 + boards/mro/ctrl-zero-h7/default.px4board | 1 + boards/mro/pixracerpro/default.px4board | 1 + boards/mro/x21-777/default.px4board | 1 + boards/mro/x21/default.px4board | 1 + boards/nxp/fmuk66-e/default.px4board | 1 + boards/nxp/fmuk66-v3/default.px4board | 1 + boards/omnibus/f4sd/default.px4board | 1 + boards/px4/fmu-v2/default.px4board | 1 + boards/px4/fmu-v3/default.px4board | 1 + boards/px4/fmu-v4/default.px4board | 1 + boards/px4/fmu-v4pro/default.px4board | 1 + boards/px4/fmu-v5/default.px4board | 1 + boards/px4/fmu-v5/protected.px4board | 1 + boards/px4/fmu-v5x/default.px4board | 1 + boards/px4/fmu-v6c/default.px4board | 1 + boards/px4/fmu-v6u/default.px4board | 1 + boards/px4/fmu-v6x/default.px4board | 1 + boards/px4/fmu-v6xrt/default.px4board | 1 + boards/raspberrypi/pico/default.px4board | 1 + boards/siyi/n7/default.px4board | 1 + .../smartap-airlink/default.px4board | 1 + boards/spracing/h7extreme/default.px4board | 1 + boards/thepeach/k1/default.px4board | 1 + boards/thepeach/r1/default.px4board | 1 + boards/uvify/core/default.px4board | 1 + platforms/nuttx/src/px4/common/CMakeLists.txt | 1 - platforms/nuttx/src/px4/common/px4_init.cpp | 6 - .../nuttx/src/px4/common/px4_layer.cmake | 1 - .../src/px4/common/px4_protected_layers.cmake | 1 - .../src/px4/common/px4_userspace_init.cpp | 6 - src/drivers/cdcacm_autostart/CMakeLists.txt | 40 ++ src/drivers/cdcacm_autostart/Kconfig | 6 + .../cdcacm_autostart/cdcacm_autostart.cpp | 663 ++++++++++++++++++ .../cdcacm_autostart/cdcacm_autostart.h | 124 ++++ .../cdcacm_autostart_params.c | 68 ++ src/modules/mavlink/mavlink_main.cpp | 26 +- src/systemcmds/serial_passthru/Kconfig | 2 +- 67 files changed, 982 insertions(+), 25 deletions(-) create mode 100644 src/drivers/cdcacm_autostart/CMakeLists.txt create mode 100644 src/drivers/cdcacm_autostart/Kconfig create mode 100644 src/drivers/cdcacm_autostart/cdcacm_autostart.cpp create mode 100644 src/drivers/cdcacm_autostart/cdcacm_autostart.h create mode 100644 src/drivers/cdcacm_autostart/cdcacm_autostart_params.c diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index b9d46ce27dc7..c0b895a8fe8a 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -439,6 +439,14 @@ else # Must be started after the serial config is read rc_input start $RC_INPUT_ARGS + # Manages USB interface + if ! cdcacm_autostart start + then + sercon + echo "Starting MAVLink on /dev/ttyACM0" + mavlink start -d /dev/ttyACM0 + fi + # # Play the startup tune (if not disabled or there is an error) # diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board index cb56388c36fc..5f4bcd2b0cfd 100644 --- a/boards/airmind/mindpx-v2/default.px4board +++ b/boards/airmind/mindpx-v2/default.px4board @@ -12,6 +12,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 4018e493a2ad..1209adb9dcc4 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -8,12 +8,14 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3" CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y diff --git a/boards/atl/mantis-edu/default.px4board b/boards/atl/mantis-edu/default.px4board index 58fcec76d7e8..fd76e4d6ca56 100644 --- a/boards/atl/mantis-edu/default.px4board +++ b/boards/atl/mantis-edu/default.px4board @@ -2,6 +2,7 @@ CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" CONFIG_BOARD_ARCHITECTURE="cortex-m7" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_MAIERTEK_MPC2520=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y diff --git a/boards/bitcraze/crazyflie/default.px4board b/boards/bitcraze/crazyflie/default.px4board index e7e9705f2dc1..02b70b58c35d 100644 --- a/boards/bitcraze/crazyflie/default.px4board +++ b/boards/bitcraze/crazyflie/default.px4board @@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m4" CONFIG_BOARD_CONSTRAINED_FLASH=y CONFIG_BOARD_CONSTRAINED_MEMORY=y CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing" +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BAROMETER_LPS25H=y CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y CONFIG_DRIVERS_GPS=y diff --git a/boards/bitcraze/crazyflie21/default.px4board b/boards/bitcraze/crazyflie21/default.px4board index aa55b50621e8..0c268b6983a6 100644 --- a/boards/bitcraze/crazyflie21/default.px4board +++ b/boards/bitcraze/crazyflie21/default.px4board @@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_FLASH=y CONFIG_BOARD_CONSTRAINED_MEMORY=y CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing" CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_BOSCH_BMI088_I2C=y diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index f312504ee5e4..2a0e40e37efe 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index 99e831c12938..b2212d5f15f6 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y diff --git a/boards/cubepilot/cubeorange/default.px4board b/boards/cubepilot/cubeorange/default.px4board index 91ddcda596bc..e3c84b183895 100644 --- a/boards/cubepilot/cubeorange/default.px4board +++ b/boards/cubepilot/cubeorange/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/cubepilot/cubeorangeplus/default.px4board b/boards/cubepilot/cubeorangeplus/default.px4board index 837876ee7d41..d755eea8d814 100644 --- a/boards/cubepilot/cubeorangeplus/default.px4board +++ b/boards/cubepilot/cubeorangeplus/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/cubepilot/cubeyellow/default.px4board b/boards/cubepilot/cubeyellow/default.px4board index 45cf93a38d95..62cf898af96c 100644 --- a/boards/cubepilot/cubeyellow/default.px4board +++ b/boards/cubepilot/cubeyellow/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/diatone/mamba-f405-mk2/default.px4board b/boards/diatone/mamba-f405-mk2/default.px4board index 32ec4fd47b45..e8ee5ec656c8 100644 --- a/boards/diatone/mamba-f405-mk2/default.px4board +++ b/boards/diatone/mamba-f405-mk2/default.px4board @@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/flywoo/gn-f405/default.px4board b/boards/flywoo/gn-f405/default.px4board index b016b0db9a6a..54d17325bc92 100644 --- a/boards/flywoo/gn-f405/default.px4board +++ b/boards/flywoo/gn-f405/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y diff --git a/boards/hkust/nxt-dual/default.px4board b/boards/hkust/nxt-dual/default.px4board index 884487955590..cab44e781293 100644 --- a/boards/hkust/nxt-dual/default.px4board +++ b/boards/hkust/nxt-dual/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board index bc04f1ce9491..6261079e0d9d 100644 --- a/boards/hkust/nxt-v1/default.px4board +++ b/boards/hkust/nxt-v1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/durandal-v1/default.px4board b/boards/holybro/durandal-v1/default.px4board index 362eaff74250..ecc1bc81013b 100644 --- a/boards/holybro/durandal-v1/default.px4board +++ b/boards/holybro/durandal-v1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/kakutef7/default.px4board b/boards/holybro/kakutef7/default.px4board index bcaedd9cf281..8aaa037cc55a 100644 --- a/boards/holybro/kakutef7/default.px4board +++ b/boards/holybro/kakutef7/default.px4board @@ -9,6 +9,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y diff --git a/boards/holybro/kakuteh7/default.px4board b/boards/holybro/kakuteh7/default.px4board index 270caa7b6510..dbf8aeb7f217 100644 --- a/boards/holybro/kakuteh7/default.px4board +++ b/boards/holybro/kakuteh7/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/kakuteh7mini/default.px4board b/boards/holybro/kakuteh7mini/default.px4board index b49f1cfa012f..eb465e00275c 100644 --- a/boards/holybro/kakuteh7mini/default.px4board +++ b/boards/holybro/kakuteh7mini/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/kakuteh7v2/default.px4board b/boards/holybro/kakuteh7v2/default.px4board index d9d432beec13..45fd6e11eb79 100644 --- a/boards/holybro/kakuteh7v2/default.px4board +++ b/boards/holybro/kakuteh7v2/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/pix32v5/default.px4board b/boards/holybro/pix32v5/default.px4board index 45bd43ee4f4d..0093ee2dcfd0 100644 --- a/boards/holybro/pix32v5/default.px4board +++ b/boards/holybro/pix32v5/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/matek/h743-mini/default.px4board b/boards/matek/h743-mini/default.px4board index 64e472d77048..22efafcfdb38 100644 --- a/boards/matek/h743-mini/default.px4board +++ b/boards/matek/h743-mini/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/matek/h743-slim/default.px4board b/boards/matek/h743-slim/default.px4board index ce5f2222296e..71024fea5ceb 100644 --- a/boards/matek/h743-slim/default.px4board +++ b/boards/matek/h743-slim/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y diff --git a/boards/matek/h743/default.px4board b/boards/matek/h743/default.px4board index ce5f2222296e..dcd9fad5aef1 100644 --- a/boards/matek/h743/default.px4board +++ b/boards/matek/h743/default.px4board @@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/modalai/fc-v1/default.px4board b/boards/modalai/fc-v1/default.px4board index 2a33d1ddb875..e9104cfaeec1 100644 --- a/boards/modalai/fc-v1/default.px4board +++ b/boards/modalai/fc-v1/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index 6fa7ebabaf02..15b94d5dc8c2 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -12,6 +12,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y diff --git a/boards/mro/ctrl-zero-classic/default.px4board b/boards/mro/ctrl-zero-classic/default.px4board index d07a7c1fc9d4..665fbc8626f4 100644 --- a/boards/mro/ctrl-zero-classic/default.px4board +++ b/boards/mro/ctrl-zero-classic/default.px4board @@ -12,6 +12,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-f7-oem/default.px4board b/boards/mro/ctrl-zero-f7-oem/default.px4board index b0701855bf22..9fe340b87f1b 100644 --- a/boards/mro/ctrl-zero-f7-oem/default.px4board +++ b/boards/mro/ctrl-zero-f7-oem/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-f7/default.px4board b/boards/mro/ctrl-zero-f7/default.px4board index 074a4f2ca052..d09ca8a5b50f 100644 --- a/boards/mro/ctrl-zero-f7/default.px4board +++ b/boards/mro/ctrl-zero-f7/default.px4board @@ -9,6 +9,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-h7-oem/default.px4board b/boards/mro/ctrl-zero-h7-oem/default.px4board index 549ba99b7331..ec6c59888db5 100644 --- a/boards/mro/ctrl-zero-h7-oem/default.px4board +++ b/boards/mro/ctrl-zero-h7-oem/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-h7/default.px4board b/boards/mro/ctrl-zero-h7/default.px4board index c32ae10fc056..7bb96d3aca08 100644 --- a/boards/mro/ctrl-zero-h7/default.px4board +++ b/boards/mro/ctrl-zero-h7/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index d4b1d29370aa..40301136e26a 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -9,6 +9,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/x21-777/default.px4board b/boards/mro/x21-777/default.px4board index 5a51a776dde0..361aca448471 100644 --- a/boards/mro/x21-777/default.px4board +++ b/boards/mro/x21-777/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/x21/default.px4board b/boards/mro/x21/default.px4board index 7c206260016f..8640bff623b0 100644 --- a/boards/mro/x21/default.px4board +++ b/boards/mro/x21/default.px4board @@ -10,6 +10,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/nxp/fmuk66-e/default.px4board b/boards/nxp/fmuk66-e/default.px4board index b8bc5cc7f424..749e62e5d54f 100644 --- a/boards/nxp/fmuk66-e/default.px4board +++ b/boards/nxp/fmuk66-e/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MPL3115A2=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y diff --git a/boards/nxp/fmuk66-v3/default.px4board b/boards/nxp/fmuk66-v3/default.px4board index e53ae83c880f..268e89c70fd8 100644 --- a/boards/nxp/fmuk66-v3/default.px4board +++ b/boards/nxp/fmuk66-v3/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MPL3115A2=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y diff --git a/boards/omnibus/f4sd/default.px4board b/boards/omnibus/f4sd/default.px4board index 287d99165930..8d3c58a7f0f5 100644 --- a/boards/omnibus/f4sd/default.px4board +++ b/boards/omnibus/f4sd/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/px4/fmu-v2/default.px4board b/boards/px4/fmu-v2/default.px4board index 59d1c02a7331..f0753941e03d 100644 --- a/boards/px4/fmu-v2/default.px4board +++ b/boards/px4/fmu-v2/default.px4board @@ -9,6 +9,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y CONFIG_DRIVERS_IMU_ST_L3GD20=y diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index 1ced5b78737e..5c24d0e731fb 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v4/default.px4board b/boards/px4/fmu-v4/default.px4board index 0e1bb8f54774..ab106bdb7b90 100644 --- a/boards/px4/fmu-v4/default.px4board +++ b/boards/px4/fmu-v4/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v4pro/default.px4board b/boards/px4/fmu-v4pro/default.px4board index f722e649efae..ff8455c28588 100644 --- a/boards/px4/fmu-v4pro/default.px4board +++ b/boards/px4/fmu-v4pro/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index bfb8b6af4645..beb865832145 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -10,6 +10,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v5/protected.px4board b/boards/px4/fmu-v5/protected.px4board index e5371b2a7dfe..fd3b7bb5222f 100644 --- a/boards/px4/fmu-v5/protected.px4board +++ b/boards/px4/fmu-v5/protected.px4board @@ -6,6 +6,7 @@ CONFIG_COMMON_OPTICAL_FLOW=n CONFIG_COMMON_TELEMETRY=n CONFIG_DRIVERS_CAMERA_CAPTURE=n CONFIG_DRIVERS_CAMERA_TRIGGER=n +CONFIG_DRIVERS_CDCACM_AUTOSTART=n CONFIG_DRIVERS_IRLOCK=n CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_DRIVERS_PWM_INPUT=n diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 2bede96763c0..46d04d8cc2eb 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -14,6 +14,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6c/default.px4board b/boards/px4/fmu-v6c/default.px4board index 148e6326fb26..51484f7903db 100644 --- a/boards/px4/fmu-v6c/default.px4board +++ b/boards/px4/fmu-v6c/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6u/default.px4board b/boards/px4/fmu-v6u/default.px4board index 50b4f6ba3d1d..e733dccc35fc 100644 --- a/boards/px4/fmu-v6u/default.px4board +++ b/boards/px4/fmu-v6u/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index f197a254a09a..7b9488933fb4 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -14,6 +14,7 @@ CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 029462aa4806..17434ed18d3c 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -13,6 +13,7 @@ CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/raspberrypi/pico/default.px4board b/boards/raspberrypi/pico/default.px4board index a5727267a1fa..410f8d4788a9 100644 --- a/boards/raspberrypi/pico/default.px4board +++ b/boards/raspberrypi/pico/default.px4board @@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y diff --git a/boards/siyi/n7/default.px4board b/boards/siyi/n7/default.px4board index cb42f3530c8a..3364cf55f7be 100644 --- a/boards/siyi/n7/default.px4board +++ b/boards/siyi/n7/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index 4bb3c7cc406c..7613792e2ce7 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/spracing/h7extreme/default.px4board b/boards/spracing/h7extreme/default.px4board index c6c28729a73c..aa9790560907 100644 --- a/boards/spracing/h7extreme/default.px4board +++ b/boards/spracing/h7extreme/default.px4board @@ -4,6 +4,7 @@ CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y diff --git a/boards/thepeach/k1/default.px4board b/boards/thepeach/k1/default.px4board index 39fefb9b68a8..d760279546c7 100644 --- a/boards/thepeach/k1/default.px4board +++ b/boards/thepeach/k1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/thepeach/r1/default.px4board b/boards/thepeach/r1/default.px4board index 39fefb9b68a8..d760279546c7 100644 --- a/boards/thepeach/r1/default.px4board +++ b/boards/thepeach/r1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/uvify/core/default.px4board b/boards/uvify/core/default.px4board index bdc591a2810d..8c144aa6062e 100644 --- a/boards/uvify/core/default.px4board +++ b/boards/uvify/core/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y diff --git a/platforms/nuttx/src/px4/common/CMakeLists.txt b/platforms/nuttx/src/px4/common/CMakeLists.txt index ab16e77a0e30..c74810b03a88 100644 --- a/platforms/nuttx/src/px4/common/CMakeLists.txt +++ b/platforms/nuttx/src/px4/common/CMakeLists.txt @@ -38,7 +38,6 @@ if(NOT PX4_BOARD MATCHES "io-v2") board_crashdump.c board_dma_alloc.c board_fat_dma_alloc.c - cdc_acm_check.cpp console_buffer.cpp cpuload.cpp gpio.c diff --git a/platforms/nuttx/src/px4/common/px4_init.cpp b/platforms/nuttx/src/px4/common/px4_init.cpp index ceeb79bd7240..aa11b1cf703c 100644 --- a/platforms/nuttx/src/px4/common/px4_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_init.cpp @@ -62,8 +62,6 @@ #include #endif -extern void cdcacm_init(void); - #if !defined(CONFIG_BUILD_FLAT) typedef CODE void (*initializer_t)(void); extern initializer_t _sinit; @@ -196,10 +194,6 @@ int px4_platform_init() px4_log_initialize(); -#if defined(CONFIG_SYSTEM_CDCACM) && defined(CONFIG_BUILD_FLAT) - cdcacm_init(); -#endif - return PX4_OK; } diff --git a/platforms/nuttx/src/px4/common/px4_layer.cmake b/platforms/nuttx/src/px4/common/px4_layer.cmake index 9199a9528997..de8fe5a0c683 100644 --- a/platforms/nuttx/src/px4/common/px4_layer.cmake +++ b/platforms/nuttx/src/px4/common/px4_layer.cmake @@ -2,7 +2,6 @@ add_library(px4_layer ${KERNEL_SRCS} - cdc_acm_check.cpp ${PX4_SOURCE_DIR}/platforms/common/Serial.cpp SerialImpl.cpp ) diff --git a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake index c55fe568d390..5fbbef164457 100644 --- a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake +++ b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake @@ -6,7 +6,6 @@ add_library(px4_layer board_fat_dma_alloc.c tasks.cpp console_buffer_usr.cpp - cdc_acm_check.cpp ${PX4_SOURCE_DIR}/platforms/posix/src/px4/common/print_load.cpp ${PX4_SOURCE_DIR}/platforms/posix/src/px4/common/cpuload.cpp px4_userspace_init.cpp diff --git a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp index f5d9882ca23a..82cace9e4d24 100644 --- a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp @@ -44,8 +44,6 @@ #include #include -extern void cdcacm_init(void); - extern "C" void px4_userspace_init(void) { hrt_init(); @@ -55,8 +53,4 @@ extern "C" void px4_userspace_init(void) px4::WorkQueueManagerStart(); uorb_start(); - -#if defined(CONFIG_SYSTEM_CDCACM) - cdcacm_init(); -#endif } diff --git a/src/drivers/cdcacm_autostart/CMakeLists.txt b/src/drivers/cdcacm_autostart/CMakeLists.txt new file mode 100644 index 000000000000..8e78ba1cd24c --- /dev/null +++ b/src/drivers/cdcacm_autostart/CMakeLists.txt @@ -0,0 +1,40 @@ +############################################################################ +# +# Copyright (c) 2023 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +px4_add_module( + MODULE drivers__cdcacm_autostart + MAIN cdcacm_autostart + COMPILE_FLAGS + # -DDEBUG_BUILD + SRCS + cdcacm_autostart.cpp + ) diff --git a/src/drivers/cdcacm_autostart/Kconfig b/src/drivers/cdcacm_autostart/Kconfig new file mode 100644 index 000000000000..aabfaad4838e --- /dev/null +++ b/src/drivers/cdcacm_autostart/Kconfig @@ -0,0 +1,6 @@ +menuconfig DRIVERS_CDCACM_AUTOSTART + bool "cdcacm_autostart" + default n + depends on MODULES_MAVLINK + ---help--- + Enable support for cdcacm_autostart \ No newline at end of file diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp new file mode 100644 index 000000000000..d7ebbddd6b0f --- /dev/null +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp @@ -0,0 +1,663 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#if defined(CONFIG_SYSTEM_CDCACM) + +#include "cdcacm_autostart.h" + +__BEGIN_DECLS +#include +#include + +extern int sercon_main(int c, char **argv); +extern int serdis_main(int c, char **argv); +__END_DECLS + +#include + +#define USB_DEVICE_PATH "/dev/ttyACM0" + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) +# undef SERIAL_PASSTHRU_UBLOX_DEV +# if defined(CONFIG_SERIAL_PASSTHRU_GPS1) && defined(CONFIG_BOARD_SERIAL_GPS1) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS1 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS2)&& defined(CONFIG_BOARD_SERIAL_GPS2) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS2 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS3)&& defined(CONFIG_BOARD_SERIAL_GPS3) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS3 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS4)&& defined(CONFIG_BOARD_SERIAL_GPS4) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS4 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS5) && defined(CONFIG_BOARD_SERIAL_GPS5) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS5 +# endif +# if !defined(SERIAL_PASSTHRU_UBLOX_DEV) +# error "CONFIG_SERIAL_PASSTHRU_GPSn and CONFIG_BOARD_SERIAL_GPSn must be defined" +# endif +#endif + +CdcAcmAutostart::CdcAcmAutostart() : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) +{} + +CdcAcmAutostart::~CdcAcmAutostart() +{ + PX4_INFO("Stopping CDC/ACM autostart"); + + if (_ttyacm_fd >= 0) { + px4_close(_ttyacm_fd); + } + + ScheduleClear(); +} + +int CdcAcmAutostart::Start() +{ + PX4_INFO("Starting CDC/ACM autostart"); + UpdateParams(true); + + ScheduleNow(); + + return PX4_OK; +} + +void CdcAcmAutostart::Run() +{ + if (should_exit()) { + exit_and_cleanup(); + return; + } + + UpdateParams(); + + run_state_machine(); +} + +void CdcAcmAutostart::run_state_machine() +{ + _reschedule_time = 500_ms; + _vbus_present = (board_read_VBUS_state() == PX4_OK); + + // If the hardware supports RESET lockout that has nArmed ANDed with VBUS + // vbus_sense may drop during a param save which uses + // BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE to prevent external resets + // while writing the params. If we are not armed and nARMRED is low + // we are in such a lock out so ignore changes on VBUS_SENSE during this + // time. +#if defined(BOARD_GET_EXTERNAL_LOCKOUT_STATE) + + if (BOARD_GET_EXTERNAL_LOCKOUT_STATE() == 0) { + _vbus_present = _vbus_present_prev; + ScheduleDelayed(500_ms); + return; + } + +#endif + + // Do not reconfigure USB while flying + actuator_armed_s report; + _actuator_armed_sub.copy(&report); + + if (report.armed) { + _vbus_present_prev = _vbus_present; + + } else { + + switch (_state) { + case UsbAutoStartState::disconnected: + state_disconnected(); + break; + + case UsbAutoStartState::connecting: + state_connecting(); + break; + + case UsbAutoStartState::connected: + state_connected(); + break; + + case UsbAutoStartState::disconnecting: + state_disconnecting(); + break; + } + } + + _vbus_present_prev = _vbus_present; + ScheduleDelayed(_reschedule_time); +} + +void CdcAcmAutostart::state_connected() +{ + if (!_vbus_present && !_vbus_present_prev && (_active_protocol == UsbProtocol::mavlink)) { + PX4_DEBUG("lost vbus!"); + sched_lock(); + static const char app[] {"mavlink"}; + static const char *stop_argv[] {"mavlink", "stop", "-d", USB_DEVICE_PATH, NULL}; + exec_builtin(app, (char **)stop_argv, NULL, 0); + sched_unlock(); + _state = UsbAutoStartState::disconnecting; + } +} + +void CdcAcmAutostart::state_disconnected() +{ + if (_vbus_present && _vbus_present_prev) { + PX4_DEBUG("starting sercon"); + + if (sercon_main(0, nullptr) == EXIT_SUCCESS) { + _state = UsbAutoStartState::connecting; + PX4_DEBUG("state connecting"); + _reschedule_time = 1_s; + } + + } else if (_vbus_present && !_vbus_present_prev) { + // USB just connected, try again soon + _reschedule_time = 100_ms; + } +} + +void CdcAcmAutostart::state_connecting() +{ + int bytes_available = 0; +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + struct termios uart_config; + speed_t baudrate; +#endif + + if (!_vbus_present) { + PX4_DEBUG("No VBUS"); + goto fail; + } + + if (_ttyacm_fd < 0) { + PX4_DEBUG("opening port"); + _ttyacm_fd = px4_open(USB_DEVICE_PATH, O_RDONLY | O_NONBLOCK); + } + + if (_ttyacm_fd < 0) { + PX4_DEBUG("can't open port"); + goto fail; + } + + if (_sys_usb_auto.get() == 2) { + PX4_INFO("Starting mavlink on %s (SYS_USB_AUTO=2)", USB_DEVICE_PATH); + + if (start_mavlink()) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::mavlink; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + + } else if (_sys_usb_auto.get() == 0) { + // Do nothing + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::none; + return; + } + + // Otherwise autodetect + + if ((px4_ioctl(_ttyacm_fd, FIONREAD, &bytes_available) != PX4_OK) || + (bytes_available < 3)) { + PX4_DEBUG("bytes_available: %d", bytes_available); + // Return back to connecting state to check again soon + return; + } + + // Non-blocking read + _bytes_read = px4_read(_ttyacm_fd, _buffer, sizeof(_buffer)); + +#if defined(DEBUG_BUILD) + + if (_bytes_read > 0) { + fprintf(stderr, "%d bytes\n", _bytes_read); + + for (int i = 0; i < _bytes_read; i++) { + fprintf(stderr, "|%X", _buffer[i]); + } + + fprintf(stderr, "\n"); + } + +#endif // DEBUG_BUILD + + if (_bytes_read <= 0) { + PX4_DEBUG("no _bytes_read"); + // Return back to connecting state to check again soon + return; + } + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + // Get the baudrate for serial passthru before closing the port. + tcgetattr(_ttyacm_fd, &uart_config); + baudrate = cfgetspeed(&uart_config); +#endif + PX4_DEBUG("_bytes_read %d", _bytes_read); + px4_close(_ttyacm_fd); + _ttyacm_fd = -1; + + // Parse for mavlink reboot command + if (scan_buffer_for_mavlink_reboot()) { + // Reboot incoming. Return without rescheduling. + return; + } + + // Parse for mavlink heartbeats (v1 and v2). + if (scan_buffer_for_mavlink_heartbeat()) { + if (start_mavlink()) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::mavlink; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + } + + // Parse for carriage returns indicating someone is trying to use the nsh. + if (scan_buffer_for_carriage_returns()) { + if (start_nsh()) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::nsh; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + } + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + + // Parse for ublox start of packet byte sequence. + if (scan_buffer_for_ublox_bytes()) { + if (start_ublox_serial_passthru(baudrate)) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::ublox; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + } + +#endif + + return; + +fail: + PX4_DEBUG("fail..."); + + // VBUS not present, open failed + if (_ttyacm_fd >= 0) { + px4_close(_ttyacm_fd); + _ttyacm_fd = -1; + } + + _state = UsbAutoStartState::disconnecting; +} + +void CdcAcmAutostart::state_disconnecting() +{ + PX4_DEBUG("state_disconnecting"); + + if (_ttyacm_fd > 0) { + px4_close(_ttyacm_fd); + } + + // Disconnect serial + serdis_main(0, NULL); + _state = UsbAutoStartState::disconnected; + _active_protocol = UsbProtocol::none; +} + +bool CdcAcmAutostart::scan_buffer_for_mavlink_reboot() +{ + bool rebooting = false; + + // Mavlink reboot/shutdown command + // COMMAND_LONG (#76) with command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246) + static constexpr int MAVLINK_COMMAND_LONG_MIN_LENGTH = 41; + + if (_bytes_read < MAVLINK_COMMAND_LONG_MIN_LENGTH) { + return rebooting; + } + + // scan buffer for mavlink COMMAND_LONG + for (int i = 0; i < _bytes_read - MAVLINK_COMMAND_LONG_MIN_LENGTH; i++) { + if ((_buffer[i] == 0xFE) // Mavlink v1 start byte + && (_buffer[i + 5] == 76) // 76=0x4C COMMAND_LONG + && (_buffer[i + 34] == 246) // 246=0xF6 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN + ) { + // mavlink v1 COMMAND_LONG + // buffer[0]: start byte (0xFE for mavlink v1) + // buffer[3]: SYSID + // buffer[4]: COMPID + // buffer[5]: message id (COMMAND_LONG 76=0x4C) + // buffer[6-10]: COMMAND_LONG param 1 (little endian float) + // buffer[34]: COMMAND_LONG command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246/0xF6) + float param1_raw = 0; + memcpy(¶m1_raw, &_buffer[i + 6], 4); + int param1 = roundf(param1_raw); + + PX4_INFO("%s: Mavlink MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN param 1: %d (SYSID:%d COMPID:%d)", + USB_DEVICE_PATH, param1, _buffer[i + 3], _buffer[i + 4]); + + if (param1 == 1) { + // 1: Reboot autopilot + rebooting = true; + px4_reboot_request(REBOOT_REQUEST, 0); + + } else if (param1 == 2) { + // 2: Shutdown autopilot +#if defined(BOARD_HAS_POWER_CONTROL) + rebooting = true; + px4_shutdown_request(0); +#endif // BOARD_HAS_POWER_CONTROL + + } else if (param1 == 3) { + // 3: Reboot autopilot and keep it in the bootloader until upgraded. + rebooting = true; + px4_reboot_request(REBOOT_TO_BOOTLOADER, 0); + } + } + } + + return rebooting; +} + +bool CdcAcmAutostart::scan_buffer_for_mavlink_heartbeat() +{ + static constexpr int MAVLINK_HEARTBEAT_MIN_LENGTH = 9; + bool start_mavlink = false; + + if (_bytes_read < MAVLINK_HEARTBEAT_MIN_LENGTH) { + return start_mavlink; + } + + // scan buffer for mavlink HEARTBEAT (v1 & v2) + for (int i = 0; i < _bytes_read - MAVLINK_HEARTBEAT_MIN_LENGTH; i++) { + if ((_buffer[i] == 0xFE) && (_buffer[i + 1] == 9) && (_buffer[i + 5] == 0)) { + // mavlink v1 HEARTBEAT + // buffer[0]: start byte (0xFE for mavlink v1) + // buffer[1]: length (9 for HEARTBEAT) + // buffer[3]: SYSID + // buffer[4]: COMPID + // buffer[5]: mavlink message id (0 for HEARTBEAT) + PX4_INFO("%s: launching mavlink (HEARTBEAT v1 from SYSID:%d COMPID:%d)", + USB_DEVICE_PATH, _buffer[i + 3], _buffer[i + 4]); + start_mavlink = true; + + } else if ((_buffer[i] == 0xFD) && (_buffer[i + 1] == 9) + && (_buffer[i + 7] == 0) && (_buffer[i + 8] == 0) && (_buffer[i + 9] == 0)) { + // mavlink v2 HEARTBEAT + // buffer[0]: start byte (0xFD for mavlink v2) + // buffer[1]: length (9 for HEARTBEAT) + // buffer[5]: SYSID + // buffer[6]: COMPID + // buffer[7:9]: mavlink message id (0 for HEARTBEAT) + PX4_INFO("%s: launching mavlink (HEARTBEAT v2 from SYSID:%d COMPID:%d)", + USB_DEVICE_PATH, _buffer[i + 5], _buffer[i + 6]); + start_mavlink = true; + } + } + + return start_mavlink; +} + +bool CdcAcmAutostart::scan_buffer_for_carriage_returns() +{ + bool start_nsh = false; + + if (_bytes_read < 3) { + return start_nsh; + } + + // nshterm (3 carriage returns) + // scan buffer looking for 3 consecutive carriage returns (0xD) + for (int i = 1; i < _bytes_read - 1; i++) { + if (_buffer[i - 1] == 0xD && _buffer[i] == 0xD && _buffer[i + 1] == 0xD) { + PX4_INFO("%s: launching nshterm", USB_DEVICE_PATH); + start_nsh = true; + break; + } + } + + return start_nsh; +} + +bool CdcAcmAutostart::scan_buffer_for_ublox_bytes() +{ + bool success = false; + + if (_bytes_read < 4) { + return success; + } + + // scan buffer looking for 0xb5 0x62 which indicates the start of a packet + for (int i = 0; i < _bytes_read; i++) { + bool ub = _buffer[i] == 0xb5 && _buffer[i + 1] == 0x62; + + if (ub && ((_buffer[i + 2 ] == 0x6 && (_buffer[i + 3 ] == 0xb8 || _buffer[i + 3 ] == 0x13)) || + (_buffer[i + 2 ] == 0xa && _buffer[i + 3 ] == 0x4))) { + PX4_INFO("%s: launching ublox serial passthru", USB_DEVICE_PATH); + success = true; + break; + } + } + + return success; +} + +bool CdcAcmAutostart::start_mavlink() +{ + bool success = false; + char mavlink_mode_string[3]; + snprintf(mavlink_mode_string, sizeof(mavlink_mode_string), "%ld", _usb_mav_mode.get()); + static const char *argv[] {"mavlink", "start", "-d", USB_DEVICE_PATH, "-m", mavlink_mode_string, nullptr}; + + if (execute_process((char **)argv) > 0) { + success = true; + } + + return success; +} + +bool CdcAcmAutostart::start_nsh() +{ + bool success = false; + static const char *argv[] {"nshterm", USB_DEVICE_PATH, nullptr}; + + if (execute_process((char **)argv) > 0) { + success = true; + } + + return success; +} + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) +bool CdcAcmAutostart::start_ublox_serial_passthru(speed_t baudrate) +{ + bool success = false; + char baudstring[16]; + snprintf(baudstring, sizeof(baudstring), "%ld", baudrate); + + // Stop the GPS driver first + static const char *gps_argv[] {"gps", "stop", nullptr}; + static const char *passthru_argv[] {"serial_passthru", "start", "-t", "-b", baudstring, "-e", USB_DEVICE_PATH, "-d", SERIAL_PASSTHRU_UBLOX_DEV, nullptr}; + + if (execute_process((char **)gps_argv) > 0) { + if (execute_process((char **)passthru_argv) > 0) { + success = true; + } + } + + return success; +} +#endif + +int CdcAcmAutostart::execute_process(char **argv) +{ + int pid = -1; + sched_lock(); + + pid = exec_builtin(argv[0], argv, nullptr, 0); + + sched_unlock(); + return pid; +} + +int CdcAcmAutostart::task_spawn(int argc, char *argv[]) +{ + CdcAcmAutostart *instance = new CdcAcmAutostart(); + + if (!instance) { + PX4_ERR("alloc failed"); + return -1; + } + + int ret = instance->Start(); + + if (ret != PX4_OK) { + delete instance; + return ret; + } + + _object.store(instance); + _task_id = task_id_is_work_queue; + + return ret; +} + +void CdcAcmAutostart::UpdateParams(const bool force) +{ + if (_parameter_update_sub.updated() || force) { + parameter_update_s param_update; + _parameter_update_sub.copy(¶m_update); + ModuleParams::updateParams(); + } +} + +int CdcAcmAutostart::custom_command(int argc, char *argv[]) +{ + return print_usage("unknown command"); +} + +int CdcAcmAutostart::print_status() +{ + const char *state = ""; + const char *protocol = ""; + + switch (_state) { + case UsbAutoStartState::disconnected: + state = "disconnected"; + break; + + case UsbAutoStartState::connecting: + state = "connecting"; + break; + + case UsbAutoStartState::connected: + state = "connected"; + break; + + case UsbAutoStartState::disconnecting: + state = "disconnecting"; + break; + } + + switch (_active_protocol) { + case UsbProtocol::none: + protocol = "none"; + break; + + case UsbProtocol::mavlink: + protocol = "mavlink"; + break; + + case UsbProtocol::nsh: + protocol = "nsh"; + break; + + case UsbProtocol::ublox: + protocol = "ublox"; + break; + } + + PX4_INFO("Running"); + PX4_INFO("State: %s", state); + PX4_INFO("Protocol: %s", protocol); + return PX4_OK; +} + +int CdcAcmAutostart::print_usage(const char *reason) +{ + if (reason) { + printf("%s\n\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +This module listens on USB and auto-configures the protocol depending on the bytes received. +The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the parameter SYS_USB_AUTO=2 +the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin +and continue to check for VBUS and start mavlink once it is detected. +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("cdcacm_autostart", "system"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +#endif + +extern "C" __EXPORT int cdcacm_autostart_main(int argc, char *argv[]) +{ +#if defined(CONFIG_SYSTEM_CDCACM) + return CdcAcmAutostart::main(argc, argv); +#endif + return 1; +} diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart.h b/src/drivers/cdcacm_autostart/cdcacm_autostart.h new file mode 100644 index 000000000000..a0e12715151b --- /dev/null +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart.h @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include +#include +#include +#include +#include +#include + +#include + +using namespace time_literals; + +class CdcAcmAutostart : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + CdcAcmAutostart(); + ~CdcAcmAutostart() override; + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + /** @see ModuleBase */ + int print_status() override; + + int Start(); + +private: + + enum class UsbAutoStartState { + disconnected, + connecting, + connected, + disconnecting, + }; + + enum class UsbProtocol { + none, + mavlink, + nsh, + ublox, + }; + + void Run() override; + + void UpdateParams(const bool force = false); + + void run_state_machine(); + + void state_disconnected(); + void state_connecting(); + void state_connected(); + void state_disconnecting(); + + bool scan_buffer_for_mavlink_reboot(); + bool scan_buffer_for_mavlink_heartbeat(); + bool scan_buffer_for_carriage_returns(); + bool scan_buffer_for_ublox_bytes(); + + bool start_mavlink(); + bool start_nsh(); +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + bool start_ublox_serial_passthru(speed_t baudrate); +#endif + int execute_process(char **argv); + + uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 500_ms}; + + UsbAutoStartState _state{UsbAutoStartState::disconnected}; + UsbProtocol _active_protocol{UsbProtocol::none}; + bool _vbus_present = false; + bool _vbus_present_prev = false; + int _ttyacm_fd = -1; + + char _buffer[80] = {}; + int _bytes_read = 0; + + uint32_t _reschedule_time = 0; + + DEFINE_PARAMETERS( + (ParamInt) _sys_usb_auto, + (ParamInt) _usb_mav_mode + ) +}; diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c b/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c new file mode 100644 index 000000000000..3dcc16ad2f4f --- /dev/null +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c @@ -0,0 +1,68 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * Enable USB autostart + * + * @value 0 Disabled + * @value 1 Auto-detect + * @value 2 MAVLink + * + * @reboot_required true + * + * @group CDCACM + */ +PARAM_DEFINE_INT32(SYS_USB_AUTO, 2); + +/** + * Specify USB MAVLink mode + * + * @value 0 normal + * @value 1 custom + * @value 2 onboard + * @value 3 osd + * @value 4 magic + * @value 5 config + * @value 6 iridium + * @value 7 minimal + * @value 8 extvision + * @value 9 extvisionmin + * @value 10 gimbal + * @value 11 onboard_low_bandwidth + * @value 12 uavionix + * + * @reboot_required true + * + * @group CDCACM + */ +PARAM_DEFINE_INT32(USB_MAV_MODE, 2); \ No newline at end of file diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 722c1254f65c..186bfe793631 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2094,11 +2094,6 @@ Mavlink::task_main(int argc, char *argv[]) /* USB has no baudrate, but use a magic number for 'fast' */ _baudrate = 2000000; - - if (_mode == MAVLINK_MODE_COUNT) { - _mode = MAVLINK_MODE_CONFIG; - } - _ftp_on = true; _is_usb_uart = true; @@ -2223,11 +2218,24 @@ Mavlink::task_main(int argc, char *argv[]) /* open the UART device after setting the instance, as it might block */ if (get_protocol() == Protocol::SERIAL) { - _uart_fd = mavlink_open_uart(_baudrate, _device_name, _flow_control); - if (_uart_fd < 0) { - PX4_ERR("could not open %s", _device_name); - return PX4_ERROR; + // NOTE: we attempt to open the port multiple times due to sercon returning before + // the port is ready to be opened. This avoids needing to sleep() after sercon_main. + int attempts = 0; + static const int max_attempts = 3; + + while (_uart_fd < 0) { + _uart_fd = mavlink_open_uart(_baudrate, _device_name, _flow_control); + attempts++; + + if (_uart_fd < 0 && attempts < max_attempts) { + PX4_ERR("could not open %s, retrying", _device_name); + px4_usleep(1_s); + + } else if (_uart_fd < 0) { + PX4_ERR("failed to open %s after %d attempts, exiting!", _device_name, attempts); + return PX4_ERROR; + } } } diff --git a/src/systemcmds/serial_passthru/Kconfig b/src/systemcmds/serial_passthru/Kconfig index 4c4cb107d8ac..aabd8c59fe27 100644 --- a/src/systemcmds/serial_passthru/Kconfig +++ b/src/systemcmds/serial_passthru/Kconfig @@ -11,7 +11,7 @@ config SERIAL_PASSTHRU_UBLOX bool "Detect and Auto Connect on U-Center messages" default n ---help--- - This option will enable the cdc_acm_check to launch + This option will enable the cdcacm_autostart to launch The passthru driver. # From e72ecdbefb2aaddc5ad7fd6c9171996edf7d0bcb Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Mon, 20 May 2024 12:38:19 -0600 Subject: [PATCH 242/652] drivers/imu: new Murata SCH16T IMU driver (#22914) --------- Co-authored-by: alexklimaj --- ROMFS/px4fmu_common/init.d/rc.sensors | 6 + boards/ark/fmu-v6x/default.px4board | 1 + src/drivers/drv_sensor.h | 2 + src/drivers/imu/Kconfig | 1 + src/drivers/imu/murata/Kconfig | 3 + src/drivers/imu/murata/sch16t/CMakeLists.txt | 47 ++ src/drivers/imu/murata/sch16t/Kconfig | 5 + .../murata/sch16t/Murata_SCH16T_registers.hpp | 115 ++++ src/drivers/imu/murata/sch16t/SCH16T.cpp | 516 ++++++++++++++++++ src/drivers/imu/murata/sch16t/SCH16T.hpp | 149 +++++ src/drivers/imu/murata/sch16t/parameters.c | 44 ++ src/drivers/imu/murata/sch16t/sch16t_main.cpp | 87 +++ 12 files changed, 976 insertions(+) create mode 100644 src/drivers/imu/murata/Kconfig create mode 100644 src/drivers/imu/murata/sch16t/CMakeLists.txt create mode 100644 src/drivers/imu/murata/sch16t/Kconfig create mode 100644 src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp create mode 100644 src/drivers/imu/murata/sch16t/SCH16T.cpp create mode 100644 src/drivers/imu/murata/sch16t/SCH16T.hpp create mode 100644 src/drivers/imu/murata/sch16t/parameters.c create mode 100644 src/drivers/imu/murata/sch16t/sch16t_main.cpp diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 490038c608fe..5410d28beeb1 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -138,6 +138,12 @@ then adis16507 -S start fi +# SCH16T spi external IMU +if param compare -s SENS_EN_SCH16T 1 +then + sch16t -S start +fi + # Eagle Tree airspeed sensor external I2C if param compare -s SENS_EN_ETSASPD 1 then diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 1209adb9dcc4..168b17cdfaa9 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -20,6 +20,7 @@ CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y +CONFIG_DRIVERS_IMU_MURATA_SCH16T=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 4b1d18e76ba0..604ab4946b29 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -133,6 +133,8 @@ #define DRV_IMU_DEVTYPE_ADIS16477 0x59 #define DRV_IMU_DEVTYPE_ADIS16507 0x5A +#define DRV_IMU_DEVTYPE_SCH16T 0x5B + #define DRV_BARO_DEVTYPE_MPC2520 0x5F #define DRV_BARO_DEVTYPE_LPS22HB 0x60 diff --git a/src/drivers/imu/Kconfig b/src/drivers/imu/Kconfig index 3b084a580169..ee0978d39cd9 100644 --- a/src/drivers/imu/Kconfig +++ b/src/drivers/imu/Kconfig @@ -8,6 +8,7 @@ menu "IMU" select DRIVERS_IMU_ANALOG_DEVICES_ADIS16470 select DRIVERS_IMU_BOSCH_BMI055 select DRIVERS_IMU_BOSCH_BMI088 + select DRIVERS_IMU_MURATA_SCH16T select DRIVERS_IMU_NXP_FXAS21002C select DRIVERS_IMU_NXP_FXOS8701CQ select DRIVERS_IMU_INVENSENSE_ICM20602 diff --git a/src/drivers/imu/murata/Kconfig b/src/drivers/imu/murata/Kconfig new file mode 100644 index 000000000000..36d4534078aa --- /dev/null +++ b/src/drivers/imu/murata/Kconfig @@ -0,0 +1,3 @@ +menu "Murata" +rsource "*/Kconfig" +endmenu #Murata diff --git a/src/drivers/imu/murata/sch16t/CMakeLists.txt b/src/drivers/imu/murata/sch16t/CMakeLists.txt new file mode 100644 index 000000000000..73b90a12fb45 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/CMakeLists.txt @@ -0,0 +1,47 @@ +############################################################################ +# +# Copyright (c) 2022 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_module( + MODULE drivers__imu__murata__sch16t + MAIN sch16t + COMPILE_FLAGS + SRCS + SCH16T.cpp + SCH16T.hpp + sch16t_main.cpp + Murata_SCH16T_registers.hpp + DEPENDS + drivers_accelerometer + drivers_gyroscope + px4_work_queue + ) diff --git a/src/drivers/imu/murata/sch16t/Kconfig b/src/drivers/imu/murata/sch16t/Kconfig new file mode 100644 index 000000000000..ef0e906edd25 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_MURATA_SCH16T + bool "SCH16T" + default n + ---help--- + Enable support for murata SCH16T diff --git a/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp b/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp new file mode 100644 index 000000000000..07d84dcb36e7 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * 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 + +namespace Murata_SCH16T +{ +static constexpr uint32_t SPI_SPEED = 5 * 1000 * 1000; // 5 MHz SPI serial interface +static constexpr uint32_t SAMPLE_INTERVAL_US = 678; // 1500 Hz -- decimation factor 8, F_PRIM/16, 1.475 kHz +static constexpr uint16_t EOI = (1 << 1); // End of Initialization +static constexpr uint16_t EN_SENSOR = (1 << 0); // Enable RATE and ACC measurement +static constexpr uint16_t DRY_DRV_EN = (1 << 5); // Enables Data ready function +static constexpr uint16_t FILTER_BYPASS = (0b111); // Bypass filter +static constexpr uint16_t RATE_300DPS_1475HZ = 0b0'001'001'011'011'011; // Gyro XYZ range 300 deg/s @ 1475Hz +static constexpr uint16_t ACC12_8G_1475HZ = 0b0'001'001'011'011'011; // Acc XYZ range 8 G and 1475 update rate +static constexpr uint16_t ACC3_26G = (0b000 << 0); +static constexpr uint16_t SPI_SOFT_RESET = (0b1010); + +// Data registers +#define RATE_X1 0x01 // 20 bit +#define RATE_Y1 0x02 // 20 bit +#define RATE_Z1 0x03 // 20 bit +#define ACC_X1 0x04 // 20 bit +#define ACC_Y1 0x05 // 20 bit +#define ACC_Z1 0x06 // 20 bit +#define ACC_X3 0x07 // 20 bit +#define ACC_Y3 0x08 // 20 bit +#define ACC_Z3 0x09 // 20 bit +#define RATE_X2 0x0A // 20 bit +#define RATE_Y2 0x0B // 20 bit +#define RATE_Z2 0x0C // 20 bit +#define ACC_X2 0x0D // 20 bit +#define ACC_Y2 0x0E // 20 bit +#define ACC_Z2 0x0F // 20 bit +#define TEMP 0x10 // 16 bit +// Status registers +#define STAT_SUM 0x14 // 16 bit +#define STAT_SUM_SAT 0x15 // 16 bit +#define STAT_COM 0x16 // 16 bit +#define STAT_RATE_COM 0x17 // 16 bit +#define STAT_RATE_X 0x18 // 16 bit +#define STAT_RATE_Y 0x19 // 16 bit +#define STAT_RATE_Z 0x1A // 16 bit +#define STAT_ACC_X 0x1B // 16 bit +#define STAT_ACC_Y 0x1C // 16 bit +#define STAT_ACC_Z 0x1D // 16 bit +// Control registers +#define CTRL_FILT_RATE 0x25 // 9 bit +#define CTRL_FILT_ACC12 0x26 // 9 bit +#define CTRL_FILT_ACC3 0x27 // 9 bit +#define CTRL_RATE 0x28 // 15 bit +#define CTRL_ACC12 0x29 // 15 bit +#define CTRL_ACC3 0x2A // 3 bit +#define CTRL_USER_IF 0x33 // 16 bit +#define CTRL_ST 0x34 // 13 bit +#define CTRL_MODE 0x35 // 4 bit +#define CTRL_RESET 0x36 // 4 bit +// Misc registers +#define ASIC_ID 0x3B // 12 bit +#define COMP_ID 0x3C // 16 bit +#define SN_ID1 0x3D // 16 bit +#define SN_ID2 0x3E // 16 bit +#define SN_ID3 0x3F // 16 bit + +// STAT_SUM_SAT bits +#define STAT_SUM_SAT_RSVD (1 << 15) +#define STAT_SUM_SAT_RATE_X1 (1 << 14) +#define STAT_SUM_SAT_RATE_Y1 (1 << 13) +#define STAT_SUM_SAT_RATE_Z1 (1 << 12) +#define STAT_SUM_SAT_ACC_X1 (1 << 11) +#define STAT_SUM_SAT_ACC_Y1 (1 << 10) +#define STAT_SUM_SAT_ACC_Z1 (1 << 9) +#define STAT_SUM_SAT_ACC_X3 (1 << 8) +#define STAT_SUM_SAT_ACC_Y3 (1 << 7) +#define STAT_SUM_SAT_ACC_Z3 (1 << 6) +#define STAT_SUM_SAT_RATE_X2 (1 << 5) +#define STAT_SUM_SAT_RATE_Y2 (1 << 4) +#define STAT_SUM_SAT_RATE_Z2 (1 << 3) +#define STAT_SUM_SAT_ACC_X2 (1 << 2) +#define STAT_SUM_SAT_ACC_Y2 (1 << 1) +#define STAT_SUM_SAT_ACC_Z2 (1 << 0) + +} // namespace Murata_SCH16T diff --git a/src/drivers/imu/murata/sch16t/SCH16T.cpp b/src/drivers/imu/murata/sch16t/SCH16T.cpp new file mode 100644 index 000000000000..5a682bfe23bd --- /dev/null +++ b/src/drivers/imu/murata/sch16t/SCH16T.cpp @@ -0,0 +1,516 @@ +/**************************************************************************** + * + * 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 "SCH16T.hpp" + +using namespace time_literals; + +#define SPI48_DATA_INT32(a) (((int32_t)(((a) << 4) & 0xfffff000UL)) >> 12) +#define SPI48_DATA_UINT32(a) ((uint32_t)(((a) >> 8) & 0x000fffffUL)) +#define SPI48_DATA_UINT16(a) ((uint16_t)(((a) >> 8) & 0x0000ffffUL)) + +static constexpr uint32_t POWER_ON_TIME = 250_ms; + +SCH16T::SCH16T(const I2CSPIDriverConfig &config) : + SPI(config), + I2CSPIDriver(config), + _px4_accel(get_device_id(), config.rotation), + _px4_gyro(get_device_id(), config.rotation), + _drdy_gpio(config.drdy_gpio) +{ + if (_drdy_gpio != 0) { + _drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed"); + } + +#if defined(SPI6_nRESET_EXTERNAL1) + _hardware_reset_available = true; +#endif +} + +SCH16T::~SCH16T() +{ + perf_free(_reset_perf); + perf_free(_bad_transfer_perf); + perf_free(_perf_crc_bad); + perf_free(_perf_frame_bad); + perf_free(_drdy_missed_perf); +} + +int SCH16T::init() +{ + px4_usleep(POWER_ON_TIME); + + int ret = SPI::init(); + + if (ret != PX4_OK) { + DEVICE_DEBUG("SPI::init failed (%i)", ret); + return ret; + } + + Reset(); + + return PX4_OK; +} + +int SCH16T::probe() +{ + if (hrt_absolute_time() < POWER_ON_TIME) { + PX4_WARN("Required Power-On Start-Up Time %" PRIu32 " ms", POWER_ON_TIME); + } + + RegisterRead(COMP_ID); + uint16_t comp_id = SPI48_DATA_UINT16(RegisterRead(ASIC_ID)); + uint16_t asic_id = SPI48_DATA_UINT16(RegisterRead(ASIC_ID)); + + RegisterRead(SN_ID1); + uint16_t sn_id1 = SPI48_DATA_UINT16(RegisterRead(SN_ID2)); + uint16_t sn_id2 = SPI48_DATA_UINT16(RegisterRead(SN_ID3)); + uint16_t sn_id3 = SPI48_DATA_UINT16(RegisterRead(SN_ID3)); + + char serial_str[14]; + snprintf(serial_str, 14, "%05d%01X%04X", sn_id2, sn_id1 & 0x000F, sn_id3); + + PX4_INFO("Serial:\t %s", serial_str); + PX4_INFO("COMP_ID:\t 0x%0x", comp_id); + PX4_INFO("ASIC_ID:\t 0x%0x", asic_id); + + // SCH16T-K01 - ID hex = 0x0020 + // SCH1633-B13 - ID hex = 0x0017 + bool success = asic_id == 0x20 && comp_id == 0x17; + + return success ? PX4_OK : PX4_ERROR; +} + +void SCH16T::Reset() +{ + if (_drdy_gpio) { + DataReadyInterruptDisable(); + } + + ScheduleClear(); + + _state = STATE::RESET_INIT; + ScheduleNow(); +} + +void SCH16T::ResetSpi6(bool reset) +{ +#if defined(SPI6_RESET) + SPI6_RESET(reset); +#endif +} + +void SCH16T::exit_and_cleanup() +{ + if (_drdy_gpio) { + DataReadyInterruptDisable(); + } + + I2CSPIDriverBase::exit_and_cleanup(); +} + +void SCH16T::print_status() +{ + I2CSPIDriverBase::print_status(); + perf_print_counter(_reset_perf); + perf_print_counter(_bad_transfer_perf); + perf_print_counter(_perf_crc_bad); + perf_print_counter(_perf_frame_bad); + perf_print_counter(_drdy_missed_perf); +} + +void SCH16T::RunImpl() +{ + const hrt_abstime now = hrt_absolute_time(); + + switch (_state) { + case STATE::RESET_INIT: { + perf_count(_reset_perf); + + _failure_count = 0; + + if (_hardware_reset_available) { + PX4_INFO("Resetting (hard)"); + ResetSpi6(true); + _state = STATE::RESET_HARD; + ScheduleDelayed(2_ms); + + } else { + PX4_INFO("Resetting (soft)"); + SoftwareReset(); + _state = STATE::CONFIGURE; + ScheduleDelayed(POWER_ON_TIME); + } + + break; + } + + case STATE::RESET_HARD: { + if (_hardware_reset_available) { + ResetSpi6(false); + } + + _state = STATE::CONFIGURE; + ScheduleDelayed(POWER_ON_TIME); + break; + } + + case STATE::CONFIGURE: { + Configure(); + + _state = STATE::LOCK_CONFIGURATION; + ScheduleDelayed(POWER_ON_TIME); + break; + } + + case STATE::LOCK_CONFIGURATION: { + ReadStatusRegisters(); // Read all status registers once + RegisterWrite(CTRL_MODE, (EOI | EN_SENSOR)); // Write EOI and EN_SENSOR + + _state = STATE::VALIDATE; + ScheduleDelayed(5_ms); + break; + } + + case STATE::VALIDATE: { + ReadStatusRegisters(); // Read all status registers twice + ReadStatusRegisters(); + + // Check that registers are configured properly and that the sensor status is OK + if (ValidateSensorStatus() && ValidateRegisterConfiguration()) { + _state = STATE::READ; + + if (_drdy_gpio) { + DataReadyInterruptConfigure(); + ScheduleDelayed(100_ms); // backup schedule as a watchdog timeout + + } else { + ScheduleOnInterval(SAMPLE_INTERVAL_US, SAMPLE_INTERVAL_US); + } + + } else { + _state = STATE::RESET_INIT; + ScheduleDelayed(100_ms); + } + + break; + } + + case STATE::READ: { + hrt_abstime timestamp_sample = now; + + if (_drdy_gpio) { + // scheduled from interrupt if _drdy_timestamp_sample was set as expected + const hrt_abstime drdy_timestamp_sample = _drdy_timestamp_sample.fetch_and(0); + + if ((now - drdy_timestamp_sample) < SAMPLE_INTERVAL_US) { + timestamp_sample = drdy_timestamp_sample; + + } else { + perf_count(_drdy_missed_perf); + } + + // push backup schedule back + ScheduleDelayed(SAMPLE_INTERVAL_US * 2); + } + + // Collect the data + SensorData data = {}; + + if (ReadData(&data)) { + _px4_accel.set_temperature(float(data.temp) / 100.f); // Temperature signal sensitivity is 100 LSB/°C + _px4_gyro.set_temperature(float(data.temp) / 100.f); + _px4_accel.update(timestamp_sample, data.acc_x, data.acc_y, data.acc_z); + _px4_gyro.update(timestamp_sample, data.gyro_x, data.gyro_y, data.gyro_z); + + if (_failure_count > 0) { + _failure_count--; + } + + } else { + perf_count(_bad_transfer_perf); + _failure_count++; + } + + // Reset if successive failures + if (_failure_count > 10) { + PX4_INFO("Failure count high, resetting"); + Reset(); + return; + } + + break; + } + + default: + break; + } // end switch/case +} + +bool SCH16T::ReadData(SensorData *data) +{ + uint64_t temp = 0; + uint64_t gyro_x = 0; + uint64_t gyro_y = 0; + uint64_t gyro_z = 0; + uint64_t acc_x = 0; + uint64_t acc_y = 0; + uint64_t acc_z = 0; + + // Data registers are 20bit 2s complement + RegisterRead(TEMP); + temp = RegisterRead(STAT_SUM_SAT); + _sensor_status.saturation = SPI48_DATA_UINT16(RegisterRead(RATE_X2)); + gyro_x = RegisterRead(RATE_Y2); + gyro_y = RegisterRead(RATE_Z2); + + // Check if ACC2 is saturated, if so, use ACC3 + if ((_sensor_status.saturation & STAT_SUM_SAT_ACC_X2) || (_sensor_status.saturation & STAT_SUM_SAT_ACC_Y2) + || (_sensor_status.saturation & STAT_SUM_SAT_ACC_Z2)) { + gyro_z = RegisterRead(ACC_X3); + acc_x = RegisterRead(ACC_Y3); + acc_y = RegisterRead(ACC_Z3); + acc_z = RegisterRead(TEMP); + _px4_accel.set_scale(1.f / 1600.f); + _px4_accel.set_range(260.f); + + } else { + gyro_z = RegisterRead(ACC_X2); + acc_x = RegisterRead(ACC_Y2); + acc_y = RegisterRead(ACC_Z2); + acc_z = RegisterRead(TEMP); + _px4_accel.set_scale(1.f / 3200.f); + _px4_accel.set_range(163.4f); + } + + static constexpr uint64_t MASK48_ERROR = 0x001E00000000UL; + uint64_t values[] = { gyro_x, gyro_y, gyro_z, acc_x, acc_y, acc_z, temp }; + + for (auto v : values) { + // Check for frame errors + if (v & MASK48_ERROR) { + perf_count(_perf_frame_bad); + return false; + } + + // Validate the CRC + if (uint8_t(v & 0xff) != CalculateCRC8(v)) { + perf_count(_perf_crc_bad); + return false; + } + } + + // Data registers are 20bit 2s complement + data->acc_x = SPI48_DATA_INT32(acc_x); + data->acc_y = SPI48_DATA_INT32(acc_y); + data->acc_z = SPI48_DATA_INT32(acc_z); + data->gyro_x = SPI48_DATA_INT32(gyro_x); + data->gyro_y = SPI48_DATA_INT32(gyro_y); + data->gyro_z = SPI48_DATA_INT32(gyro_z); + // Temperature data is always 16 bits wide. Drop 4 LSBs as they are not used. + data->temp = SPI48_DATA_INT32(temp) >> 4; + + // Conver to PX4 coordinate system (FLU to FRD) + data->acc_x = data->acc_x; + data->acc_y = -data->acc_y; + data->acc_z = -data->acc_z; + data->gyro_x = data->gyro_x; + data->gyro_y = -data->gyro_y; + data->gyro_z = -data->gyro_z; + + return true; +} + +void SCH16T::Configure() +{ + for (auto &r : _registers) { + RegisterWrite(r.addr, r.value); + } + + RegisterWrite(CTRL_USER_IF, DRY_DRV_EN); // Enable data ready + RegisterWrite(CTRL_MODE, EN_SENSOR); // Enable the sensor + + // NOTE: we use ACC3 for the higher range. The DRDY frequency adjusts to whichever register bank is + // being sampled from (decimated vs interpolated outputs). RATE_XYZ2 is decimated and RATE_XYZ1 is interpolated. + _px4_gyro.set_range(math::radians(327.68f)); // +-/ 300°/sec calibrated range, 327.68°/sec electrical headroom (20bit) + _px4_gyro.set_scale(math::radians(1.f / 1600.f)); // scaling 1600 LSB/°/sec -> rad/s per LSB + + // ACC12 range is 163.4 m/s^2, 3200 LSB/(m/s^2), ACC3 range is 260 m/s^2, 1600 LSB/(m/s^2) + _px4_accel.set_range(163.4f); + _px4_accel.set_scale(1.f / 3200.f); +} + +bool SCH16T::ValidateRegisterConfiguration() +{ + bool success = true; + + for (auto &r : _registers) { + RegisterRead(r.addr); // double read, wasteful but makes the code cleaner, not high rate so doesn't matter anyway + auto value = SPI48_DATA_UINT16(RegisterRead(r.addr)); + + if (value != r.value) { + PX4_INFO("Register 0x%0x misconfigured: 0x%0x", r.addr, value); + success = false; + } + } + + return success; +} + +void SCH16T::ReadStatusRegisters() +{ + RegisterRead(STAT_SUM); + _sensor_status.summary = SPI48_DATA_UINT16(RegisterRead(STAT_SUM_SAT)); + _sensor_status.saturation = SPI48_DATA_UINT16(RegisterRead(STAT_COM)); + _sensor_status.common = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_COM)); + _sensor_status.rate_common = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_X)); + _sensor_status.rate_x = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_Y)); + _sensor_status.rate_y = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_Z)); + _sensor_status.rate_z = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_X)); + _sensor_status.acc_x = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_Y)); + _sensor_status.acc_y = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_Z)); + _sensor_status.acc_z = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_Z)); +} + +bool SCH16T::ValidateSensorStatus() +{ + auto &s = _sensor_status; + uint16_t values[] = { s.summary, s.saturation, s.common, s.rate_common, s.rate_x, s.rate_y, s.rate_z, s.acc_x, s.acc_y, s.acc_z }; + + for (auto v : values) { + if (v != 0xFFFF) { + PX4_INFO("Sensor status failed"); + return false; + } + } + + return true; +} + +void SCH16T::SoftwareReset() +{ + RegisterWrite(CTRL_RESET, SPI_SOFT_RESET); +} + +uint64_t SCH16T::RegisterRead(uint8_t addr) +{ + uint64_t frame = {}; + frame |= uint64_t(addr) << 38; // Target address offset + frame |= uint64_t(1) << 35; // FrameType: SPI48BF + frame |= uint64_t(CalculateCRC8(frame)); + + return TransferSpiFrame(frame); +} + +// Non-data registers are the only writable ones and are 16 bit or less +void SCH16T::RegisterWrite(uint8_t addr, uint16_t value) +{ + uint64_t frame = {}; + frame |= uint64_t(1) << 37; // Write bit + frame |= uint64_t(addr) << 38; // Target address offset + frame |= uint64_t(1) << 35; // FrameType: SPI48BF + frame |= uint64_t(value) << 8; + frame |= uint64_t(CalculateCRC8(frame)); + + // We don't care about the return frame on a write + (void)TransferSpiFrame(frame); +} + +// The SPI protocol (SafeSPI) is 48bit out-of-frame. This means read return frames will be received on the next transfer. +uint64_t SCH16T::TransferSpiFrame(uint64_t frame) +{ + set_frequency(SPI_SPEED); + + uint16_t buf[3]; + + for (int index = 0; index < 3; index++) { + buf[3 - index - 1] = (frame >> (index << 4)) & 0xFFFF; + } + + transferhword(buf, buf, 3); + +#if defined(DEBUG_BUILD) + PX4_INFO("TransferSpiFrame: 0x%llx", frame); + + PX4_INFO("RECEIVED"); + + for (auto r : buf) { + PX4_INFO("%u", r); + } + +#endif + + uint64_t value = {}; + + for (int index = 0; index < 3; index++) { + value |= (uint64_t)buf[index] << ((3 - index - 1) << 4); + } + + return value; +} + +int SCH16T::DataReadyInterruptCallback(int irq, void *context, void *arg) +{ + static_cast(arg)->DataReady(); + return 0; +} + +void SCH16T::DataReady() +{ + _drdy_timestamp_sample.store(hrt_absolute_time()); + ScheduleNow(); +} + +bool SCH16T::DataReadyInterruptConfigure() +{ + // Setup data ready on falling edge + return px4_arch_gpiosetevent(_drdy_gpio, true, false, false, &DataReadyInterruptCallback, this) == 0; +} + +bool SCH16T::DataReadyInterruptDisable() +{ + return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0; +} + +uint8_t SCH16T::CalculateCRC8(uint64_t frame) +{ + uint64_t data = frame & 0xFFFFFFFFFF00LL; + uint8_t crc = 0xFF; + + for (int i = 47; i >= 0; i--) { + uint8_t data_bit = data >> i & 0x01; + crc = crc & 0x80 ? (uint8_t)((crc << 1) ^ 0x2F) ^ data_bit : (uint8_t)(crc << 1) | data_bit; + } + + return crc; +} diff --git a/src/drivers/imu/murata/sch16t/SCH16T.hpp b/src/drivers/imu/murata/sch16t/SCH16T.hpp new file mode 100644 index 000000000000..6e390d70b7d8 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/SCH16T.hpp @@ -0,0 +1,149 @@ +/**************************************************************************** + * + * 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 "Murata_SCH16T_registers.hpp" + +#include +#include +#include + +using namespace Murata_SCH16T; + +class SCH16T : public device::SPI, public I2CSPIDriver +{ +public: + SCH16T(const I2CSPIDriverConfig &config); + ~SCH16T() override; + + static void print_usage(); + + void RunImpl(); + + int init() override; + void print_status() override; + +private: + struct SensorData { + int32_t acc_x; + int32_t acc_y; + int32_t acc_z; + int32_t gyro_x; + int32_t gyro_y; + int32_t gyro_z; + int32_t temp; + }; + + struct SensorStatus { + uint16_t summary; + uint16_t saturation; + uint16_t common; + uint16_t rate_common; + uint16_t rate_x; + uint16_t rate_y; + uint16_t rate_z; + uint16_t acc_x; + uint16_t acc_y; + uint16_t acc_z; + }; + + struct RegisterConfig { + RegisterConfig(uint16_t a, uint16_t v) + : addr(a) + , value(v) + {}; + uint8_t addr; + uint16_t value; + }; + + int probe() override; + void exit_and_cleanup() override; + + bool ValidateSensorStatus(); + bool ValidateRegisterConfiguration(); + void Reset(); + void ResetSpi6(bool reset); + uint8_t CalculateCRC8(uint64_t frame); + + bool ReadData(SensorData *data); + void ReadStatusRegisters(); + + void Configure(); + void SoftwareReset(); + + void RegisterWrite(uint8_t addr, uint16_t value); + uint64_t RegisterRead(uint8_t addr); + uint64_t TransferSpiFrame(uint64_t frame); + + static int DataReadyInterruptCallback(int irq, void *context, void *arg); + void DataReady(); + bool DataReadyInterruptConfigure(); + bool DataReadyInterruptDisable(); +private: + PX4Accelerometer _px4_accel; + PX4Gyroscope _px4_gyro; + + SensorStatus _sensor_status{}; + + int _failure_count{0}; + + px4::atomic _drdy_timestamp_sample{0}; + const spi_drdy_gpio_t _drdy_gpio; + bool _hardware_reset_available{false}; + + enum class STATE : uint8_t { + RESET_INIT, + RESET_HARD, + CONFIGURE, + LOCK_CONFIGURATION, + VALIDATE, + READ, + } _state{STATE::RESET_INIT}; + + RegisterConfig _registers[6] = { + RegisterConfig(CTRL_FILT_RATE, FILTER_BYPASS), // Bypass filter + RegisterConfig(CTRL_FILT_ACC12, FILTER_BYPASS), // Bypass filter + RegisterConfig(CTRL_FILT_ACC3, FILTER_BYPASS), // Bypass filter + RegisterConfig(CTRL_RATE, RATE_300DPS_1475HZ), // +/- 300 deg/s, 1600 LSB/(deg/s) -- default, Decimation 8, 1475Hz + RegisterConfig(CTRL_ACC12, ACC12_8G_1475HZ), // +/- 80 m/s^2, 3200 LSB/(m/s^2) -- default, Decimation 8, 1475Hz + RegisterConfig(CTRL_ACC3, ACC3_26G) // +/- 260 m/s^2, 1600 LSB/(m/s^2) -- default + }; + + perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": reset")}; + perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")}; + perf_counter_t _perf_crc_bad{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": CRC8 bad"))}; + perf_counter_t _perf_frame_bad{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": Frame bad"))}; + perf_counter_t _drdy_missed_perf{nullptr}; + +}; diff --git a/src/drivers/imu/murata/sch16t/parameters.c b/src/drivers/imu/murata/sch16t/parameters.c new file mode 100644 index 000000000000..205b2f020e08 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/parameters.c @@ -0,0 +1,44 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * Murata SCH16T IMU (external SPI) + * + * @reboot_required true + * @min 0 + * @max 1 + * @group Sensors + * @value 0 Disabled + * @value 1 Enabled + */ +PARAM_DEFINE_INT32(SENS_EN_SCH16T, 0); diff --git a/src/drivers/imu/murata/sch16t/sch16t_main.cpp b/src/drivers/imu/murata/sch16t/sch16t_main.cpp new file mode 100644 index 000000000000..a5ae892c9973 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/sch16t_main.cpp @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * 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 "SCH16T.hpp" + +#include + +void SCH16T::print_usage() +{ + PRINT_MODULE_USAGE_NAME("sch16t", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("imu"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true); + PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +extern "C" int sch16t_main(int argc, char *argv[]) +{ + int ch; + using ThisDriver = SCH16T; + BusCLIArguments cli{false, true}; + cli.default_spi_frequency = SPI_SPEED; + cli.spi_mode = SPIDEV_MODE0; + + while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { + switch (ch) { + case 'R': + cli.rotation = (enum Rotation)atoi(cli.optArg()); + break; + } + } + + const char *verb = cli.optArg(); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_SCH16T); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; +} From 1c213fa76058b96d7b90b93cf63e88b83cd54ec3 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Sun, 19 May 2024 12:42:58 -0600 Subject: [PATCH 243/652] boards: arkv6x ark_pi6x change mavlink dialect to development --- boards/ark/fmu-v6x/default.px4board | 1 + boards/ark/pi6x/default.px4board | 1 + 2 files changed, 2 insertions(+) diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 168b17cdfaa9..1d1cc6f53d3f 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -60,6 +60,7 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 45f992d69eed..49de557ae4bd 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -39,6 +39,7 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y From 664a0f2cda1a5379c554fecef811ac127d9e0320 Mon Sep 17 00:00:00 2001 From: Konrad Date: Wed, 17 Apr 2024 13:42:25 +0200 Subject: [PATCH 244/652] HomePosition: Add minimum position change needed to be recognised as new home position --- src/modules/commander/HomePosition.cpp | 5 ++++- src/modules/commander/HomePosition.hpp | 2 ++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/HomePosition.cpp b/src/modules/commander/HomePosition.cpp index ea3955e27fe2..4aa341dbcf1c 100644 --- a/src/modules/commander/HomePosition.cpp +++ b/src/modules/commander/HomePosition.cpp @@ -34,6 +34,8 @@ #include "HomePosition.hpp" +#include + #include #include "commander_helper.h" @@ -83,7 +85,8 @@ bool HomePosition::hasMovedFromCurrentHomeLocation() } } - return (home_dist_xy > eph * 2.f) || (home_dist_z > epv * 2.f); + return (home_dist_xy > fmaxf(eph * 2.f, kMinHomePositionChangeEPH)) + || (home_dist_z > fmaxf(epv * 2.f, kMinHomePositionChangeEPV)); } bool HomePosition::setHomePosition(bool force) diff --git a/src/modules/commander/HomePosition.hpp b/src/modules/commander/HomePosition.hpp index 6346dac42e4f..07d6b1a63239 100644 --- a/src/modules/commander/HomePosition.hpp +++ b/src/modules/commander/HomePosition.hpp @@ -45,6 +45,8 @@ static constexpr int kHomePositionGPSRequiredFixType = 2; static constexpr float kHomePositionGPSRequiredEPH = 5.f; static constexpr float kHomePositionGPSRequiredEPV = 10.f; static constexpr float kHomePositionGPSRequiredEVH = 1.f; +static constexpr float kMinHomePositionChangeEPH = 1.f; +static constexpr float kMinHomePositionChangeEPV = 1.5f; class HomePosition { From 4a13e495d7b7dfc743314009e3a22d828260f49c Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Tue, 21 May 2024 19:49:40 -0600 Subject: [PATCH 245/652] boards: ark: pi6x: CONFIG_DRIVERS_CDCACM_AUTOSTART=y (#23163) --- boards/ark/fmu-v6x/default.px4board | 1 - boards/ark/pi6x/default.px4board | 1 + 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 1d1cc6f53d3f..3433f245acc1 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -15,7 +15,6 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 49de557ae4bd..7d381c9f0730 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y From 21e550fdba7a6af3990ef308851db0222fd25eb1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 20 Feb 2024 11:52:08 +1300 Subject: [PATCH 246/652] tools/bootloader: add force-erase option If the STM32H7 fails to program or erase a full chunk of 256 bytes, the ECC check will trigger a busfault when trying to read from it. To speed up erasing and optimize wear, we read before erasing to check if it actually needs erasing. That's when a busfault happens and the erase time outs. The workaround is to add an option to do a full erase without check. Credit goes to: https://github.com/ArduPilot/ardupilot/pull/22090 And the protocol option added to the bootloader is the same as for ArduPilot, so compatible. Signed-off-by: Julian Oes --- Tools/px_uploader.py | 25 ++++++++--- platforms/nuttx/src/bootloader/common/bl.c | 12 +++++- platforms/nuttx/src/bootloader/common/bl.h | 4 +- .../src/bootloader/nxp/imxrt_common/main.c | 42 +++++++++---------- .../src/bootloader/stm/stm32_common/main.c | 9 +--- 5 files changed, 56 insertions(+), 36 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index d479be314837..6328b914990d 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -195,6 +195,7 @@ class uploader(object): GET_CHIP = b'\x2c' # rev5+ , get chip version SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII + CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+ MAX_DES_LENGTH = 20 REBOOT = b'\x30' @@ -235,6 +236,7 @@ def __init__(self, portname, baudrate_bootloader, baudrate_flightstack): self.baudrate_bootloader = baudrate_bootloader self.baudrate_flightstack = baudrate_flightstack self.baudrate_flightstack_idx = -1 + self.force_erase = False def close(self): if self.port is not None: @@ -423,8 +425,14 @@ def __drawProgressBar(self, label, progress, maxVal): def __erase(self, label): print("Windowed mode: %s" % self.ackWindowedMode) print("\n", end='') - self.__send(uploader.CHIP_ERASE + - uploader.EOC) + + if self.force_erase: + print("Trying force erase of full chip...\n") + self.__send(uploader.CHIP_FULL_ERASE + + uploader.EOC) + else: + self.__send(uploader.CHIP_ERASE + + uploader.EOC) # erase is very slow, give it 30s deadline = _time() + 30.0 @@ -441,9 +449,14 @@ def __erase(self, label): if self.__trySync(): self.__drawProgressBar(label, 10.0, 10.0) + if self.force_erase: + print("\nForce erase done.\n") return - raise RuntimeError("timed out waiting for erase") + if self.force_erase: + raise RuntimeError("timed out waiting for erase, force erase is likely not supported by bootloader!") + else: + raise RuntimeError("timed out waiting for erase") # send a PROG_MULTI command to write a collection of bytes def __program_multi(self, data, windowMode): @@ -582,7 +595,8 @@ def identify(self): self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE) # upload the firmware - def upload(self, fw_list, force=False, boot_delay=None, boot_check=False): + def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False): + self.force_erase = force_erase # select correct binary found_suitable_firmware = False for file in fw_list: @@ -790,6 +804,7 @@ def main(): parser.add_argument('--baud-bootloader', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200) when communicating with bootloader, only required for true serial ports.") parser.add_argument('--baud-flightstack', action="store", default="57600", help="Comma-separated list of baud rate of the serial port (default is 57600) when communicating with flight stack (Mavlink or NSH), only required for true serial ports.") parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading') + parser.add_argument('--force-erase', action="store_true", help="Do not perform the blank check, always erase every sector of the application space") parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash') parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot') parser.add_argument('firmware', action="store", nargs='+', help="Firmware file(s)") @@ -907,7 +922,7 @@ def main(): try: # ok, we have a bootloader, try flashing it - up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay) + up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay, force_erase=args.force_erase) # if we made this far without raising exceptions, the upload was successful successful = True diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 61f3881d6f9e..e1dcfe8c5b8f 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -114,6 +114,7 @@ #define PROTO_RESERVED_0X37 0x37 // Reserved #define PROTO_RESERVED_0X38 0x38 // Reserved #define PROTO_RESERVED_0X39 0x39 // Reserved +#define PROTO_CHIP_FULL_ERASE 0x40 // Full erase, without any flash wear optimization #define PROTO_PROG_MULTI_MAX 64 // maximum PROG_MULTI size #define PROTO_READ_MULTI_MAX 255 // size of the size field @@ -649,6 +650,8 @@ bootloader(unsigned timeout) led_on(LED_ACTIVITY); + bool full_erase = false; + // handle the command byte switch (c) { @@ -728,6 +731,10 @@ bootloader(unsigned timeout) // success reply: INSYNC/OK // erase failure: INSYNC/FAILURE // + case PROTO_CHIP_FULL_ERASE: + full_erase = true; + + // Fallthrough case PROTO_CHIP_ERASE: /* expect EOC */ @@ -755,17 +762,18 @@ bootloader(unsigned timeout) arch_flash_unlock(); for (int i = 0; flash_func_sector_size(i) != 0; i++) { - flash_func_erase_sector(i); + flash_func_erase_sector(i, full_erase); } // disable the LED while verifying the erase led_set(LED_OFF); // verify the erase - for (address = 0; address < board_info.fw_size; address += 4) + for (address = 0; address < board_info.fw_size; address += 4) { if (flash_func_read_word(address) != 0xffffffff) { goto cmd_fail; } + } address = 0; SET_BL_STATE(STATE_PROTO_CHIP_ERASE); diff --git a/platforms/nuttx/src/bootloader/common/bl.h b/platforms/nuttx/src/bootloader/common/bl.h index 4115200db3bb..a39e7ce9086f 100644 --- a/platforms/nuttx/src/bootloader/common/bl.h +++ b/platforms/nuttx/src/bootloader/common/bl.h @@ -39,6 +39,8 @@ #pragma once +#include + /***************************************************************************** * Generic bootloader functions. */ @@ -105,7 +107,7 @@ extern void board_deinit(void); extern uint32_t board_get_devices(void); extern void clock_deinit(void); extern uint32_t flash_func_sector_size(unsigned sector); -extern void flash_func_erase_sector(unsigned sector); +extern void flash_func_erase_sector(unsigned sector, bool force); extern void flash_func_write_word(uintptr_t address, uint32_t word); extern uint32_t flash_func_read_word(uintptr_t address); extern uint32_t flash_func_read_otp(uintptr_t address); diff --git a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c index 1197427a942c..fd0578f885c0 100644 --- a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c +++ b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c @@ -395,6 +395,24 @@ flash_func_sector_size(unsigned sector) return 0; } +/* imxRT uses Flash lib, not up_progmem so let's stub it here */ +up_progmem_ispageerased(unsigned sector) +{ + const uint32_t bytes_per_sector = flash_func_sector_size(sector); + uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector)); + const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address); + + int blank = 0; /* Assume it is Bank */ + + for (uint32_t i = 0; i < uint32_per_sector; i++) { + if (address[i] != 0xffffffff) { + blank = -1; /* It is not blank */ + break; + } + } + + return blank; +} /*! * @name Configuration Option @@ -407,31 +425,15 @@ flash_func_sector_size(unsigned sector) * */ locate_code(".ramfunc") void -flash_func_erase_sector(unsigned sector) +flash_func_erase_sector(unsigned sector, bool force) { - if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) { return; } - /* blank-check the sector */ - const uint32_t bytes_per_sector = flash_func_sector_size(sector); - uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector)); - const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address); - bool blank = true; - - for (uint32_t i = 0; i < uint32_per_sector; i++) { - if (address[i] != 0xffffffff) { - blank = false; - break; - } - } + if (force || flash_func_is_sector_blank(sector) != 0) { + struct flexspi_nor_config_s *pConfig = &g_bootConfig; - - struct flexspi_nor_config_s *pConfig = &g_bootConfig; - - /* erase the sector if it failed the blank check */ - if (!blank) { uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE; irqstate_t flags; flags = enter_critical_section(); @@ -439,8 +441,6 @@ flash_func_erase_sector(unsigned sector) leave_critical_section(flags); UNUSED(status); } - - } void diff --git a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c index 859d861b2094..cccfd41bea4c 100644 --- a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c +++ b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c @@ -466,18 +466,13 @@ flash_func_sector_size(unsigned sector) } void -flash_func_erase_sector(unsigned sector) +flash_func_erase_sector(unsigned sector, bool force) { if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) { return; } - /* blank-check the sector */ - - bool blank = up_progmem_ispageerased(sector) == 0; - - /* erase the sector if it failed the blank check */ - if (!blank) { + if (force || (up_progmem_ispageerased(sector) != 0)) { up_progmem_eraseblock(sector); } } From 7c4507b6d6491aa446908495da20d964079295f3 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 10 May 2024 10:54:14 +1200 Subject: [PATCH 247/652] bootloader: add bootloader version This adds a new protocol extension which allows to get the bootloader version. The bootloader version is different from the bootloader protocol revision which has stabilized at 5 and is not easy to update unless a bootloader is actually breaking the protocol. The reason being that both the Python script as well as the uploader used in QGC will not attempt to load firmware if they don't know the bootloader version, so it could basically be considered a "breaking" protocol revision. Signed-off-by: Julian Oes --- CMakeLists.txt | 6 ++- Tools/px_uploader.py | 20 ++++++++- .../src/bootloader/common/CMakeLists.txt | 4 ++ platforms/nuttx/src/bootloader/common/bl.c | 43 ++++++++++++++++--- platforms/nuttx/src/bootloader/common/bl.h | 5 ++- platforms/nuttx/src/px4/common/CMakeLists.txt | 2 +- 6 files changed, 70 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 82771613c9ba..fc57b95efc79 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved. +# Copyright (c) 2017 - 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 @@ -132,7 +132,9 @@ list(GET VERSION_LIST 2 PX4_VERSION_PATCH) string(REPLACE "-" ";" PX4_VERSION_PATCH ${PX4_VERSION_PATCH}) list(GET PX4_VERSION_PATCH 0 PX4_VERSION_PATCH) -message(STATUS "PX4 version: ${PX4_GIT_TAG} (${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH})") +# # Capture only the hash part after 'g' +string(REGEX MATCH "g([a-f0-9]+)$" GIT_HASH "${PX4_GIT_TAG}") +set(PX4_GIT_HASH ${CMAKE_MATCH_1}) define_property(GLOBAL PROPERTY PX4_MODULE_LIBRARIES BRIEF_DOCS "PX4 module libs" diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index 6328b914990d..ce1b3cda5c0b 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 ############################################################################ # -# Copyright (c) 2012-2017 PX4 Development Team. All rights reserved. +# Copyright (c) 2012-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 @@ -195,6 +195,7 @@ class uploader(object): GET_CHIP = b'\x2c' # rev5+ , get chip version SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII + GET_VERSION = b'\x2f' # rev5+ , get chip description in ASCII CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+ MAX_DES_LENGTH = 20 @@ -206,6 +207,7 @@ class uploader(object): INFO_BOARD_ID = b'\x02' # board type INFO_BOARD_REV = b'\x03' # board revision INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes + BL_VERSION = b'\x07' # get bootloader version, e.g. major.minor.patch.githash (up to 20 chars) PROG_MULTI_MAX = 252 # protocol max is 255, must be multiple of 4 READ_MULTI_MAX = 252 # protocol max is 255 @@ -412,6 +414,18 @@ def __getCHIPDes(self): pieces = value.split(b",") return pieces + def __getVersion(self): + self.__send(uploader.GET_VERSION + uploader.EOC) + try: + length = self.__recv_int() + value = self.__recv(length) + self.__getSync() + except RuntimeError: + # Bootloader doesn't support version call + return "unknown" + pieces = value.split(b".") + return pieces + def __drawProgressBar(self, label, progress, maxVal): if maxVal < progress: progress = maxVal @@ -594,6 +608,8 @@ def identify(self): self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV) self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE) + self.version = self.__getVersion() + # upload the firmware def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False): self.force_erase = force_erase @@ -625,6 +641,8 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%) " % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent)) print() + print(f"Bootloader version: {self.version}") + # Make sure we are doing the right thing start = _time() if self.board_type != fw.property('board_id'): diff --git a/platforms/nuttx/src/bootloader/common/CMakeLists.txt b/platforms/nuttx/src/bootloader/common/CMakeLists.txt index 7ba4af38266d..e61fb88b8979 100644 --- a/platforms/nuttx/src/bootloader/common/CMakeLists.txt +++ b/platforms/nuttx/src/bootloader/common/CMakeLists.txt @@ -37,6 +37,10 @@ add_library(bootloader crypto.c ) +target_compile_definitions(bootloader + PRIVATE BOOTLOADER_VERSION="PX4BLv${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH}g${PX4_GIT_HASH}" +) + target_link_libraries(bootloader PRIVATE arch_bootloader diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index e1dcfe8c5b8f..4b4162d4b124 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -80,7 +80,7 @@ // RESET finalise flash programming, reset chip and starts application // -#define BL_PROTOCOL_VERSION 5 // The revision of the bootloader protocol +#define BL_PROTOCOL_REVISION 5 // The revision of the bootloader protocol //* Next revision needs to update // protocol bytes @@ -106,6 +106,7 @@ #define PROTO_GET_CHIP 0x2c // read chip version (MCU IDCODE) #define PROTO_SET_DELAY 0x2d // set minimum boot delay #define PROTO_GET_CHIP_DES 0x2e // read chip version In ASCII +#define PROTO_GET_VERSION 0x2f // read version #define PROTO_BOOT 0x30 // boot the application #define PROTO_DEBUG 0x31 // emit debug information - format not defined #define PROTO_SET_BAUD 0x33 // set baud rate on uart @@ -143,7 +144,8 @@ #define STATE_PROTO_GET_SN 0x40 // Have Seen read a word from UDID area ( Serial) at the given address #define STATE_PROTO_GET_CHIP 0x80 // Have Seen read chip version (MCU IDCODE) #define STATE_PROTO_GET_CHIP_DES 0x100 // Have Seen read chip version In ASCII -#define STATE_PROTO_BOOT 0x200 // Have Seen boot the application +#define STATE_PROTO_GET_VERSION 0x200 // Have Seen get version +#define STATE_PROTO_BOOT 0x400 // Have Seen boot the application #if defined(TARGET_HW_PX4_PIO_V1) #define STATE_ALLOWS_ERASE (STATE_PROTO_GET_SYNC) @@ -158,6 +160,18 @@ static uint8_t bl_type; static uint8_t last_input; +int get_version(int n, uint8_t *version_str) +{ + int len = strlen(BOOTLOADER_VERSION); + + if (len > n) { + len = n; + } + + strncpy((char *)version_str, BOOTLOADER_VERSION, n); + return len; +} + inline void cinit(void *config, uint8_t interface) { #if INTERFACE_USB @@ -258,7 +272,7 @@ inline void cout(uint8_t *buf, unsigned len) #endif -static const uint32_t bl_proto_rev = BL_PROTOCOL_VERSION; // value returned by PROTO_DEVICE_BL_REV +static const uint32_t bl_proto_rev = BL_PROTOCOL_REVISION; // value returned by PROTO_DEVICE_BL_REV static unsigned head, tail; static uint8_t rx_buf[256] USB_DATA_ALIGN; @@ -973,7 +987,7 @@ bootloader(unsigned timeout) // read the chip description // // command: GET_CHIP_DES/EOC - // reply: /INSYNC/OK + // reply: /INSYNC/OK case PROTO_GET_CHIP_DES: { uint8_t buffer[MAX_DES_LENGTH]; unsigned len = MAX_DES_LENGTH; @@ -990,6 +1004,25 @@ bootloader(unsigned timeout) } break; + // read the bootloader version (not to be confused with protocol revision) + // + // command: GET_VERSION/EOC + // reply: /INSYNC/OK + case PROTO_GET_VERSION: { + uint8_t buffer[MAX_VERSION_LENGTH]; + + // expect EOC + if (!wait_for_eoc(2)) { + goto cmd_bad; + } + + int len = get_version(sizeof(buffer), buffer); + cout_word(len); + cout(buffer, len); + SET_BL_STATE(STATE_PROTO_GET_VERSION); + } + break; + #ifdef BOOT_DELAY_ADDRESS case PROTO_SET_DELAY: { @@ -1107,4 +1140,4 @@ bootloader(unsigned timeout) continue; #endif } -} +} \ No newline at end of file diff --git a/platforms/nuttx/src/bootloader/common/bl.h b/platforms/nuttx/src/bootloader/common/bl.h index a39e7ce9086f..377164a28ec9 100644 --- a/platforms/nuttx/src/bootloader/common/bl.h +++ b/platforms/nuttx/src/bootloader/common/bl.h @@ -96,6 +96,7 @@ extern int buf_get(void); #endif #define MAX_DES_LENGTH 20 +#define MAX_VERSION_LENGTH 32 #define arraySize(a) (sizeof((a))/sizeof(((a)[0]))) extern void led_on(unsigned led); @@ -123,6 +124,8 @@ extern uint32_t get_mcu_id(void); int get_mcu_desc(int max, uint8_t *revstr); extern int check_silicon(void); +int get_version(int max, uint8_t *version_str); + /***************************************************************************** * Interface in/output. */ @@ -135,4 +138,4 @@ extern void cout(uint8_t *buf, unsigned len); #if !defined(APP_VECTOR_OFFSET) # define APP_VECTOR_OFFSET 0 #endif -#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t)) +#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t)) \ No newline at end of file diff --git a/platforms/nuttx/src/px4/common/CMakeLists.txt b/platforms/nuttx/src/px4/common/CMakeLists.txt index c74810b03a88..f6c25c26f320 100644 --- a/platforms/nuttx/src/px4/common/CMakeLists.txt +++ b/platforms/nuttx/src/px4/common/CMakeLists.txt @@ -83,4 +83,4 @@ add_subdirectory(srgbled) if (DEFINED PX4_CRYPTO) add_library(px4_random nuttx_random.c) target_link_libraries(px4_random PRIVATE nuttx_crypto) -endif() +endif() \ No newline at end of file From 8fe8f2fcb3e522e06a7ca4b21be3b5067c1b5b90 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 10 May 2024 12:25:01 +1200 Subject: [PATCH 248/652] px_uploader.py: clean up various tidbits Includes: - Remove some of the outdated Python2 checks and compatibility. - Try not catch all exceptions but only the expected ones. Otherwise, this makes it really hard to debug if anything unexpected actually goes wrong. - Make use of fstrings. - Make output slightly prettier. Signed-off-by: Julian Oes --- Tools/px_uploader.py | 86 +++++++++++++++++++++----------------------- 1 file changed, 40 insertions(+), 46 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index ce1b3cda5c0b..b46ea178cf2d 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -50,9 +50,6 @@ # Currently only used for informational purposes. # -# for python2.7 compatibility -from __future__ import print_function - import sys import argparse import binascii @@ -70,35 +67,32 @@ try: import serial except ImportError as e: - print("Failed to import serial: " + str(e)) + print(f"Failed to import serial: {e}") print("") print("You may need to install it using:") - print(" pip3 install --user pyserial") + print(" python -m pip install pyserial") print("") sys.exit(1) -# Define time to use time.time() by default -def _time(): - return time.time() - # Detect python version if sys.version_info[0] < 3: - runningPython3 = False -else: - runningPython3 = True - if sys.version_info[1] >=3: - # redefine to use monotonic time when available - def _time(): - try: - return time.monotonic() - except Exception: - return time.time() + raise RuntimeError("Python 2 is not supported. Please try again using Python 3.") + sys.exit(1) + + +# Use monotonic time where available +def _time(): + try: + return time.monotonic() + except Exception: + return time.time() class FirmwareNotSuitableException(Exception): def __init__(self, message): super(FirmwareNotSuitableException, self).__init__(message) + class firmware(object): '''Loads a firmware file''' @@ -163,13 +157,13 @@ def __crc32(self, bytes, state): def crc(self, padlen): state = self.__crc32(self.image, int(0)) - for i in range(len(self.image), (padlen - 1), 4): + for _ in range(len(self.image), (padlen - 1), 4): state = self.__crc32(self.crcpad, state) return state -class uploader(object): - '''Uploads a firmware file to the PX FMU bootloader''' +class uploader: + '''Uploads a firmware file to the PX4 bootloader''' # protocol bytes INSYNC = b'\x12' @@ -361,19 +355,22 @@ def __determineInterface(self): self.port.baudrate = self.baudrate_bootloader * 2.33 except NotImplementedError as e: # This error can occur because pySerial on Windows does not support odd baudrates - print(str(e) + " -> could not check for FTDI device, assuming USB connection") + print(f"{e} -> could not check for FTDI device, assuming USB connection") return self.__send(uploader.GET_SYNC + uploader.EOC) try: self.__getSync(False) - except: + except RuntimeError: # if it fails we are on a real serial port - only leave this enabled on Windows if sys.platform.startswith('win'): self.ackWindowedMode = True finally: - self.port.baudrate = self.baudrate_bootloader + try: + self.port.baudrate = self.baudrate_bootloader + except Exception: + pass # send the GET_DEVICE command and wait for an info parameter def __getInfo(self, param): @@ -423,8 +420,7 @@ def __getVersion(self): except RuntimeError: # Bootloader doesn't support version call return "unknown" - pieces = value.split(b".") - return pieces + return value.decode() def __drawProgressBar(self, label, progress, maxVal): if maxVal < progress: @@ -437,7 +433,7 @@ def __drawProgressBar(self, label, progress, maxVal): # send the CHIP_ERASE command and wait for the bootloader to become ready def __erase(self, label): - print("Windowed mode: %s" % self.ackWindowedMode) + print(f"Windowed mode: {self.ackWindowedMode}") print("\n", end='') if self.force_erase: @@ -672,14 +668,14 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ self.otp_coa = self.otp[32:160] # show user: try: - print("sn: ", end='') + print("Sn: ", end='') for byte in range(0, 12, 4): x = self.__getSN(byte) x = x[::-1] # reverse the bytes self.sn = self.sn + x print(binascii.hexlify(x).decode('Latin-1'), end='') # show user print('') - print("chip: %08x" % self.__getCHIP()) + print("Chip: %08x" % self.__getCHIP()) otp_id = self.otp_id.decode('Latin-1') if ("PX4" in otp_id): @@ -689,17 +685,19 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1')) print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1')) - except Exception: + except Exception as e: # ignore bad character encodings + print(f"Exception ignored: {e}") pass # Silicon errata check was added in v5 if (self.bl_rev >= 5): des = self.__getCHIPDes() if (len(des) == 2): - print("family: %s" % des[0]) - print("revision: %s" % des[1]) - print("flash: %d bytes" % self.fw_maxsize) + family, revision = des + print(f"Family: {family.decode()}") + print(f"Revision: {revision.decode()}") + print(f"Flash: {self.fw_maxsize} bytes") # Prevent uploads where the maximum image size of the board config is smaller than the flash # of the board. This is a hint the user chose the wrong config and will lack features @@ -710,8 +708,7 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ # https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144 if self.fw_maxsize > fw.property('image_maxsize') and not force: - raise RuntimeError("Board can accept larger flash images (%u bytes) than board config (%u bytes). Please use the correct board configuration to avoid lacking critical functionality." - % (self.fw_maxsize, fw.property('image_maxsize'))) + raise RuntimeError(f"Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes). Please use the correct board configuration to avoid lacking critical functionality.") else: # If we're still on bootloader v4 on a Pixhawk, we don't know if we # have the silicon errata and therefore need to flash px4_fmu-v2 @@ -812,10 +809,6 @@ def send_reboot(self, use_protocol_splitter_format=False): def main(): - # Python2 is EOL - if not runningPython3: - raise RuntimeError("Python 2 is not supported. Please try again using Python 3.") - # Parse commandline arguments parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.") parser.add_argument('--port', action="store", required=True, help="Comma-separated list of serial port(s) to which the FMU may be attached") @@ -900,9 +893,10 @@ def main(): # Windows, don't open POSIX ports if "/" not in port: up = uploader(port, args.baud_bootloader, baud_flightstack) - except Exception: + except Exception as e: # open failed, rate-limit our attempts time.sleep(0.05) + print(f"Exception ignored: {e}") # and loop to the next port continue @@ -917,10 +911,10 @@ def main(): up.identify() found_bootloader = True print() - print("Found board id: %s,%s bootloader version: %s on %s" % (up.board_type, up.board_rev, up.bl_rev, port)) + print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}") break - except Exception: + except RuntimeError or serial.SerialException: if not up.send_reboot(args.use_protocol_splitter_format): break @@ -945,9 +939,9 @@ def main(): # if we made this far without raising exceptions, the upload was successful successful = True - except RuntimeError as ex: + except RuntimeError as e: # print the error - print("\nERROR: %s" % ex.args) + print(f"\n\nError: {e}") except FirmwareNotSuitableException: unsuitable_board = True @@ -986,4 +980,4 @@ def main(): if __name__ == '__main__': main() -# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 +# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 \ No newline at end of file From 6ebb2b33dfcb2fc8dd6cfd6e900f1a6618245980 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 May 2024 15:18:44 +1200 Subject: [PATCH 249/652] bootloader: track ArduPilot protocol Just so we don't conflict on these commands in the future. --- platforms/nuttx/src/bootloader/common/bl.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 4b4162d4b124..65f1e0f0417d 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -111,8 +111,12 @@ #define PROTO_DEBUG 0x31 // emit debug information - format not defined #define PROTO_SET_BAUD 0x33 // set baud rate on uart -#define PROTO_RESERVED_0X36 0x36 // Reserved -#define PROTO_RESERVED_0X37 0x37 // Reserved +// Reserved for external flash programming +// #define PROTO_EXTF_ERASE 0x34 // Erase sectors from external flash +// #define PROTO_EXTF_PROG_MULTI 0x35 // write bytes at external flash program address and increment +// #define PROTO_EXTF_READ_MULTI 0x36 // read bytes at address and increment +// #define PROTO_EXTF_GET_CRC 0x37 // compute & return a CRC of data in external flash + #define PROTO_RESERVED_0X38 0x38 // Reserved #define PROTO_RESERVED_0X39 0x39 // Reserved #define PROTO_CHIP_FULL_ERASE 0x40 // Full erase, without any flash wear optimization From e4fd80b6ef0993fa9a7ad73308dc5c9c55b14a2f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 May 2024 15:19:12 +1200 Subject: [PATCH 250/652] bootloader: remove unused/duplicate defines --- platforms/nuttx/src/bootloader/common/bl.c | 7 ------- 1 file changed, 7 deletions(-) diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 65f1e0f0417d..1b86adbde350 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -131,13 +131,6 @@ #define PROTO_DEVICE_FW_SIZE 4 // size of flashable area #define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10 -#define STATE_PROTO_OK 0x10 // INSYNC/OK - 'ok' response -#define STATE_PROTO_FAILED 0x11 // INSYNC/FAILED - 'fail' response -#define STATE_PROTO_INVALID 0x13 // INSYNC/INVALID - 'invalid' response for bad commands -#define STATE_PROTO_BAD_SILICON_REV 0x14 // On the F4 series there is an issue with < Rev 3 silicon -#define STATE_PROTO_RESERVED_0X15 0x15 // Reserved - - // State #define STATE_PROTO_GET_SYNC 0x1 // Have Seen NOP for re-establishing sync #define STATE_PROTO_GET_DEVICE 0x2 // Have Seen get device ID bytes From 5bace785e02d3ce3fa151676f6b175e3a2acb670 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 May 2024 15:41:12 +1200 Subject: [PATCH 251/652] px_uploader: catch serial exception correctly Signed-off-by: Julian Oes --- Tools/px_uploader.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index b46ea178cf2d..0ab3a6ff258d 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -914,7 +914,7 @@ def main(): print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}") break - except RuntimeError or serial.SerialException: + except (RuntimeError, serial.SerialException): if not up.send_reboot(args.use_protocol_splitter_format): break @@ -980,4 +980,4 @@ def main(): if __name__ == '__main__': main() -# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 \ No newline at end of file +# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 From a9962dc44dabf7c35fd0364b45bb9ece672d9068 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 10 May 2024 13:29:12 +1200 Subject: [PATCH 252/652] boards: update all bootloaders --- .../fmu-v6x/extras/ark_fmu-v6x_bootloader.bin | Bin 46204 -> 46360 bytes .../cuav/nora/extras/cuav_nora_bootloader.bin | Bin 43248 -> 43264 bytes .../x7pro/extras/cuav_x7pro_bootloader.bin | Bin 43248 -> 43264 bytes .../cubepilot_cubeorange_bootloader.bin | Bin 43176 -> 43200 bytes .../extras/holybro_durandal-v1_bootloader.bin | Bin 43260 -> 43284 bytes .../extras/holybro_kakuteh7_bootloader.bin | Bin 41868 -> 41876 bytes .../extras/matek_h743-mini_bootloader.bin | Bin 42640 -> 42672 bytes .../extras/matek_h743-slim_bootloader.bin | Bin 43224 -> 43264 bytes .../h743/extras/matek_h743_bootloader.bin | Bin 42640 -> 42672 bytes .../fc-v2/extras/modalai_fc-v2_bootloader.bin | Bin 43252 -> 43284 bytes .../mro_ctrl-zero-classic_bootloader.bin | Bin 43204 -> 43244 bytes .../mro_ctrl-zero-h7-oem_bootloader.bin | Bin 43200 -> 43232 bytes .../extras/mro_ctrl-zero-h7_bootloader.bin | Bin 43180 -> 43212 bytes .../extras/mro_pixracerpro_bootloader.bin | Bin 43180 -> 43196 bytes .../fmu-v6c/extras/px4_fmu-v6c_bootloader.bin | Bin 46040 -> 46100 bytes .../fmu-v6u/extras/px4_fmu-v6u_bootloader.bin | Bin 43232 -> 43264 bytes .../fmu-v6x/extras/px4_fmu-v6x_bootloader.bin | Bin 46688 -> 46764 bytes 17 files changed, 0 insertions(+), 0 deletions(-) diff --git a/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin b/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin index f4ec9666cc17bc27660ae6490a108594c5085fa5..62ef9238b1061e35a5c6535077ed20491e59bab0 100755 GIT binary patch delta 8641 zcmb7pd0Z67ws2MV%+PEyfXEIr3?qXhI&6wD=&&^)Cg2WH!x%M=3Q9CavfKx_8)H;T zuPFMi32HFW2#nk(F^DFb#N_4%3|<%FRi81V(Zoj4?pgagJ(#@r$M?^h-|x(+uCw&1 zQ>Ustd!H*GxR8{#%&9Im&`CQJ$ zk=_1TV{hBj3svj{lZ^XbNG-xg%xvn5Q6@^Gufklh^ZGr6X|B^P)1;bG%~+pz-C(Xo zG9$l)Prk;bQQWiL>pow5SNWja+X)uQY~U9C-sIY^!W z^9d3ja2$7$3jwR~5t5~xhJPTtl;>J1TF|upmeohc|Y*nYMe@S!247@ zp3V1|R1`PYEn`b1s+>v)eKBE`iVaJXIPQptfWrtJlb>-Id?( zB*li}FG*hP3wRMBvFStF#hV?B3xx?P{Ge_6n8*e2h*nO2m`$ri5Qzo zO%_Q@@Tdfe+YJ%-xgUx@2awS&V^RNPxeg4OEtYi1`lox^GstF@);C+!b*R#$Awzhm zX5p_$pn5dENwU-v@n1-tIx%3j_*PT!Nm(*%~x`@-5bl;J`_8^s9 zij1{4VPZ1cu!?RmbOwMK$>fFMp-JU73{h2>?FButu3xMQ zz>zK$``=d7bysrsQN+v!*Z^>z>=+)3H<2U56DV}da&h=)7%+KXH^v(sLk!cd;9AM| zy0J?N-7+p8AkXbz6lMuPis#!EY~Txc$7r*H3v}W=;D1)+hk;hm*Q($mon%=ei+R$X zSccyr0V76ha$SfkaZ0K%H=*kQY@82IAN%)(G-(=rCTl^_2V~xe@%U}Bf5cKM#9{H# z2VuO)5h&=p6mEgI0#zp4rPamm2odP z{)mjK_Pk{f(Ze^iT#`6yxEqec3oZ%U4fu%Ep-aW2X(>fC6>{QL^!+`04C2}xsq6?= zR_GDnIvk3YDwt%WED&{$LdCrL8D*6 z*<{t|!m>>JIbj{r!St+g_gdEp|DpU9_O=jo#Hwu1UA9x$gk1b7CyJ9=fvmLlUHq0V z@j(U*UQsxL-R0p}Bg)vYj=}ax*u643_mB`nVv;l+PWvCz5f%~Fg;mNEHC>O^leuK zn>Cz29c=0qb|R6lck~JkfZqqa4>7GGzZqK1hH2nE$%aypk?;_^6aYsJy}|(xO`6zA zK$9>cjmi4N%%Z*7vYukDHhX-5i?0Kkr2jR*lKx7-gZjD!+1x28{v zmL!!Ya;l@^Y0itHi)0Qeb*>;QYBY!CzeChxB17H*DWJyzot~D1C;eC|QKpOu#qU@a zkNJf1IckHWs8f7U)h;Clmb7s!#wFzK=hS$jW&d+}jE`6@j9*IQ$CmVozBu_cBVzPf zh^Yg-_8C@ZBWB?M!lfq@lB9R^&-ZR-jtmS&5& zD8FpM6p7hvlRNH<*Qr$~&d)&&jY@raLHI&hf3 zw`MWY<360p_h=U9aG2K2n^`nta@^vJUicCoZ||X1NbBJDxSN(LhN^M~YEvzb3d3+L z+l7o&sqaw+`2qNR>Wx|;xKx2Cekb6oB(Z1_{s-An)QJN~@#He!u_Ds>_36M%7l~!E z7B^Y0PVU40Ke-1pQl{O(vzD_jhF~}nFBix9jt_@O&~jR&W4x}3`~$*I)o7;+ns>2&2uvQ(k!Fpg^R~&!*MjMCFi;5w zenTcsiwtabVFTTL+l+yp(FyM(OQ$7!kDZ2?(EvY^L(^8{6cRl>2ltYB)5j0l)QT7h z;64GEd^~*=erUNmU4!vl;+iqrx4F)TyFpLW8@UT){!Fzz%~{Jfkj*m_a4Kn?xf!3d zjGy%Z_U`=@G5-MQCU;5`a3=9DORP!m*)PN!t}2o)ecO+GlGJ*$j%~;{s6XrX4$%HI z_#_*nH~aJ(@P}5sSI6QplkzrodG}{fQf9of%b;G8TW;TM+td{#1V=UGe{H>~z`c0P zSJqK#NcYAxJDc0-LS{YclgzR`J5uYQcUWyIf-}{QZ@sdV9qs#dCOfoncKdY>Mu5vNil#~fkys>k39k>BFHNOsIl4L*5?(Oj_Rve{M*`z<>Q z{%4TOvnNi8>(-kM9@`@ZYKxUUc+6S$gS^C_n(xcdfxMGlNTtY~dgBO4ZdK*`KXhj}&youXMl-vT#m<<{#GiF+)Dqu~Y49AN|y(HwOt} z;M)tIo?OI=AM_yIA4MIyc`pLTSWZ^zcRLjMfH1FpE#sp z1pFP%T_#yC7yC3HN6bwK1JiM`_hlnaCVej_WKg-{Hez zw#rO#AG&2RcdtFNN@w<2n*nCvML}AR5~q~j{fm^BC*yLmqg)+)9w-CXz6Vb|$ErQj z<>Y*MtTx^CcyUqg<9WY(7NMcT&71#t8zf{oiyy#Jm+AO%dK@ts~>S9=`@An8gj`L8}rbCbWi)JA{_U- zH6$3tM}@)Z)Xq#c!3{f5AVKq%1W$3KR%5-qClPjp&bw8h;3U~LPd{45MG7=$6-9oP zNOS!F?V^-|j1VL~r4iDVlaN6oiV;Q3q>+2`k{}BWeMMVyv}juk(t5EsgqAhYRrIba z0s|M#cf}jRi4Ox>zZFmwQ0l>HW4;xblFb4t!73TILP%)6CLjaSBW}?eq!RfoQMO&y zi1d&8B>GfA)~FsItG{~%e>hdpaHuO}J{)`i0SgdQ{>qIm@}gT3r|272nYz5-sptPO{J&hlS);T% zR+dh46{1Y7*sf?6`Md6sNdrB1tXM1QKJU?eu8wY`Ihv;R#v1N)9o7_c$d^)qa}7|w zfXRy%OX03PO3G4CdHSJl@|g%zV`$1&U!fZzC*fo?@Ed6Y(_(ynQgC%}$Hbz@>foxZ zM?o~DRy3o8V?r35C(Z5zE7G2^ma>VgZ$I{>IY#^eVwL71L~N)ra#QMLX+72yux_5m z3vbkga5QD)R@CXk;gw2AM;=wwwLht?L66LJH-vpHW$een6w-%*XAD04(XBn#L$zil8?W?hk``j;D#t^K)N%Ja_Ru@!8LoafPHbwzpQ-% zQc6~R3kNODeea$v$n@K@jT{B$U9n2e(|KN&P=~amS>sJOU9opA9*-x z>5U$absmnjwTdG{VMKbUugKK$?Q#e?;!0$t(Ay^Q57e$)?%}Th{-xcjxXi*(t)kh@ ze+7DBSi402Z4ZBq$glPYpp~FX{ClM6RWwuTL59(;1*!n4KvFF78#|>%6G=zvy?c^b1Y_Oc?$0NNh3SxnSBZS<1HNyLx&A(7(qPcEDFVYSZJ2E=Y zLD3-%LdFlm$pF|%kqL{2QGjMH8Zq}r8;~_Nz97h31sx`l8TDTWwUM znl-bUfs-q9I0H=)H~*b$2_%F%GtI4q!;1kYR2kj;x{l(3TWRta`e04nf@OiaB-FETNUvpV?6n2iZr);-Jv%LFE|~P27e@UKw=|{` zX^IE>R#1f$RAzqv40XkW((o3tV(|goMuL}2!JEm#C9AQXTwijF`pHhtES)JGAr<*} z2`R5w>i-`$4BJ2TlWMVpA4M)#MB^;-q(YBp6Ln>5yqy=s0@lvw+y8s3=KTUTs4cQ> zZ+1-AN*ExfqjT*1U6CxPG|24yKSk0|nH~I3n=B@x?|wDSiFk{p1Z11YZi zsc@5YkIP5>Dn`Z*VU0k|A^pp;V7#fzHCRbzEw5SN;(rnctCb_6D)6so?J#I}izqIG zmGws{0$CS-0iF!3)H?T!CkA*SfiJn5s`af>LLG&gs_Zed|TAO!L7K8$7`w#V6EEHzoMAJ z49QxRPhGZ?cUP6*H%Q;AN~l{GzVQ+D#6}*y@gd%0*|pjiQ#b77!|D{D_Em_vT!WZ# zb>!dGzu?Q3^KXh6uO;W-UXAle<~v35kL*XRKa#EQ+`+>vEB}%};a5mw%|jeRw$v_y z`^w|mv3N1j*J-E$Cn>3m1F4mD%gsO7rRa0>H(~#mO24oI_y*^v);YNMYTm4Ap#^}%ykm^bIE5-=kIfcj5b+7=t{K#t?L#Z1! z^6thla058IaTest;hWatg=GJx-3n=`D_hBPoBtC&4_w{c33ly%HwOqyR) z#kiOp+p;)1!Zx_XrOHI>ldKx1{Y$gFr_8JbA6App_g=tdr0%^V!`v`eRh?kFf#A`d8ye@lmEuz z)t}~5!V3H}n>>bw;BoN7-T$^;7F5Z!CCXI7el4i71U?SZQ76CO^5p%c7|$p3wok#& z5zF@Ez#=FZA(d1;R=~$38!Y1|+mm4#C+s*B^MlRCmkW}Yc>W{s&s8mAs-Q~l$MSr! zDAil)>xU*5ijZb^qLGiURVUQDCy<$V64^x(A%40@5qv@N-8njOj>}*yw{H^g_5-cBndkS47*ckg z&lRIvbIf|vTJutq;!U16k@-6_lNLKQ((y5=0A9BXCPksP@ga8Ui4k`SbCgIEo7l7< z@Ja@Fw~c(iGm>)H$gewN!sqUk3eGY%FHBXweyJsF)i&BlLC)VmVALO&1caPTKd z@vhM5QpZez+4o(Z-xb-#mmn21LKGhs(f~X7Wn}HH9Z(z$`DGAav1r_r=bf|{F|IvQ4dULONO>hZ z{Ybp`Rt8o%vBAMlgU?#ZR=mf-=UO)IZNd>&rz}R%H-b%OaRcN?&la$Qw+ke9U#Wiv zY)aCX7(W>2EX$F7Ub31VJLKo{^Pmi0nFS5L zLg-C_4B%-G`R0Rf!2dfw)Zh-%{-N|`>C%U>q1)`W97bo`6!5W(fe7ExAukYMsrxn+ zr@mzy1?|gQTYKULzelG3#7$!{c&N=_eTSd@~UoSvTiO6tNiM9jzIQw}W#d4NGn z5IXj(y|Mx^nJW>~u>{_~Y>6pY2FXv7kvbJIS@3aiE8rOb>j5Mt>G%Jmk^UB~?_-{J6{cWx$lo}f4`dQ?W*ps zuCA`GuCDos>b_6at)m0pr%@t8C{d`hZ>1-xF>8O|zl#pzjv^Lul?6!4@>nQ2s}cs0 z?ZMe29=V4Var_@FjPMUB!;Ftu`HUB1ER@briG||s+Yb)lG%M5 zv4cc~%?Q5ZWjZ)M(c0;xg}Y=;SPI@uPK2f7cJh5#1fEV@VLCjP#D=HgVZDRxXsqkq7EktUyJ!owYxX;Sb&mVOrV?JYl@=zFP5mQqI62h66tl$BKM9+OHX;QNw3{Qc zG5(Njj9dxR42&9v4J12iN?^LTkY6jkZ=!`nawsZ2B+$$7b$LZR&MblHb`WP&G8Rb4 zfTYCR-PJta!SVi`*q;^}y2s{Sb1oKMMs4s7MAx0ApCXpn#zd0J0cCg#xjaBiVGsFv z!2V%j62qUXN5V*tDvr4Y$`{4^BW@rZWJcBwC0gm!k87 z=k-u@9;MAW5)rcyuP19_oVXuZ80)}=#1Qw%>_t8mUs#ViEq^?c;8bl{cb6FFjw zg`F~p93Ppfa5&`yz+nQ87oTyMR47^VV)7D>*Yt4w^LLKXBrQGy zUn2SOMEEDsu+w;3nhi zBvd;DPbJyfF);sXZA!>I`IiR8VmLkvdYwv|w9$A0Y13*A*)q;#hXtno)PgvbVi>EZ z!n$NNs`xArsim9YjrEG2DM29Ggm}f+6UCDvMt-FnyZiL(Uc$s!|?lJO}rBWZlX?QXZT1H6ICOjT(bOQoS2 z1~hQL8|ie*l+D_4lw40*6rAhD99?I0gn$^M$+&?LX(=uYW>u8q2Q>!ok4`n|^B(Y)5o>G=6&D0~BH9}<;uu^T09lh&co9;JB2 zZOvJr6m`)c{zItsitoz|AKBDf{tLLCEXNv>VoXU>L|}gxA#y-uGv+i7P2*PSq%oY& zsMo*5y0mx$B2 zxV+U3dg8*YIw6=2v$RUvkSy+ov1$O<0N#z*dRZh;I%X`b?^VYfXrst9z^zQa&e$sL z>7gmhItgeB4k9Pg4F$R8ojFWPv0%%|F7%2UfTr~SCSaxiWq^D8e;rDjxowh7Q)<<9 ztt|Dg&+S5`r4~J})MpUwP%SPaxkI&8hwEYWRY;iaQryTzWp&};zUo6-1$%tJk8D6; zjb3pC^m+_M+L18U1@%UhgpVX&d5@^AXF3rU+d{Y)#U?by(M_`+M?(k13eAFH~axMlpx$HSD9&O+8oB`uQ_DiGY z)40=~J|+;SFEt@{NH${E0ABkHC*>fv;u*XKcoRS{&=uHdUug2D!Pzd$O~#0Pk~|6VyEUuT=nv1)- zUPszU;5zPlr-Ch{T&~(C ztuW;Y8fHP|-y3lHDru@|j!?z;rL2+)O$(MUeu9CrPkN#9ZVO6?Nj6m_wKQCi5@%kJ zj5sD^wZw(4mV!e4JQT)5w@9P2{RSybs-aXX^%;L38qF$N%5{rp+(=K~a@?0pvY6gH zeXLD4eO#^Ot~FOM(RVF0=MfM4bQQ>e+wo|z1?zM(Cz&UXO{lo;huiQdcMHv-B#-!! zPhH$)%LwP}zZON}_`GIhqRIk~u_y>2;4^=edK^N;P?V?ve48Yh=Rwr5(d>Zp(LA<1 zaF~qrLG60b(lv5oY!cpUZyVc=gKznIBTTl@Bj(v1FZRQRKl(Te;*`@GUD-KmOil_N9Dwz&Z?D>)tcno=Md>GzD){I{mcL&B) zCeFgdCw$2|vKny$_;qcjQ5Gd1(M-sKL!fBFs3|ME?>aRw0LOd8HfZE-*EqVxlMc2K zX^RCp11GRXT%Bu?K~w+jvdh6bDxno4q)RIPuC*qo?=_~ARU4s~2APiYyCsW1kUJA} z1%hb7+PgHKnhY?n(kj*ir4~xyJTbOGCYu|Cg$Q2QZ#W?pZj%)RRC@gfXUX0 zgYiTA`H4D=%gMc$rUV|W4iN6pr3RDmH)5WoRT;Z&{72-qNy&H!*)eH7K55rY-i!T9 zK0|CFz*us%EE!_q-^x;AhqQbwB^qz44Q*FCQ9zp3VAb^tTk-I(oP)suQp0NsE;tR^RwqtB+8GdVx#1hK zrCb})_#+-;uyVjrQ*bJO|3g3Z({CO*yU68oo!_z+`)}OhS>#FinB?;|_E-S8JS1ee znCO2uM0MG!@HQlTVM`HkKwf^l`#rbqv7MB^9IrZV>vJ@LRK1*nFOVZI$4C6Rb(U&( zn@;sov+2pXbbwIQU}_-b&db#p0){Ek^atH-q-sh=*qM8*?y@tF&vokfD|{JzCy`52 z#uRI>8LY-083%OPibGoP@bmoMeEoNaA2Mi9{;6ifsq^yA;9YTf%kS;s|KJ?Zg=VNb zDYd~G-dv_#-qZ4)GyAcc9`F+#(m`IDnykC(oE_KasGgtTUj6vH27|S)6d6-faK+iH z4g7pfK@Rz3YC2eW%hVZo8%dvbiJ^rHGI39fi`pflPGe9xU&5oUJNSSEq+=!gH7#r+ z>C=k?xD$vigN3~D8F_EI3GP*2Pfy3+67Te=kym7Y9c=-F%#7?Ptr*o5z+=ABN(pm( zOx*ojkDbbaeaU46J-;X+eef-XQ;ExNk>VNY5Ij`R(1u+GO4qHcpr_|}ZBJ`0X`B(C zl;(X>Va|Ip^VgouWo+_^v;H$0L?F2pPvE$Ig}7#<`7d&HI63I`RWigf3Lhf#EwM?H zPARutDh0P7L3alC;MHd;3t&?U`5t9g!*!D!w?yD)`OSMNdkr|py(C;aN{7lsmJ zBEc6mvSTe4TDU9|YUZn9VV;cT*q~}jft~KSUkM$&L8@jNhS0({GA(=}%i>bNM*tQ= z#6}B0z_&Lj+0ncjsAkJ}YG zE77~Oqcn#5H}Jj*l1@O)4`v}&2ADS+v5NsegDTebtYZ5d#J)5av8w?t0EE5*jsdX3 z_$HK_fscZLbl~2Q;H;*0z@-ioWBlVzes@pE{NA6ZpPWC^%!1^gJ_+7ECguRc%%smPNIk zn%32FS%Z}6W;I1Izn0!`E4f%a8n9ZI4&(2bE6-Ur?P=F@}j)evE_XL{-pEo_!S zv&Pz-*c;R?h!zBf27VJ&ML?~lDKCUA4{Mrkj$R&CnfoiDvKe9`0D#6pIUF#YMu!<9i%;MbG6^Sa%KF@cG7^s1m>ODm&i9`ceCmyL{)hWJ zg}X|q>0$q$9`>!kzRJ%ed|+e2UN+ch;q~8}-t;OWn&@3WD&2n${BK;N1{yl^RE0cEqZfJ&hssIq}_E2NB&QNf#smJQ{G)jybUZH+TOmK^0V5-u?l(v`QRqq@wP{|$?%i>=g zidjd~(FXsPbRNMR-h-?FEo}6@n{)Ttb@2CnGydE4ILHG~89Q%)|7lln z5oe)=zmmoCk_L}Bo#ik=K%NOJwg6Vt2pGX?LaZ{Dvtr?jtV9wz3;3pHM3cYF8$<=V z$*=SJPgA%QZlxtgpzcVY0j)OTEkN1P*_$hqG_*9nfa2U6~8 zYahNJKedACjAKo_TU{m+<^9n%V|Nz8|)>}_NM&6sieZl>x-^O&6amNl^jUg z1EBzQaxBC5;gvyGkZFsv@o@6VVjZMAE-bE^;}gTB-ppSrBo+ERD@Q_^l~6(!&veG9 zLwTQw;h&KY<-KCJ+{+&aSN5ke(q;iQQ9@cHU{2EUde|b03c-G}v9Pvz{|R!iG7i_0 zOO^4M*zZ-UsL;*c+U16NC3KBJwUush9r3(AKD1ue!BMKd2|;V65u}}LpSGl!!a?Nt z(gG^PL!K@z!Jm6fH&U{3^s=wUHNA z{D|k<)8CLWZX)S#ErXoRk+;mM+wLRIdBpYBJzQqLvoe{&JBgp|5uQXu+dTX$nNd9g ze?qob>!?&OIa{58-z0ac7aK3RwY(Lk*a5CxNu#1fxOQ}Z=A4?x!3D(OR`G|yGF!o3 zeg?RBg1o(||LA>gD?~Y;f?Muk>D-TCktOBEapu)<67wp4UAHa|iXn!X~x5-l=C85eDJi2!I$2qE7 zS zMqno?Uz_H?8+@hTt#0w}WYgLxcnCPMHa5ZnA(V0-VNEdUGk6qT4ZEyaLvF8)pd#Gl z>Du9tQcqhq8Ftp1b*tgV<-dNrTG`;0b>!gsKSQ!V|2+rX>gf%+kjO9CFb|(4CpJ{z zwIu5Oir5LR-hB*dV@LgO*;Q=g1*@v1+^PXBoF<>VKMwCAzr25>|8R)9AQ53@ArW2% zX*mRYE>$MSHvSlu=(Ada3;+6ng0#vP5*(ngVT0fTdzO6qffmP*s~^nFcmuN3U)lXS zGXqL^NnGzz#nE5_9&x(wU(RnOE}gc=SW5W6NnExhmcdZn;vM_UP4h8~es%MB{5px> zk{((O`4q${=~Oj5uDD<`&fJoYvk2L8AWr3Wi62UemPGM3=;vmVVi+nuh!@2*vhpxN z7Hkam)Pkzpq#aC`;75rV;u5;ks>C=L@z{LaNd2UE!9 zt@H3)l1@hb;Q{2Je`(lLPgMn(l`OAE%<(C?Y^3G*q0r;Ep6@qskV>Ml;(R4hJgZO_ z3lyq!Ko0mQnS|dbcv}i~6T>z${u5cYZAi*iuhBHay-vcL_tfLVqIgZl5Dkms8**%Y zuGL^!ZJlpXuMowL$UnA?PMguKQ_hYT3SqdfVQZ+hF462({{2DTCQa2KU3^OIoX{It zpx`bt^22B<-AyKa7#Gz^lq4*}=SOnO+4^HSs3psRGhL!gHh!2qs`zZ*CXXn1B0H$g z2wEqE1iqY)9yi$bcCspuxY;vFVt0R?A9RDc{xY8e-Vg}~rA)vc@gRBh;TF(O^+%&4 zc#l#u%5ySj>$M}DES26fk%y%1qmj}5J=z}rKYQTDuOHK8J(12UJfe7>q--CDemnc!Ub9NlRMc^V^AsYIwZWBX+`qSn4s4ce00(AW8I2$hRH#i1Wy_ z8Z#~;M`~iJ=RD-AnhBJ~Lt=K6z|LB@<2ar`qIc%|AK!u4l>m21#m;EeFFmF8I~RtY z?Z!qA*bl>N>hTVktle){EgsO>&BUqO2l44Vu93w}G83nQ!_Ol=?;;m>mj%~=J5in{ zf?&e6_LPtPn5s}uv4CdhLq6A*DTx7|JWdk*JW86=mU&USk=YXzK#qoOWH=<8cBvs# z^+sj8wJaBs$}S{)>*~EjIhs(j5-KY9sy3*1K=Kd?`{3J4-_j)i9Af@PLWwy7rY-rixW}C) zWA}XpiK2eBI(PybSsRZZlJeU4h!(dE(uU_7)bMn~f@y!#q$-rezmiS0#TjQ^gQ48i z^Mx~8GoE5Pqtnx@x#;1;6L z7rKJYp)aJuAvgedUU6Y=FO&lOT9omx%|ShjRm&P#Nmz zjL#xF_Q$Jt!pa=0BVX?CUu6L;QgJG?sxYXT)na%#VyGw!qkSrxniQI*19d3pF)n;6 zjsUGI|4{fyQs50|3YO5QxU6xOu!;A_}IW*=ICmy+9uuEM$S>EW-T=VeFI@JRcC zBcIY$$I}t}z=+u2h9LGPKp4Pncv!iahS-r%9|aH!{~@W>^YcLc_W%z8et8Do5r|!w zh1dfCu_F=N2>3jJ(%?AI@F>L6Q16Ahp937kAa)>!nyW;91q6!j?Xlhuyu(; zM^+$qG(hiI2xUJj`z=6h%j<|8_bT+Tu$R8F5+qqbrq}g+m9@Dk}E(cf-pztZb|Bptt)F;_j o+9R-PY8|`~k{u`GspWO#^vSqBO;9lgnw2mJ{k4w#cyj3f0ytK_ZU6uP diff --git a/boards/cuav/nora/extras/cuav_nora_bootloader.bin b/boards/cuav/nora/extras/cuav_nora_bootloader.bin index 015f8e3c8523e81e2e2a1b90cf967a63b072369c..dbfe7cc7b3e85daa97f337810b5e5d1041cff223 100755 GIT binary patch delta 22154 zcmagG33yY*`Zzpu&Pj68HC=#oKS^3>n-Bn8y6 zsKCMd11idcogt;-2*$!XFy|94Wj_kREH_dQ>pXEJln zytBRY&dj^b5uKF%JayzUg{y^jN^eUnODw(||9N6$tX8C{9j4kAq(vGezSkd97W@Co z8D4_KwLT=q^&xS#7m3gHwRD%i+0woA&2q6rcR|`bMk`|K48#|tZFke##@vHJ;+cLV zhCsRR`%z25FqF*NFiK`1AcT_pKR|4C>6#z*V^32jRQfl%H_%{Up^OC7vlzm1rCYQsz3@Ct-P2zzWXCNl&&DhsU;s}UM&?S_- z6_Ga~sU}elO@yREH&abLMiVp_NN;9*t>XcbN!5BR9@4^&sfnEa+S% zd43k2pFIQV3sMEajLFnvhy03r&srP2$R2tD1w;T42>>Y&s4x;Li2Sb#0rqZXq7mRK zlBpxrMP$P2=qbI~hjAUAnC3z)$VgQdpVFX6qY+J{XvG)`<65=_Ar8$@HKt8P9M)ch zQf8Zo>9deXDLW&vnzNFMNiKto-2tcA+`p7#OE!cO^t!h6e$EJ37& zNrA-|oe2{MlNFtLFSokL|J(S+plKnz-WuE#&!<`NW+e7XX;!=)iED(73Jo{3h;w1# z5`xWzdTODbYM{5;Oj2I>PI1h}HWDzdq+IkH=2>YmoSqv`yYqDObLvpO!~}0N`J4no zT>?{@P%hfDfc6t$`9a_kX5y$)+HEn@y$j7IiHQ>cT2+R$s*+$X)`G+%UZf2xp*bWT z^g=D#^HTg|ooF+g#SZfqkQPVl$nY2ZjcvC7ggRi~V9_tABLpz^yArX@5TY9GI{eXM zp5gtTa$&kMN|>aK#uFix5Hd8vjLZvC>SWDN|#DN&!l?)Z(nRZ>QJUqS}q8&1_*2;77zL`^p%k?$2KAnN#x(=6LO2! znw>G#xC5p8oYh4HdAJyh^G=`^We5f9047?)@>rx!Fk)Eqq^VdpY1$?&AiXjVOnhMV{|!|94por zUNuyrhFPLSk* z_^^b~jlW?@d) zQv9*-byyPqQn(eC7QS0b<>g1Jn>qehD-xdq$>G;^oB+4Kci7!G<)a8fjN&5XhO-D9AJpgeL-v4p=;1Z;FJF)_ArU;k96H<0d zOk#VW~E^5WatMgzcKtzZ-)6vVLU+}Kopht{ zG0uNT$mnnQ)$$G0NZ@hZorYbKft$nA+{hIaoEVRHt3t{^A#NNJYyI4c?+Y>(N?PQCHFN~l(0;P9 z*7G}f1&@-4@g=-kTWz4l7ktJ1Yf`O|7N7F*@zYLb@KkOdFYj81vG_`#oG&s!g~3=PA0 z8>?qaz-&xSbvS4-&xZ{!Es+m_;tOcsU-W(Bh|pCvr;eyYNJdM+wP^8wR^vNZfuBiGMxm{|)JwQl`Wt z<*0DZ`+Bd_@8M6}gw|mBJQ-yQeF#>X-*d=M3YH5^Q3<#}_*Yau&Jkjw)5e4iJoOZz z{GR?_%#4xVmfYm`L=SMh?1-V6K7hn($sCV)l>=|4576RxVOg{e_X=-CPYkvBnGTLm zwz^%ExK_9tokkV-1un@D^Cm3nydabeJ7;oUqm0MN8o&@Gwh7aRB}_K>E1DShEE#!| z?$2w2(=#{mjetkDDgZUYpW39(CEbq{4i3}cox=CSGKa18 zTk7>zj=#QWiB!W8ug{I>9rdS>~m0a;!9-2?vgfB~u<=G*Ne$A_#;)fjK}d%h;qFGlt?-&7g> zp7SRN0kMr#8Rp_3_kq5lXSX;P(bHaE=GWwk#C( z#KhrugytAc)batG%Z?4s=!A76BfVR@P;kd2;J1YE*zpgmVTBp$F^C3~s2D)pZ_}C(7kWSG^@pv=VsA0El@!_3FC)Z$3E;jj)4)2s} zC`cdm343E-Oql0obije|RqK$L?;Yx7Ub6xuk=s6xFnx3kjl?Elc3dXa?-SO=J%yJD z?zpTZtyjhu*CV$@k?~wAuO6EP4iUAgEF7e?hz;?24Z-;b9-)>&WS(1|lZ=`Y^ttG$~cV0}Fg4 zjBl6N-OQz>;xII{-{dz<;41((p9m2NBf|d}K&ihwZ@4D#m9X-z3gZ*T+Bybg{3}f; z!{OlgAh!xbpJ8M0dv^N&?n2rj$bSs{?z-6YXLrO}V5WkRfV6*htJXaGw~f%3HQlOO z4v0F;hw2!9h;l0GNlgma_pf^wS(aP(S&mw-Ti$h500#KJ=n{rMT~BI*T1@MQs#y=! zAa@1D@zJ^8-$FV{{K|`V29<0x;kq8@P_?885};7+P?=gtvHa(PIdNjr7+C`AS;2Hq8Vn^x z>*ZprBs{3&@iJkTZVq*&PmpxkNzeM4Z?Z-#p7@LfQTfkPAO8q!FUo5SnwkQ&%o9qI zCsMrw!mG)nnL*Fba_bCehs{-+~M7q#FwmvA7B6T;FH zhvC7FXMl0^aZCN4$9$HhY`xzzPsmT7fFBTEN}rDX!uRPhiXuJ5^SBVC#7Z-jg4XfRcUJsF0sN1{DP36kBPGP=Kw3gX1JXUFpo!IvOg0_ z^v_2W9F5`^;$h{#&Kb=NyZ8wmB{=n&Qr@?FTu<*wMIIQlE}~puBVHh~_zZX2ivVbc8S=BWs+zbgdC_AnT}uiIkJq(TtR& zTuwhJXI{Obwq5@9N-WYCx58=E;`hAX0^->2j9JC6s(V*`T`y15w!vZL#qKntvmWc- z=0m)+XM*VzoY5(rVX|KudRLIe7OyEYYwImJ>H@Jjjlbohd$%qJRwYNF7ba!$u@@wk zJ>4Bjq!VbDUNyfvpQcw3X+_|M4=-km9TJn5U#}A>`ZT15L{XA$hBv)rxKNCUH6=~J z)Nojw2K%YHUJd8Qfamfc?6=MS->Mr0)rjE*^s3A9h}Ph#7bP~YT@liHQDQ1(TpB=^-=FeKle& zDxIt}YQC&2V)55<+=?f9oisP#v7IFC8$)Si6gea-m6xgJM=W0dUl7lnggS(T(FwzU z_UjhMHRUz?J>UELTxmSn)W07PDn@4vuWmH2X80fFlUnK3_m|AW^C}aV+*ZMoG+bb^ zRmC}_^y)d7>M}>Et#(C!>&D988wh$gR&cBB*zXbi+-iLZ)&jldtub=Eu9Kn(%`Fw5 zhTOmU$?*3zm0H zFI>&6mWi}%A;y{e=CIC47zA4>RE|k6r>=<2IQa+Hbcr)!L%gNer6TR!ZBqs8p~c|$ z9Q8BWs#OcR6;V|yhWMmYr;s)Rrr?hjsWEJ^0?6mlrr^~Ep?=JSc?UnMTK#eC((YHI zP-fL%g05b#J!n!~Q9E;9Xjjm!RjbXSk*@lSW_3(iDL!A>6~DEip=)1w(B3kM&L@@<^&uk&zpc{Uut!njL`G*((b{9kHKyQTyvgXsm-%bq*^d>^IU3D<*2oauI_HFg`UHbW72xuxvn)iBh#a zg9~8Uq#Cul4Z5D{DxJvCx;2ze_pIMDuHOhNUQz7#_~7Ugi~OF0a3m9|aD;*Y5C$A8 z;GidLK9K|>r!oBh7mcrup-7 zd=VsAVSLVHTSWhmLJl?`Ppe;Y0cP{fs~9+DM4HnZ#Wi-+yY;!HB9F-__tXGMF>VX; zdmbOy1_)W&eTH5K@isu$Q2GS}3>s!7P8Jtx?lI2Pt*LrBO0Vsui~0mky(JThGeFLv=?&-IFIchpL{?_P&ZM^(J7~GJ!yw+W2W30 zdAMp7(R5P!DLvd_ZRt-h1H%t`*}*DvCypZO+{7~NhA5-5-rTchxo(Zk)edz8AO8M^ zW>q=VDnI-qJky6C?L<(g{}T-T@Bie~4ehGwkn8z`wAf?&WT;8;lY2xo*oRVWJ->aT z+2C(blm;1->PKF*yXPrxh5THXqTdm?UI@U(?bpr z=yIJg+Ncw6Rq1*89!>kTT!}E%&38P0J*ueu7N;C)}V~Y%Nt9vX45pX zd!_RCb}tHayEm;|J!PG-IH*32-&~}T1+}g%ITzT`;uh1k`t6_;wE;u^w)bcGoYoi1 z5}uTa;mRhrJbcC#S&tam(2K@^a-*i9*9h@$i0xwvonLkb4MUmvj%(8Cn)s1&pYqjz zO1aC>7^C=9&0nQSdrp9k%qT9X`KM%9_7Y5^NUNZub8C#52YH1%0Uc;57mdM5UfV`D z-s1P%@xIp;3~T=v?_XifQ`$WK$?i4utB`&vaHPDn0`K@hdQ=6+%s{-3_9<)0_PG>b z$mUs57H>l0;u^o_a{paH`pq^4ZdF+$Eb~|{yV8Y5@zc5$`Cu<9?<|U$Bheg8Rvy(! z+gP=T!;?ViFtKz5Z0RKuWmvMx1WQPyE&3>DtCXvmd-5%4WC1kx3dAHGB{EnB%AHTW zOMqQdL@imN7O8OBLFv*x( zY}g-4q*AVgjCl{NO41CRAKtHBL-g-(#&gIQB+9x_&}HaQQ19C>W;gAWWCqfy4G_1u z$ZAHK)B?QO@2QbU9^OvyLo{Lp!td$rJLI~mK&?YK`Q-*nST-A+59C}RX9QB&Q4gFG z*Q9ebpmbDTlg{or;I_zcU7O1rzgDcBCk0hgUghm<6SY;{0>=fN zWE=q$P78Sss_rrG`rGlEk)5>skuvO~rh{d}iglK(GARh~i_#wmV7NkW3k@J=uJ0|_ zA@89z^xtSrU$q7J)v3ixy9*-^t^!6_4HyYq+D+3~tj77BVG+O*tJ7B;TydX*YGrk# zdLM{2`7mm~XN*r3c#|g&Yo+VTny5PRo^&b?OkcU6x=A$n>;Vv5M^ufhJD#1#V&PTi zoEt-^zYyqNuv%(0GARv@65g7WnQ(Ies0W7lsKoNO zEJSPp&cB6_MRlWIxHgHiX|zD9`O4R(ps*rgDS!beBqoUPL2e1)ErSOcluQrPsHPNc0WA=C4|AEnZl zhXm%_mdB>rb&pNkXR%$k5<<9cp#kKIPq!H9aXX&uaq1Qan2`Aomd&23U3?z)y&>5N zrSyBw`SvY|CVX4YzA7YsBnztnPDe8dmv}Hs<(BwUx_3smI_nfX#?AOI(OqQax;z)bWBzbf$oj($6KA z!~>MDdP=NqL|Jt4&iRDY=33?~jxE)QwtP*`DhwfCBl>ZW8ENLuA6B|^evNjgWzh4} zAV}?f&v68q{hk${5kqhAAr^%|2>L{cGWH{u(6|cXmx0+M6h&ms4k9j)0DEKygrNQ- zuC8sivn1F1JYudZ&KrB?IhJ$r!=6Zl_Z>E6A6>Gw<-5RCb`lXf)ue^Zr> z2lcazpIVPUgxTxE+fnMp7O>-UM8C#}6MZN(1k7KIIM<6(ff~5mptB#8gd_RtB;iDL z5iy|>wLfbO0gdP|$rLZ^q9WlK8FuifD?bV6O#nV_tV7`*Axja%Wrs~;+K6T>)8E)@ z56?bN_Je2q@-C!Wx46GvYu#u4$dq>BXRBZljOLNk#`>$QEO-K7x+Al*Z$o#IEvqpA1w5 zNZbIHOC=zdZ5;5t0SF~)kOigHrc-QlUL)3m8AOu-^-+YT$AYQHZ9t2v&fY4_LE9!t&CoDNUp8LskY~f5xW$EeimX)i4hW>NJ)4K z()WS+o#s`ITkC@gSWr)6!)8!QBQ3|rRx3MH5}ry+xD0`^&lrpIfC6}UHxcQ5&O0ue zkL7Vr#7dOrb*f^ki&TwN0mGLiZZ@%wCs3IN{C=*E>$w+=lQjXMu+ zxP_-(C*0}b;m!`(9KagYs_VSI5;QIP4_Zi%llaF>1!67pF+hzDzYI{w{m5EqcEx^p z^HjLfxldNy0^M9lsw6d{75@V{R>-mZI|r>GIrfDcAg4N5^i>orlMOI9j!ZQ3c0LNe9%QJloyYK&kqMI)%K#}Zp=!~`wP%0 z0?9b^))HVt@wn|pq?ltBya8|dJDh;D+n?7C zokVP#>t}g!3(mRWBG_Pr%|#42tfgC#{tn*X0dpj-by5e?M3-663e!3FCwL7 zJ8cT*(RfmYY%8f4SnHiQn||jMj5LeA?y7hXvBeOkLO`eeerQ0I%4ek|wvYyN;9d7R z#H8GD7?IvO`6@LIG=0jUPMs^%TQ!%Xd(dNKLZe#>HH$Rci^w!F?OA~?Ub4wETfcFm zpiIrsoEtPJ+{*BjD??8V^gGCHzUh=Uq7KBX>~H*9}hBx3Fd~8|vniu%afuE^!8%RuSF` zw8=~@40ZAaM{nRM_o%$6aDSIVey8nE*Jm-3i*zUk=ohpLV{SU|lpC;$7lt!ETonb| z$>Q*p&ZE8D(kdrec(CY{-}09vMl}y42iOzlptLkmrIcSbno8hlepfzDf{w?)Qntw* z1a-8tq7#F4`U^XIC`hM;gKBIa6ZcC40m0jlc-)>Q;-G@UB-jV-w~yHiZmTHR0lSr* z6o_cFGfj+8LY3ZFm~$`{+Zn*plLe7dOojpUEAQCTdrp_8i>e?}J{FdyQT*5*3yK10 z{-nu%`>fp;OLsA>uVG)8TuG3+z2jScpA66xT;AESY}dsFvbt8CY<7#W`*aqB2-IL~ z*y+O?>~Hh0Ikd7_E%t`f4ZW^paX1sCOY*J@pi36O7Dcc{WjNSFPr9hOxRnp; zgPasFsgz*0##$9yF-(@@+*Gb%}<5~(PMHqCD&V{TPigx18e*j(kva@Nrzu^#DaQ8?#6+9y@u03#gD05 zGBush8PXKlKeiWr=c-B!`zV#4;az+C3hb(pAckx&`ubjnCv7iUaR09cK0M$@l6gxq zNA;i=;(0kA&d0at;1nZkc^G(2{j$;kzHM6G3>@0?eaiG>{KNp1@`@pQf1ymm`sH0L z{TndYAegKryBl_l&vv^W%Kp8yT6;49Q%WRDe(R(Io*G9z5BZn-hCB-eWcY` z!s^0PF!%27lZ1$w6Cw;{bk|q3@H=|R@P{J!-QUxNc{Af|yTM&<_mSzpse&2NCoKg- z!+IWVZjU2w;b!pO+In>cKaWS-OJIng?rPS4YsJf8!~u&ac)k><8aJ4tc-j%a5@(|f z$*GQ2HIuor!z>NwP2f|7C1LX{^@JY3Qb${WE67!M%v?ONiHK{}R!Zz2U=nX$zU@-M znrQ4J?m!QK$tCnMfh0oCH^NV|vhYzMYPKe-337Tae-Gq;AFm0NZW4-SCyiY1?Ot3~ z&^`Z;0CR6>8uV%4gmY~g+kE^zOcgV2a^*2 z1nKZjJ2)w6|8RW?%IW8eos3{1d4V%RxaUS zCbQQGUjLlV0`hIZdaQha$OJhnDLv`XbYIR&td}{7iM9D=HOM%}PZFgJX-3r;F;xfh zLV{y~HN0%=L&N#tK1Tc(XmOtNGvZGYBfban7bC_3>rUhkMr?0VfsvVF{eH|IfjbGR zMx+a#I!n@V+IsSj?<;_R!SYaa(C)r$-98I|w+O2qinkpqd-DiNQShLBUz1QxzttwO zP~VHvHR;&i@OtpftcIMeFmdC)k=Tm$;3|nZMqJQ0svi76K@W$-C)OYsd%mC9%m8C? z8$@VEH1#ocnu$sJn{9aS3<=aEEl*b>b}fV_<{ect-R;OYQN|Dpe*t9 zZK;L;b%WFc?prn1L?#v8{-fsFO(fF6VG+@Y(JTP{oqv!Nr|4@gM)O$loxp!L{6AVO zy5duSKO4)44@-hz_b`Al}4?MYMN3O zw=$|a|8^uzY2*jcsE;Kzh}s7RN4ZeSX;&qm#s|A`FfB^{A7HsKVvvLlHlsMbhRJoh zvY~hL16cS=%`ou1HHy#H=wqNs)kYJ#{ZtL8Gi>O#wdR`i_K`XKN2X}!IVkaHU_6i1 zBsXaSw%0^!tR)3Z;3)-%Ov9W6Pb@vvMQ{x6S&@E^VGyVUR4}J+n`^O-VBT~ zHkT9drX_+j&VI?rq_;Ormvn};og+r|IGM2o{|8OqwZYULkpGY0(=$K@sG=|4ARe<1 z`{kR@xR6eEKqi2LBRI{0EM+JCJ_~8MLu8k22bW*}J;G=mh`$SM^LtJPz#9VK9|yn> z0r(n)Q9NL0fePQV)8fW|7d;+m*hp``L8^Z%0KW|&QvVI{K>)%|zZQU47l2r6mwy-y zgOBsect#`JECcEk2GV%B4H9pX0-zXQ8Yu7-6jNfdjI)K>bb% z0Q~a-c(nYX8)W0VAK+)Uf7y_jSr99OXTZYH0reHIwxfN5|=v&MY3mnAZ=I|4oChnyx#}15*>3^Pid{ zhYcVdExh^b5L5CU(2W)7N~nG~wtTNQw1l(J;wRpaGE}c7M_qRCG_yu+O}9|63xWoy zJ=MZliI!^6qdSq;TnuhkzX18IgDN^8UK!YpnW>x=i^;;Jhc&thP>Lo;p@C@blx3Vn zZ5{M@`mi?Ct-u@{p9_S9M>Muqn@HKjvg$^Z%C@Na+9R}hzc;Q#4!9}>|Ixgo>Jl=l z07yo&-HyDqMn@ z?=|o&@M6`_`vXnoJwN5jrh&`}aT`!)3mFU<$SUZ_s}O^lEijP%!lg$vRJSDbKa!2Z zgfWj!jLC(qmEn^vFEkB${^@1zG6l3q32PtKgwFH*8hH_yi1QMi$OR zq$}@ff0intz<$cZHIuiYnJt3su{!*iu;;OIJYH}=X2$b`v6j#AF~MV*4qksH^ULr- z;jQ`e_51tC%{uA|x0n)Fcn_OyI_V=~fLB>-4daLL4=-liiL4Q@k|byr=&6-l}_YdlBi5Bnj0EN3$pTCR+D(DQV&Tg~e5ao)C#R zFEj28@J0l-B9K-?8c7H&yo@_u9s%Z~KJa5S@FdmaAA(5)kHtUyNRtOOH})fq0pj|8 z9Z2Fs=!QPzV=&(&S#ZfR9lq0BMiwU?T;7iwnwu8AEypq<_j#vmd z%k2t+_X-HYcI!AiQ~1I968PYjEiO#_d4Nc`az{SD8wf52P87dK?hjmUsR94PLyO~u z%ZrV8tq}L5E_BB!aG}%Kt$xq8Qb*gs;Mr7a^Pup|vm>c@eZpU#%}yLxjM!h71H1DaV#fo% zhw&_Ea~JbShs5js!i{G~FT>H@!3*%22hMpU%ne8frzm{cP~ zOUSI+Hfd$W=GuSOzT}*_Qa(|pN4LMT6M>liCVxUz=>=d%lO42P@4%q@Yq4iokvOMc zh+bi`Edx7%3-sG!O`3J{N+fps?zm8zQGCPxQ-cu@I^F+=%MQ=4+Cdv5&EjIKG53QD zr@iciCj-{M;B1q28@8J$P7eHsY#lo(BAPTrGNbhn5Z;zv0Jrw0b)xU_)VY2Pj_ zr{-+A#mJglaTscyzRIHaodX;AuIlFakY~XX{JrG8fv9VBWPhAnEM^_ zL+<9Y5LuaF6dRJKSQ5+F=^)sDGrl#x~cnR8-4e?pWGWVZjA-nx~CU>xFrR zn}xE-n7xmql%;S75s5DQMey*7vK*5Z7zFz^X`w+_Cc>3eBwmK6O31kdt6-fp2keu1 zM!#ptXTqUp9;6TZ8U@)>P5OQZ(yQCINplQ46_FQ-AvOREY%$jlb_gBE@0aGnlY3C8 zSUQ@*{epd|L)iLMx@z9wJ?A^S^oUAw2_v6M=O6cB-8z^pm@$;s3@L7G(|=d`V89Pd zKlle+k^Rm2-#H~dfUfu%d?w>h3EwR-*z|#WOla`lMS*S7gMqE$K|?QG!6H+3b3g=_ zKXM0;Tw#Da6hT-(x*=-XaF?1KQnmfKBsW;}c`X(l5-v)cs+S)9m&6eATo|VhrRe>yZBB{Y`tH9M`b*5!0-_n~wF3wBYQ>hQFHjuA{Di zOhfNmhqJzNG44&M-*bWNhTI(9$m9FgNx8E*tUV~nE#FG2>WvaZ?h|s6i#Hdc)LoA6 zUHSE=mzXxK-86JIV+SyvEwIm@dpeov_t^Y`_;kGOp_c0A>LTJh_U4gftpaW;$_^k+ zpQp-KE>bK5LKO|}rC4dcUCDhfsqAv$`&;aX-`@(_(C;}l!0>rZa1%%-ug?Xijv?01 ze0!>%oNI5(=JI`>DZWs*DrBAXQ1xdw!%_H`L;r8zq|q0;#L`!6kXR=@W?*$HjTIKqN4LbO=fM>zLC$5JJIPkHU?vwEcfG7J67$gP^YQo!p zQQHjtR#2`S1P}E90N78xp2q%Ec$zdo?z~+A;OfQ@o=Mfi;zDA4DxEwM4V#t<8$m)J z0<~`p|Hs2P$5~BfZ#NCEmad@G@=hb&)G~O?dLYmAg!`%X!dyMgLN9I11``2y*&8s9z|4A%6CqW(f|& zS61T5it`q0zvmXLHsY1w^*qsZ7*&s~vbN1J6sYb;Vxo7rTLtD0@}}R@>iZQIl2m?G zO5I({kKhwPkqEco25R8{1EJ}KO#Hs!dSND<$`fB)GOThy&WrUZGpT*;%EqoU;c=Id zI8r$Iq7J7E*IrCwGvMkI67irQe<>AH!kCxRY<-?BVE0DitpPF{*?qr&$_m^{{ctB2 z_~Cxf3;jd1zg%Aky|0=qNg)U5}5YmTla4{rQ|9tead#pQm_qy5Or zr1m;CrFJ`vCX@=-Gj)qBx|%LmEwJN6iFI-?sF+@l6Z9cqoTkCy%%5YnAn_NdfEcD( z@Yk61nIOFc##|w0)p%SiOked7HQg(Gv}z5$C1k$*KQhAMuM)m~ISCgDw_bh(>xH7# z8jAJ_Pp)2t8wJ*)(`S_|TR{J>V5C+IXBV z#Mw1ej90kdZp7h&%|0sem%jfDyuLRd?%U^MpKF$W181IEUvNXBd{J5oRzHY&OsbKTjTXJ0poHe|GG#l+eDbTDD#5y5 zbp93B)MUmdUt!3-1}l)29ftp4*&$aUIP;5*uN)y8Vgg*=_Iob)n8e6-`Xjs}4?3OQ z&m=0_i4N)VdaWo(Yr||Eu#jYcC*tP<{uBTXQZ4j;3CNUwj}vn9Addn3fjTLGm3`}R z&OVr>Gd|)FC*yr^iH?-r0cC@rEa+mPnLRB}S_Oa<0P>SSEkuGi2erHcidA3xvAz&P zS<`iPeY-pu?g#A>USAgn9Q=ptbXX&Nzb=l-927d&RVbKKWZgU=xn~tqyv}T=fRymr8jVKS!|4&hPbGy)W~!zJxXVdYtmV&EMjw{ zwV_^+RHq|WZ7P&5O}B#L{q&hzNHd`cb2BZ&pVwQGo{#0LK;<56nQ2LUUUJQ}`hP?% zxt0y)IE47WzEn0p*fsn_#ZZ!G8$P*N%m2 zZ6DV@G`R#w^Y@0`^^`57jNBUZd8oimU~*1p0~)SMKW!v8vuR9(dC9Y-ncSyYDpIJr z`KFM+ex_}jFR29QK4S^9ekq066Pr?jC>IZ8bQt&?xZ}OUIzx?HW2{+Cdri?-VytOR z`(vX@esih$U|w|9TB(AeR9I;m5Js_A)j@Xs$c`P>cT9V`FtxvnV)k?~c!%Y8r>uk! zkHLG$GV~b$1iYCzxyBf{KphI2ZFBujD@wul?X>8uQT25o*`cds@AJW`hna%h8f#F& zPK()EXgLj*-Y%CgYr`bCnY?8~8s+U1KHH$i*M!y$S++{x0Q|pAD9gOnU8Df*`c^*P z`oHtta=6>l=eg5oFcRh(Z{A&x4@jQB3=m#R@^AwQ^=7Nyvevr9B7Z@G)042@AT$S- z8%X2}i48f&aT%B&Sggv#2QG~O{kQG(J2COa38jSB$#*0Cn-9$=){eh}q>XuXX)!E> zt8h5Wfi21GFNO}>@7*RntU|h^w0#RB+VWt?(F68+cxOSGUplTot+(i&Sz%l@!*(Pit)irAemJ*x zzT}zMr_hCSy7@#J_jrz<^3PD9-i?H3XZS)jx00$ku^Qk*1_Xt`ih6m3rM7JC4d)%zd=lO^C zL5Y3)+rp4G=KNgHI~xHf?@PH5`@lavaB9E#pu~VHoia!xVocDwIQFul*gCZZjhZbf ztIsGDpahxK!dgMaRWPq`*@fe#gYbquzuh$B{Jt&}O!GNSwt0Lmuj_c%DG5mu?6WC{Uu-Qhw6hB>DE$9kyRmL#YD5&W+BDb zdCC6^-eab%jt|`|l?5c_@yr|CNSrr<4}tAd*+o-J!1ol>>6Rs=1K<&Z;d>U)0mJ7m zb3pMFYc^RfyGTv5yqW-}uE6b6lscuydN_+G^?E#6gISPccA?})T;j11s}TLh{Z#4+ zVb&YP*eC3IBW`S^x!6L~C4@Ti8qMIeD6_Jqmqz^Rqq5YzqD)bGT78dN;Q;b-0G%iN z{>B{qxKQ+FW@!0<0^BiFaBlcKy+X~KBk*Kl$D3u`G_N*b=|jdBtjmsUi8oms_5Wcon{E;q~l*BUDw7clbPW1@qRI;Y9d+YntN4<7}hPQzf{!YT_P0 zj@0cU)|I&HBm_Vpm_t03$GD$0vfP?+=c7@c*3y ze`LHJGMxj@6qM>{Z-yf%$Nn8TLDAQ)uw&0RDn7;^&X$-Z=&eD|qi~$b+u>pykGF%4 z{4PW1^GuWk`L+ks_5+j4Hp<}hGN2F#>)bUjVY)n?`EYT1>?>r2k*(hc*L+{uHh$Q( zrjOlh$kVr&f1osFJJQFtBk^g$xh)1;gsyEGTrPyZ6$e~Y+FNO{+x`P9j+CxSOvlw* zln$=-775jF72Dq6k$#$UgJ~PT_)>#+&FvZW*h_VP;pQ+0S7}4MRDXUa9k$I_-Wgx4 z2|4AH?j(6Pd05}@>+s$z_bJ>vOhK38yJ%YO_8aVCQq2yN@pgO-b$?aCyx9E>M|~1} zct@2}&`B2{pThG&0GeTt+n-|>gEDG90B}Xk!U8JK*eN&u5{E`6)L%3r-IuqJIV+&x z+-Oo>LYd&(C;af&BwL?-UF>{l4s-ADD6_)>a1UH{QBD3IN%v8@QQT_Z(-nfD!$r{5 zK|GQRsrPxh6~3qlV<*lJ^U-3h2|mEng)#AqqR!WXRq9*2nO8!00a8@>R1pQ8xB$K= zF!+8Ufedsvi#q>)A+p^*X=nNUU15x|lQzEX`pV5IjvBRIMgP=JI)w8odazgC9dGU< z7%M@LuJ`qUBQ@!Y(x(n|f%Sz!7bvg%c5t8@tlNK|U97d&0xDjyA8=Fb{DPs*^oh!$ z&g3Is*x(z`85`+0ATRf+^KTSBd5OxKUtsKHjk|r+wmn^8c#r8E|33fVg_({=>W_A@ z)O>h{y$X*OI^s4anE_kN(8wXY!X(peMl!`3FWtSxh|TwKc60~})v=5!9Wvv!_RLtMPH)s zpI`8GEZ>RvJlAOA#pROo*KeqK=|)-Mhv%ERD0X32NEpuB=i>QJ(8Fwl{mbcc@GrTj ziSrAxT?St1B1B>{xyV8%x>{AEl2cBVJRkJKHdOT*2mZdfl4p1StDNN71$-2FJ_}z* z1CB57IX3uS0f)rT`s8rk;Kk~8Yo!^9AHrw+F2R>Xz`0y(X@XDm+?9v^1@Bw>5Ww$; z|Dk*VoWR3va085d0grs+Z|DnnGvGQg`RJGmz8Ht#3vvf$XnR!f4C2ARznG`(u?OBj z*TLtVd`XRbLkwAvm1vQLl$_%l#CkR0`YfVQ#4tVKhLvp^P|%UH8HpuOARD}J%fZm6yoV8w$c*D7Sr|2$tmNy?J| zALoMaHxSGs6?#}#CN{=e8D3lVMR%|~G9;I5FJ`d7hdyyq1`u=mg|?lX4N##a_%5A2kM6Za(Y>o@)=`2*@>KXnL(yr0|56|3?s&e0FSukp zeaG|pKziBRCX*8-leZ@ZM#6!cvFMJcaUi7_KGX<`l4OWkpAHO-Va^oMPif0`nv}xQ zx{!Gz3(bd2c`X^d5(sVpKrKy=!v68m0I6!rKxkP+X$DYwEL68)0BfR(eV(KNN)rij z91%%D==@~>)EEO2m=SAp@yO3X^MQ=05_Jgwtkc@whcn?*2n>7}qtZ+!pA&7y%K2oL z+JH`}L|K`vIHZNuVE85tL&aDa%^lCeW|F7sKpn(ATl za3Dblk(j<4%P~TG;8_9BB!-Wipj{9L-OX3RGl37j`y6sN4h_UdPwmxWn=>7;i}Z*s zgg6bt;xzacU@Bt&1t9{`hv8iU#3>LSxf^z6f|JZ>CR+-(XN?_gcp`gj z*4VLG3vw3aBBA>IWSjp{81-XAEs&CmyXmLrL+`AJ4Yxp#s)q8vUWC~E1w-jE3m5%m z%!(B+@oUBdC5Pv}7Qbh^0fG2Gsr%BuV-%0V_-}ir>?|HsF&t&GD z+1`0)=ACz&V?RfUPU_fY3YQ42RJtv?1Zkr!f=PRRh$Xrtx_GN8@jMcPdXPBLi^K&z z&0VECn!A?mh$xBV^&+Mttuq4g4C`MxNaTBw=!F_9dd(6Od(kyrVnQGla?zC^g_2l| zk`O{kw?9BE1L^8NQQK_G`eQM?uG?Wj8b{kEB za!l`qhl+#wYKTWcY!WFd*qR$iVMswskdtN6>0+z~sHYPZlu4v1QkN3*D0Q0GnO>Ap zLc<`8GtAv+25lpdcN=?XYdEhJ;k{^|7H-8* z#uz@S8--)?zT21;4jt%3Jrlw#2vZ@j4H^s9A`L+vhH=H0 zghNn47|I75}i(KG_w(|`82Bjm>!kiH1v3WPQY zeg#t9gjj^|I|RWX*UX8s3@M4_!>j0S`*W-7a8|fIqUyQ2Q*}sB*7EQ58@s}*KB{9h zhJPZlatGW@fm5CAF?K9R@8$&1PA zw66@YA}wPXYCm7U0UGps4wC}y@47SEv2I05MQinh~;V6MRVe4cb(ZpDhxWtQe%3@lB#HYM^*lRYkS!^@wt)iZccj2ch zm?NeQwb_3~X>BZw1a?0gN8;a6TPTB)-U&kNQV5X^c0E2^&M}@p)3O{ERi_xS zs%iXWtRFvRn~rf;$kQt}G$5^pqs7iX!7xZ|%k3Xktl=KE(&8Oojs<_nb2*R1St)&b z1s0>dS8pLqi+}bo`W$NxkJAgT8hAURMaG+EQNtU?swsNMhQwgsK|Z0Vm7j0L;xoOm zFv2cx4E)Ezdzmg~1=1y2VyrZ@io_O4E{65TSwiZNm^;=N3kiidyf-HBV!a=WhkLMC z<&%k5Bt{=pM5@I3WPz$9(s0x{s>L(j z>R}Sbw!(XnmLu^pJcYKtQa7C&!==DE;|>mg%kx+%Vbn#V*SHuILJl;Og-v$v35cx2HK z+cgQj1EKOfcUeMHk>;X=RCrV#Y_L71L9Hsj1*R`W$}N#`D1~$S>tBI&zDx{3W7}|M zB!99QC*yJH#%Yqi8h306Yjh)}!TF3@X?+wK}nk!Xk}_ zttwj(Y{s_QV(zI`2N(RdfpOEhMwZj@sC*tMrG{8Lm!oZWk_*2Xz^_yHoUk*p8u9< z$T^%lxxnpQCd$z*mqlVqAC;Iy*s?omahuQ1;k_D;bz_zm7x?n?9j;~K9CQKxL(n3*cigH1)yPp~dEL~}zeaxRpM=lvd&aD4D2oF&{F zoH{bJ@7ZU`l1F{Nn;9d$JE_s{iRjaCvSWrO`VbN;By$|*R1RECAEL!+!jvdI?h=+q zjT^Mr&$MZ{B;M_!#C<|zR4RT_xE_@?^aJQOFBl~mAmla3IGm&fG*DuvkU1oNLWzHB zBjcVaBX9Ekd5v&>WPf=poIop{>V*SQ{70|o%4=XabrW%*MY)wyI;8Nw?=wD^SZ z;gHOzeST|QIz%Cj!N=Zr6P^?o21=Y4Y6e;E!VUvwOa{}%ogZH_GI*TLq1 zmi>YH!~C9oLcBT?pA;pFXW-e+YYdc_AY2$a67zyAW+J{I6vU(|kN4fF z-vk5KaAYy?!b>r+0Q%k-ZRGYooXd_1$!LcyA|vo_;Dxg>@%Wg~5i@#_0XCDN4(pJX z61Bp}*hE9{=_CUZm!Cp}%gqlgDX=*-IDV_hU#a0#xugX_SQ9^H!QXv^4I>AR8rEm#EwMC;d#ofeWz(^95;~>;vfV1N`35^oNEp8lg8fiLRD81Vm0*9~L;rHC>Ln(KhH(X=5S+M`E2;m8% zY}fi^+@?m9;c#fUV7Cgx+J(*Q_w4om%Y}3UCC~QVaoukGvnzb7U5E64cBwY3_;fwM zwxLT^H4N5oDonzB@76BD_1JaSq^e_h*StE?nuZ&`iV}Ogi>)j9gVy8xb?ck1sep+& zJq-6v9ke)W1FnGvHxD$p85%_Hsg#DB%?-{ydyCRjVyl;`p=)=Wx}5{-4=Qb-1Y8TX zs#bhTx~ziKEI`{0FICHM1Erb;MdG-`3BDx06Sn9e;H->w{hk~Cr1HUa`n4aKXlK9Y zPhmk~bl3;pwnkMES+$h-&M9GPS#(6v@AZ_p%S+G?8ydj5L1IF5>7&RY&3_Bw>HgNU61fdN*Kww`gT zX3+PLJ|w{4ekp9%4#!o;8?>iEf)SSMM<-W7QMQ2*=ldA(2?%q2gDh%Z-53hhWBHYh zNTU$13TO3+_^fb8A3bDL58eyA2qt}e{~%JPPA*RD5n_@!{F1OBX*R`qg?}bxC$91} z-DHheJn~N>$^QA-$NvU?7UeYrPfq6Lusa4NkE3wEP?9`?fdjWkSeyJ113OO=K23gz zsR0~EQkpT z?H1;yE`dt1lJH$>{v1k-mf9Al0Hjy@e{pS;9#eI|xfX?vxKs^aF4-+vQJ?2$Khlv@ zI7jBR-!u4BUc*;QyQgB@BPne?ppW zh>^=LoRFp(V&&8Ya+FQ+BaNylQVdi6=?K$DF1#(AO-qa#)8FltD}4w4Mx^pVAd-;sR|4fPL3wpu(@hD8<@wW66B>+- zL`JhUgcS2|?4A>@rVow$x;F>-1UAF%WPn*b0TbII1Z6xQo_jo!TZ9Lf{xN$56ZP{a zbcC=oBXb;EOuJPS)`#+fQEv{hicMNh&;0_c35BpmBz5`YSk~CqP%WujA|EMjpB&vZ zJDrLC`6F5-^krl{BrDlqM4AEVv#kjQkvciOq>g1x@S1N|o7!oec^%=`TIKkH-}7a& z-}7p-uqbn8(JSiywcpmsQ*{^Nu<~MemeE;r(_3&X4{HyT|6bp}itMU5 z{SvdT&YGjn7n`!UTQ2(Eu9d)pj8bIo8o}Ard`s6LB8D`x&^5hwLDwXjUPS~G*!y;* zx9k2-5~Kk3bWELIqyWKZ0%sH{Yli3hFmwjmU>l602FWe*5;Z6jHUsc@tk+3v`aDZ} zk%nzjA=YRdL?e}sZIH)-uptLA{@edmY)+sUYE}u84Dsq8{QC0P#=IuKr`6x%O63T> zwDorf&I#dFLxhfqPjn-2P#P>MfYhn$)Nn#!@uyxO@lF2Q6%9hgGed0j+RO5=3&F7E zS{1<;f*z4+a`}8v3M7e`$+2RwLCUoboJBAopd$nwWH@q*q69P?Zma2>baO0q|EA6? zGUfq+R|PYzMyyqAkgd~{F2x0RlCITvj+da;#82GEQCroLnd;s7EGIseQu3BV%x=Fngpy z5!eK(5TPVz4%gRj;JSdL+Tm{p0-{8~%{3#m+0TG}#ng>f5JgplqW1z>gaqSx4d!)l zw8+O^px5OV&&6|R#WUF#$Rr9s7*zSGCG@)4nCdV`s(Cw9+d7M^zO7R=>+BeKp*~>E z)?tuJ)*JQh6dht+CN71e(eLSa!1WLoIItr8o)7%gy2#>S&2&6tmcAQ-Mxoj~V``sA zp z@6G2F?k|x(pX4Ryvu+JLXLa0Yoj94AQ{ngcdY7zGjL?gd=_SiAgJy{E{zyBxD8^bU z;)prc5Pc-5y+9{4e!4VxyuQ1?%mlGfr{6N5rDbUSdP;B8ukd?*@fl(7vqiv=!}%!| z`aM~IF@h~JIzt#rQbT$$glSNlC5_wJS^ zWIgrLvaT~U-ZMnBDmTLOZfT8yyx9mbfB|Hr)YeYVC~c1f1*>s}e!a}WxT6Bg&gjc; zJGgGQ6xX&}if$RcZo#_W)=h3#44>3aYj;aSs!i=-I;Hm&DWqQMUEkm64ppXHRCY4K zbEH&p%_zhcKZMvF5Wn*vHjhT^rUzj=#2-PxkZ&V@Z$Q{BsaoPhMkxa=73~}%+Lg$W zcwE1hXh8L=^lMucLoV!=RvS{dU9h?4%z`Z#F=r|n5m{qoM1Id3{ePABdv*c`|E~0; zVL+E57Zc@pM3#dZG01^NoOhyBr}Kv{6!}A3mofC6=O?$DLpMtCEm3W>XrtxnXD*)U zI70^u`ySHU{GMgK|J?_E&tttGx}JXigXcw;W~~YUe#?Q<-gJ@|Svc zrP+$RmmM8wJOUbj*g4Sj*Z_cG^3wJV=zlkz((iOVbsCSPokmfGG^@UIQ6rO_;i6xu zbqcFT>u`%uJ6dbQ3fsNmNB@1JQ*P_lADz)2M%%g*kJ?5~ydQV8Y%S4!Qt1=BhaAXyXm-+EQqyQ zpz60nHy3UUP;uZ{jXu%u_dplwj?eDUo~%H$YlI;`ZL;HFXp}y*#)sm8&k)%7QN}Fa9P#Zeq*nx;>yBT?%~q z&)(nU^DZp0#Pc#y$)0q}m5*MLb&HY5ZTHYfB(ADFe$NQ;OAy;f7CFD_3XVdV`Hm+o zal_<3_MyGpFH-JuG}0)RRK6~af9Dh+-Y6O?e~~hlzX+2g(kcKluhN*A&MDmS=uop! zpXlA-L&9vJ2giJ<_GXOV^NsIy*!h(18K9moL+Zt~A4s+*j}fZ=;wsXJCY^HTL4{BH z;`FqS-LnS@5mH+P@xzul6A}w5{hr}{2qY7tNV}-O7gT(>buO#Pp5sEpu1PKSYtqI2 zKwgjisTh5sw4EC|TVg9fJ7`EWN{ZMESU*Jcqhg6Q)JoxobSG_tZmsD`=Ww8SzxLKb zN0B0f6;7b%UQ%QM0Jjz5Mg?_&(vyl~6(JW$&R+l%;q0N}x{!NAAafcr59_a2i7StX|*Ir#`#{fp#kARnphh>%-C zc1uNTNU4a}yNZ<;mX?&Z7sV{Kz_@qD@r12{o8d_d_JwAtxjAdCS!6?%Iw?`4rly4f4$8fcTLfv1 zCIWCGhi930hGhr;8GLfZ1yd2~2mwxGtXHMCk(YVESK?YrBdQ%&M4-#FkOB!-zbDme z4^&&q5*1;HJ1%5{bL|c2hN9Ab27rcooi1|Z?DM*AdreSNuvqf_yS@=zAE5wYnc&g?f4@XrcwnVf*h*>c?afvVBUq837Vjaehdm8 zzh{qNo{)-n3QH$s#%J^+Eg38?Ayb09htNq+s%lG1Lw6{u(S7gAeRr1c94Woxqk-(td31Y6>)^Q`k0Ua{7| z+~k0Hus~X}c2O5iFIh$Oc(#fr0u31k8JpCw8yHlbh*p?Hdw@xu2DaMjqJGc&Jv-q4 zVBmj$&#R?yM*3d``$hK(1p2RsK`Atm*yX~HB$8mUnUse@A3w3|@p z>Eh=!y`FddD22W}APYa#Y}b`dDYGmpjj^Wjwuia0$tKZArCDhxnAkgxN9ni~kM}q+ zSe52kviWmBvhX+}&7q`TPgw6P7_~inaKJ$Kh4g4iHsM&s7CO?J4njDZK{(oUI7d!M zrKF@a&U)}(OIZwmu=C1FU3bg$Gt!me=OGY#^%)x^Kn)KjO6uM&YL2xy`;644A^*Pz z{%;2UZwLOxz<;-<-!skM?mZJbriF-x~6o24Hh+|0-=F-yNsR`Z%1lyaiE zR0L|IF-w|Iv!sH2b(~-lof%+d^lQ?Kg-47Dwxr_ZqF`V={n<$%no_*pq7!Wz06gIH@+F%)yoz(_`P+3B583=^hs`5h7`eR66 z(79j%5>U;06FyID@L0e#TTJvNRD-k8u1*)&;H#y!tF`9<7*rJw^f$Wpm&yWlk4z@ zNIcR5_TZGCn~`Qf$;OC#eJCXqtX_}ckvJRw@bx;u-jtizlJa#PbWDhwM?r2%EsFWQw87>kXS*E|?o?V%9j?j(2`Q=b$ zV>xqN#~#K&t9N-6S<7gV30-Rr?EjJuG zKmp1YEMgE2qEJPl@jCoR;IkO3s14c+ln7Bo5ecirxeulmhms_Zo_1<)36tE!0+N1p^dYN59rtYZzh z(hL;$;O=5;GAdY~^E&@o~F>1x8`^y^hk;3QJ+_eh@+s0VS{a)PUFAODhjE5Jci~}4T4GGfF4R|30qKx$0?YQlT|g5#~znZQvC3OnLsaE$}0*J z8(_D6NQ>ow#3Rkr9%7$)LSlR%txpP`tm93M!Bc`C2?5zW!`=XJVZGi8OlBomE61HS z-8*kC=sLHj(CunbqNLx!CyE3F1m}0*R&l%y7D)0{$$Crx0iJNjNK|Y*? zdVU&AFCKM?+f$hFt03Y1HE|@D+U0hj;la9xxs%*U_e7=T;wg8!a)M(p#2V!|$0@g7 z`LN@#+d#M02c?%@RDb|?;+c%^QYV|C^Mn2RmwE@e@2<)OzF1siC$ZkRMf5EKX;vS zrzurV(!pH78|BcqUw{5nFzbBKOdw9+o-`GSRqV%5ZiMn;pqx=$xdA#~eGuL~s|;C)EU=BbiQffooiXdewdni>@1f?`9wT-u_5TJa%eUdE+2io0D{$?#Sf#hB3#HS7?bGJ;_KuY@ zJL193)jw1__qrUzv5Dh zDy6y^=eS%14~$S<$kgI-I^dq}13nVC|35wm?n0gQ9Mcx;_K!7aH8vQPo+rgfg~vD= zd=VeNOhBsPXd&#Qx%rXfWWq-s!8EQ}V-if`o4<1-T2@1 z(|i49dJi6R(sZ#|$q~>Ljx}*I=Li4|6VUeI+S3KW&V5p{W>i|tMH!@QNgyMsU@2wk zbvzh}V6RsfKI9^)>cUfQ|3sPdqd3w41GHcdG|}kF(%*8;d=IgcAxwpUTKs-!Ql;Ut zQWKiVjO#@ey`98R1C7-46RuLDK%o~*+Syb1cmX(ZU54EoMM>Dk}GvLGQ# zq|8}~u_Lj;o(||fS&#@Auy@wk^E*|PuRf%mqEw(5Oc%q0Nlpw*d^qrQ_OQdI{0M1i zh9S)ejvK$0M%s?pV?+#k#N#G==T~-5Ojmtj{=p7e2$-LJd)h7m*+DjfD>b;_Twh*8 z=;5+A9PoBoXtTP0R{iJE)h;r|7&6BH3^7HNhn#ZHQj!62a5^lbFV_d96<-WWFT8l| zCM`}K#=$R|<7}fz2O(}Is1*cp>_FOIU8D=|gD&j#E%n{56mdvMFsN$=utPhd33jLv z4uYE{E~++m^<(M5PO6q1WM)2wSM0(tF@DeL-mm|#0FGl}{MZ3lwy5-12UZC@wSc%{ zV^&^pky%XElI1c$&-N64^arc|)^(E0cbU1%+-&%N+!fPpFNMXGgW9N^)_SXJQm34X zX{VGEyXPM5B5lCR!O%uXhYZfb1jZX9%q=F8laOwSK)o~2zKXy7-}H5~&q@v0*RNV&|7 z1NrG%jTRc8uWruNwgW(A76n^J|#hnv&Si?>CZs?rv-5}}t2#}2S6xzP}3-XD3 z3N!ym;gkWjRpu?JG_o75QE*k<5H7A+4^G6euY=;atI>Jjw58+HfvsEJ6O?v}I|Hs< zRb0>&L-t1na^Qy8<^u({&l$j4EbSl;YuGV5+wFQh`%hrTzS#A|OGFo`x?5dB94-b6 zi>F80hJfc4gU#{zBEEf4WZGHHNtF zs=UxL@=N;9Hn!5_f{rW|>aA$gYc(#S^_?i~(pcf5y6(MimNf%OQ#148F6m{<&n|50j z!ie{UX)_`R?YKIfo6Dg+#W4OKgyl1$A8wJ>b6dF^uBZp?L)%LmlWJ#Ezx^lzw_ z@(r~L`Op2H4Z^aS(b|qaCgJAgPL~SyMsW{uI(h_p8FZP{BJ$Le!Ur?6@ZW?>GqsV$ zkkftntSg@z3(`vkPl<z)=E;-<-~CP)=dEwAB$}pEAh#g+g%wiN!+vV~My?nDAIE)g=jY9?KqI z(GWCQ2J1_=no1)Lj`ZnQ<8+ymcyTt}tN^j+_0vQ%^%Zc+s)mTkdJr8F9O0k~l8qDY zJ~rg3upS0HUi}`hV2U>+Mm!8s86(Dn10In^81Zsrz)XiImVs~#E+K@LAib(#FgIP& ztF(3GACEDS{~QK9hUAvm)j5p^d3__LVZ?ns+4_T4Rg=I!9tSR>stwzZq2yDKD7b49 zd$0=pDw)?#@Qk=tB1HZer>y%b?}kj@$L;T~D7cAP5x=0$t}01{Di@hrs7hwv{5KRq4@wm@R;?12|O5I4+0 ztRKSMxrqG`!ix|{;mCQ2O@w?3I?4gb42kr5rk2R#j4;2gwEG26Acy;92`!zTN>WA} zDC4f=6POg#d8hK)O{ftP7Csm;+DcGn5A~DUHj2LHVze(7-G~2|in`!`ZIS4TO9oBD zC`Mc(FB;A@R#frj{0Ing)jXvr4Q-$&_X@;DZsrfGNua zfte8}g6o#*bl^Q=#IL1`pdUYIO1Q|>q9ic#)0=JJP0I*?RwIUUB(@Qh%{8&BBP%9# zM$nX2aR?3nSc(I=`b<9udRz=3#YyL2Suy;E)cI`XHAz!9n>%b8?ED65?1W)}zxIO4q()Ofxs?Dn7m~qc zAUXetDauLE!_w1S1hwG11(w~iewbg-%d~VBR?7C!d#M@>6cK0t;)3H7_%d3&0xA(& zyygelCcWBZ6y*Tk#Q@Ic25^>MiIPWhBic~r80Yf1(GErM>q#Zk_|F@6b0NaAIZ1I@ zli{?l18`kV7`#>mvN6tj(a5B>)=w9X&WW-q4k_O7dy@MJbSk>z2Jv&P_A9E-xX3p6 z5_VJtkh2qzJ_+H6!4M)Lzd@e>SJ6CR&N#`;@N#v#F*)QwRUAO`QoeB|uX(3ZuBg z&ZeWzZFbV^tN&@Wv5ySQNZW3Zg?1Qfya3L^8UDYPq3y#!0Xw}cP@o11JmXM&I9NlA z8o!KVwDM{>tk&22QaQ3}cahSdU!Qej5j3|HO3!Hhsy-oe>P6E0i|}l5ly*BRz^}i5 z16SI84pQy?!z{H06P?2>drae<*QDLYNQr{>kdWCNn1e3#4^;S{{#gYRyLWs7D>ag= z)PZ$6r|;??1AB2wpIEmtZjh6#WW^y$JCI+}M*#VtZ&2W%CmSf1j!h2&(g-#y@dNN4 zrp3ekFPpAA&H<1O@1SB0C~mHJ zLoKLI9ni6cOfhTKe43RKtH5$8YfZ6gc%pjh_qf32XEL~8{SIql6|9*yh*!g!0S(M# z4UfelVbBv=JYN|3MAV?uJyMTrHqI5wo*Xyy->~}_F7fgrQ@`g;FGDbst8RleBmCn@?V#sqXA8+zGq@F&TR+FY z2l{e~&rkoOA7e+6P$CHFd7pCL6LghlO*6J++d=z?r z+pd4Lh>NI?t*;eUiBp9$3v=*8f@k3<-8(RM_nk73oTfsZAK_+1Ol!w# zTJ+28e`E-xx7Bc6oB2bpnafLGxU57KH#e+}MG#uO80*0XzZ>ldw3k`G~M-F}XYP9{m4w z{Hw(>%Jzf*;Og``qJxY>2jRlam;U?p#AZ~{L{x%E8v~BkGKl~c2WCVhVMu8Z7JYt_ z%7D~;KjTh7SW9>WEdJSC(Xas&>hsDOw;HsbSlr|%Y>504Xfi9vv)~7w2V8azF41sW zp_rdxP&Js#BLV%C11^x5fOP>c$&Eb9V6Of!kItYSF%WQ$+Z7DTcZCL&*x&IF;pqY{ ze-Xbbyi{Hg_iG;!BIJ%q+U%rQ$Cj%F zU-=~PzMb%leo*yi2Q1a(nmZL`E^spL-9bM~yRB%%WXB2~X>&HK_E0jxf4pNunxqjF>ohLimD@n=7PYxUc*M7EeAizP5;|ZQm{WG z-?eHmdp+Qsvd}NYt%_lP?iaxWZd$XjYGoSL+b`^2nK0~jKLIqwe;2Oz-FBLRSs{ym zHt-YI`Zof`egiJLWr-k04H0IpRM}+yzx=!G(i1Ae-ivUbXwxy`qir8X3Fv{dI9Zm& zS==F2RFkume!WqW8?5Ph%~m}YewMb`$tp;5T$C8Afrr{#XyV_!X~4gG6Y&byo{)4c zJL(T?Q+l`cM%3?yD>Dmh+YW3Cg1OjfVw?w-AlRt8o~bU34&XnmmuOkGK*!g>;dvjh zQN&ezz)v2uO{TU>A8b4D%*6V0Pnc#N*mk04SOw0GsDHzBU?aZru9S2PXMOEr+}mJ# zX8CqYk7}~GA`Xw;2q~=d*uR!k_Uz?DfCOkF%Bu@e%09M3AwP%L~)$Se~ux z^F&HQ?=w1TsZY=>F;bI#!onqaOfT58gtwMdQ={Q%c~%|czfA=7jr<_a&S@80c%$}B zD-XLj0j^X$n}J^xwm&BhTVZ_qxgw}Gzo?U|2ZjulC!VGe8^uYPWox4A`!-cA^KO zzc-IvJh{GCdtAhvy&)Cej_L8ZP^wXU z)jr?*s@n+L%Lv=c4sSNu)A>EpOic_(M?bl6>RKl}8F2b)=S6A1;mraHNavdc%bh4= znUmD}wGZ-DB$Wt+_)}M9YFVHLN}vC~YbXmIg(@?g>3m!TaQ+#>yk#+IZx)!Hv!o|S zDm3Z9v!9e0O^tnzB-hj|uX1TqM>!QEa!4DR-37w_WpTDf2h!{*{1md{9yG0XhKY38 zMTs|5NweBe`XL9_+=2Yi2l*_-JW$p*9hBx*K)nX>@c$%Q9JnMz2*ZwJNjjoLkpY|D z=iz!vMJkBVmx7E%RIujGS(>wws#-3by~Wy2oxK%Y+v|C%kKytf;pUn`UYBdld!X$x zcTP?L18K4eh^xM5kXseTxZea9zsD;+yQxH9-qJt%<*npLk3gC{llZNhG%D>jnG;I3 zL5g?|vidJ2>wcAXqqN9S+C60DMv30fbg;o?FEjVHthB+-IL32jWv2UWW!E<{_vWrV zxKL&J@>W=`(y~Qjs`G)KjN<}QnD|65VaWPD!~BZC)wm3<*F*Ka@0!ZZgjB0n!R-g$ z>jz+jx*=SFU})HMY!e?+qSC%5J#Jv2HXMDuJm@z*1o{hgY+e}{K)s&g-V}Je(o3$m zkp?OnLOCWS9dNvyp7f~ z8cRixo~_tg@l8cVQ_z&(T|rZRgV5%>I}enQ5{{!J>e*{##~>j6%~9E4ihB=23WQ7u zs0bYDk578O7KeNcN(EID3x{cn;94DT`=Cd`@pbR5wu67h=e|NI8C5jm2?tm2Gs!OJ z0rVgEmWe}9aNFaM)9cyq6T#2F!Q?vswDtW8q>-AIiP6aCBHUB2XHSy^n|sr0JV9~J z%J+IU!+Ayg7rdT7PaZ`T!^-%Jvkm#Ghmol94sol%G*PC5SG}I+e18z#Qt4GGWq%bY zYU4S$$|gGcD&hY<;k`AP_+8=rni=>7VfYJ6q8{s$b7CE^d#xK*H*}m)#$HBZlJLO` zdbrQ?{R@d~8X9ZjER};sKDYz@7Ih{*WjUKO;9_*r7BbFNN?UOs}`u*Z%ExidhzAnnN#=*t>_eMkQ_*Ck1v)lnB`oyvVH zsVBj`aTr6d&2zN}uFBHnTJuxZvIY8u?@IahFK@~9q56&BSMhcoN*-?oagRv3uY4;F zo^;JMIf?PfcN=nlgBf6DOI3L`lBXw(`ZZOmZ6)bf3PV+Oo03`(|Ss!SH2q51;E3beL zj<5AZPpHAtc%9wcDi48ML+=PLZH&c&uy>;#Ckss*W2v9|gv%SJD&B7*duNG|wP|9w zxexSX8ghM34%b?HJmZAQO<7M*^&>sF>OK#5M3e8i$c<95ArhqK$jQ_&dbo}c;bR*^ ztQM=-6v5Zm3E*`ewf0DXbm>w4yo6fL+(O9{8nI@Eb;$F2YvS`UTp8%W)2%bC3C~Ne z8NC1BsQDzc`K2)QWiw6`o_N^?%I&K!kHVY~`AS)6yN_@~`b9mS5Bi1mucSnI`~JJ> z2X3869!_X}B^?`uj#q|j% z3RN`S7P2Z8V+t(GL46r*2B?qpJNdb4d?B3AYCLEfd?lPu zZTvkZviLS=*n>IIRmIc!1F5i*R9F}@y{a~HBt*3BJ?} zWbusm9nKosGZSI%`6X8Q8p-oTFZnb9xcZO{xFLr>xQN(-avYZ=#(=a5MX-5U0H&=) zeN9^35?eB<zwHadNc<7xb<9PV5YFr}9N==Bw#U=rGXeqEgfY9QS!wmO$-t*mneI6|T6aH!W?Z6VBXi_30ggaZ{ z9R99m961t(KTx;8hd)Y`8rH%V!}myZbF7jFK9FItDRfFr4EWlxMvrIXXa4C5G#EZZ zGH4s9d>|&IJd7(yh?1~URkt$s3V8TbH1&8^`tP|Y3vtX-1K&!WJPGYZ5geiwF>VDEFORvbu<(^N$*R9oH{-)&Ir4YV0#x^}a#F}ko zc_TQ+RalGQqBLV5TA~>9_rUr3Jd?a~H_KeD3jt$hE8H@!u}0LjN}-1H@KusS1?l-Y z*4#^nI%G1p`rgzW-U91$K*v-7ZTUPp&_nq=(cXWW_JFOJrN+Rj@_2^#?{pn17;^5t z4t5b$z#Vm^fdkVKR}LTCK~pQi1r^iT)|J-3K#3%v7*4y!bEjP&xk%IP zJ=y@aR=`zNlrpjVsiR{!(vin=uWtWXS#XBXv*L?KqnVm2d<1#-v|s%XgP!#IkE`$(2QqS>PBKB_=bqEQ3d>4FXnYx%O* zU-k;mVHb)De*Rs;A-&LS^;G(A3DC1wrLI;d?6(%7mA8#>zenr1tGx8omTR zZQ%v=2*auB@Lr#1q7b|5CA?kOyDL?(8oc&=o?_wKUE0`1Cy~zB83nEZ^G}Kmukf3W z5udstJQ_JekO?DknlMV3HVcV4(lyt(a+L0L%!U6S9r&=ZGjtj;W}}pItxa$o<=B5D zrz-m16?WqJ2F1ttLvTu4f?n(QJO)Rbyp^n5yoWeZ4={LMxV|R*COnq98<=6XK?a|j z0qr;#+%9+rcGNZ!tfj)Sy1TaIJ~y{xv)mWv z-fIfF>N@_Jv=UdZp^#&$9`cygj?Q}l!h4sH*5Oit$Py}{( zyC|!Czrff@*(#~L@%hGfx$)hOFa`~aulw1E^k3aV<}BFM;wx06|K9{Cls47*eJp_S z2mm1AVaI*_z1q+)UtA7cFq_2sLc6w_6qnYhLje%#95FcEvTx+RjX79f=j#{4e5!B& zIG^<)X@7y@0T9%={RKl&=OwUyyxYMt#`aKSvui7i2W29$P8j!kqV1%8W6XjM8e#92G1Lh5im6z4I7xm5ukbwaml$`H`H9;4RgUC z=T3G|VdZe<%T%+qL?m3r%D{&ohQ=wz>BW*6SI+EZ7CzoawU>sL9 z1ZmjGl4o=;(3i4TGQL1KN692{L< zsA%P9nUVN5d`<5s_@)Rro{J5Q@R^tgGSOLh-_V1gd=31Qd{C5a2Dk7~a)TGBDY?Nr z9j@XA!Ds!*N7&e69em|Z*R2YCZtTCGWh20n@2HV)sQvZ*G`0Z%2GPOb1u zDRS=C`v!7U|0^f>6sYJU)KM4Uo7s1(Kl&swTT@+1q(YZ7sku(Kvn?ep2;Nd3HC4p(&H zI*O<7lnhFUKH-}hjV%{0!ytpy05^3XF$ccDmTk#~@66HnY?1W6bu(%y0aie}cLY>% z1^$1BPh#Bn)WY?%T>if2jlML?o2E%lltkWE_YH@0HP?FIv$Zd|h32n(V*c4<|C%O<_spKS;UC@WMkwrewm_AAy0r4mzh=Qou(dPp|B(Nn`<>KLAxT;_}ry9{L`%U4;TAk)~ zp#L90pyAT~EHiD~r|)~-@e7VO(}vdY>rKHI;oFZ9>rL`YvXY&ArD+?OLRCWK zK0SO=XY{^gTrWJaFL87;2zE?B#CsoZv-}7jF31B_O$6fw5fJVZf+=Gbd{E^Gl#&HX zedSL99oQ-1_`c_GxsdwSauAwo-&zA-V2XPCEIuGyfBU^8rdVbP=Be(sg^}=e3i1iS zepe{qmqA`xiq5a~dRk5k$M$D{)$i*5twnhag8{#Zl#HLv?=;0YENQaVOX0!qY%g24NF?M5G+Thbf5d z84lhj5Kn>dA-tOn@d60@9)wF7aECe*45JYCjX>;95<`Gy(I&{dl!e$0@ctzT(;z(q z;@LTfeRS#Kr3knIQjYwx5fbLU+s6<;wd1qiQ(?jWev<9`C&B*(!ax~>&Ob6~Apf<+h#mAGJ#x|FzmHtCYRx3`l;lOwP2KYUZwwr73m7=o76W|GpIut41!RJubGq0mKzyzTLz>w$ZSRwzyuSivz_X@wBS1K?N| r&n-Bn8y6 zsKCMd11idcogt;-2*$!XFy|94Wj_kREH_dQ>pXEJln zytBRY&dj^b5uKF%JayzUg{y^jN^eUnODw(||9N6$tX8C{9j4kAq(vGezSkd97W@Co z8D4_KwLT=q^&xS#7m3gHwRD%i+0woA&2q6rcR|`bMk`|K48#|tZFke##@vHJ;+cLV zhCsRR`%z25FqF*NFiK`1AcT_pKR|4C>6#z*V^32jRQfl%H_%{Up^OC7vlzm1rCYQsz3@Ct-P2zzWXCNl&&DhsU;s}UM&?S_- z6_Ga~sU}elO@yREH&abLMiVp_NN;9*t>XcbN!5BR9@4^&sfnEa+S% zd43k2pFIQV3sMEajLFnvhy03r&srP2$R2tD1w;T42>>Y&s4x;Li2Sb#0rqZXq7mRK zlBpxrMP$P2=qbI~hjAUAnC3z)$VgQdpVFX6qY+J{XvG)`<65=_Ar8$@HKt8P9M)ch zQf8Zo>9deXDLW&vnzNFMNiKto-2tcA+`p7#OE!cO^t!h6e$EJ37& zNrA-|oe2{MlNFtLFSokL|J(S+plKnz-WuE#&!<`NW+e7XX;!=)iED(73Jo{3h;w1# z5`xWzdTODbYM{5;Oj2I>PI1h}HWDzdq+IkH=2>YmoSqv`yYqDObLvpO!~}0N`J4no zT>?{@P%hfDfc6t$`9a_kX5y$)+HEn@y$j7IiHQ>cT2+R$s*+$X)`G+%UZf2xp*bWT z^g=D#^HTg|ooF+g#SZfqkQPVl$nY2ZjcvC7ggRi~V9_tABLpz^yArX@5TY9GI{eXM zp5gtTa$&kMN|>aK#uFix5Hd8vjLZvC>SWDN|#DN&!l?)Z(nRZ>QJUqS}q8&1_*2;77zL`^p%k?$2KAnN#x(=6LO2! znw>G#xC5p8oYh4HdAJyh^G=`^We5f9047?)@>rx!Fk)Eqq^VdpY1$?&AiXjVOnhMV{|!|94por zUNuyrhFPLSk* z_^^b~jlW?@d) zQv9*-byyPqQn(eC7QS0b<>g1Jn>qehD-xdq$>G;^oB+4Kci7!G<)a8fjN&5XhO-D9AJpgeL-v4p=;1Z;FJF)_ArU;k96H<0d zOk#VW~E^5WatMgzcKtzZ-)6vVLU+}Kopht{ zG0uNT$mnnQ)$$G0NZ@hZorYbKft$nA+{hIaoEVRHt3t{^A#NNJYyI4c?+Y>(N?PQCHFN~l(0;P9 z*7G}f1&@-4@g=-kTWz4l7ktJ1Yf`O|7N7F*@zYLb@KkOdFYj81vG_`#oG&s!g~3=PA0 z8>?qaz-&xSbvS4-&xZ{!Es+m_;tOcsU-W(Bh|pCvr;eyYNJdM+wP^8wR^vNZfuBiGMxm{|)JwQl`Wt z<*0DZ`+Bd_@8M6}gw|mBJQ-yQeF#>X-*d=M3YH5^Q3<#}_*Yau&Jkjw)5e4iJoOZz z{GR?_%#4xVmfYm`L=SMh?1-V6K7hn($sCV)l>=|4576RxVOg{e_X=-CPYkvBnGTLm zwz^%ExK_9tokkV-1un@D^Cm3nydabeJ7;oUqm0MN8o&@Gwh7aRB}_K>E1DShEE#!| z?$2w2(=#{mjetkDDgZUYpW39(CEbq{4i3}cox=CSGKa18 zTk7>zj=#QWiB!W8ug{I>9rdS>~m0a;!9-2?vgfB~u<=G*Ne$A_#;)fjK}d%h;qFGlt?-&7g> zp7SRN0kMr#8Rp_3_kq5lXSX;P(bHaE=GWwk#C( z#KhrugytAc)batG%Z?4s=!A76BfVR@P;kd2;J1YE*zpgmVTBp$F^C3~s2D)pZ_}C(7kWSG^@pv=VsA0El@!_3FC)Z$3E;jj)4)2s} zC`cdm343E-Oql0obije|RqK$L?;Yx7Ub6xuk=s6xFnx3kjl?Elc3dXa?-SO=J%yJD z?zpTZtyjhu*CV$@k?~wAuO6EP4iUAgEF7e?hz;?24Z-;b9-)>&WS(1|lZ=`Y^ttG$~cV0}Fg4 zjBl6N-OQz>;xII{-{dz<;41((p9m2NBf|d}K&ihwZ@4D#m9X-z3gZ*T+Bybg{3}f; z!{OlgAh!xbpJ8M0dv^N&?n2rj$bSs{?z-6YXLrO}V5WkRfV6*htJXaGw~f%3HQlOO z4v0F;hw2!9h;l0GNlgma_pf^wS(aP(S&mw-Ti$h500#KJ=n{rMT~BI*T1@MQs#y=! zAa@1D@zJ^8-$FV{{K|`V29<0x;kq8@P_?885};7+P?=gtvHa(PIdNjr7+C`AS;2Hq8Vn^x z>*ZprBs{3&@iJkTZVq*&PmpxkNzeM4Z?Z-#p7@LfQTfkPAO8q!FUo5SnwkQ&%o9qI zCsMrw!mG)nnL*Fba_bCehs{-+~M7q#FwmvA7B6T;FH zhvC7FXMl0^aZCN4$9$HhY`xzzPsmT7fFBTEN}rDX!uRPhiXuJ5^SBVC#7Z-jg4XfRcUJsF0sN1{DP36kBPGP=Kw3gX1JXUFpo!IvOg0_ z^v_2W9F5`^;$h{#&Kb=NyZ8wmB{=n&Qr@?FTu<*wMIIQlE}~puBVHh~_zZX2ivVbc8S=BWs+zbgdC_AnT}uiIkJq(TtR& zTuwhJXI{Obwq5@9N-WYCx58=E;`hAX0^->2j9JC6s(V*`T`y15w!vZL#qKntvmWc- z=0m)+XM*VzoY5(rVX|KudRLIe7OyEYYwImJ>H@Jjjlbohd$%qJRwYNF7ba!$u@@wk zJ>4Bjq!VbDUNyfvpQcw3X+_|M4=-km9TJn5U#}A>`ZT15L{XA$hBv)rxKNCUH6=~J z)Nojw2K%YHUJd8Qfamfc?6=MS->Mr0)rjE*^s3A9h}Ph#7bP~YT@liHQDQ1(TpB=^-=FeKle& zDxIt}YQC&2V)55<+=?f9oisP#v7IFC8$)Si6gea-m6xgJM=W0dUl7lnggS(T(FwzU z_UjhMHRUz?J>UELTxmSn)W07PDn@4vuWmH2X80fFlUnK3_m|AW^C}aV+*ZMoG+bb^ zRmC}_^y)d7>M}>Et#(C!>&D988wh$gR&cBB*zXbi+-iLZ)&jldtub=Eu9Kn(%`Fw5 zhTOmU$?*3zm0H zFI>&6mWi}%A;y{e=CIC47zA4>RE|k6r>=<2IQa+Hbcr)!L%gNer6TR!ZBqs8p~c|$ z9Q8BWs#OcR6;V|yhWMmYr;s)Rrr?hjsWEJ^0?6mlrr^~Ep?=JSc?UnMTK#eC((YHI zP-fL%g05b#J!n!~Q9E;9Xjjm!RjbXSk*@lSW_3(iDL!A>6~DEip=)1w(B3kM&L@@<^&uk&zpc{Uut!njL`G*((b{9kHKyQTyvgXsm-%bq*^d>^IU3D<*2oauI_HFg`UHbW72xuxvn)iBh#a zg9~8Uq#Cul4Z5D{DxJvCx;2ze_pIMDuHOhNUQz7#_~7Ugi~OF0a3m9|aD;*Y5C$A8 z;GidLK9K|>r!oBh7mcrup-7 zd=VsAVSLVHTSWhmLJl?`Ppe;Y0cP{fs~9+DM4HnZ#Wi-+yY;!HB9F-__tXGMF>VX; zdmbOy1_)W&eTH5K@isu$Q2GS}3>s!7P8Jtx?lI2Pt*LrBO0Vsui~0mky(JThGeFLv=?&-IFIchpL{?_P&ZM^(J7~GJ!yw+W2W30 zdAMp7(R5P!DLvd_ZRt-h1H%t`*}*DvCypZO+{7~NhA5-5-rTchxo(Zk)edz8AO8M^ zW>q=VDnI-qJky6C?L<(g{}T-T@Bie~4ehGwkn8z`wAf?&WT;8;lY2xo*oRVWJ->aT z+2C(blm;1->PKF*yXPrxh5THXqTdm?UI@U(?bpr z=yIJg+Ncw6Rq1*89!>kTT!}E%&38P0J*ueu7N;C)}V~Y%Nt9vX45pX zd!_RCb}tHayEm;|J!PG-IH*32-&~}T1+}g%ITzT`;uh1k`t6_;wE;u^w)bcGoYoi1 z5}uTa;mRhrJbcC#S&tam(2K@^a-*i9*9h@$i0xwvonLkb4MUmvj%(8Cn)s1&pYqjz zO1aC>7^C=9&0nQSdrp9k%qT9X`KM%9_7Y5^NUNZub8C#52YH1%0Uc;57mdM5UfV`D z-s1P%@xIp;3~T=v?_XifQ`$WK$?i4utB`&vaHPDn0`K@hdQ=6+%s{-3_9<)0_PG>b z$mUs57H>l0;u^o_a{paH`pq^4ZdF+$Eb~|{yV8Y5@zc5$`Cu<9?<|U$Bheg8Rvy(! z+gP=T!;?ViFtKz5Z0RKuWmvMx1WQPyE&3>DtCXvmd-5%4WC1kx3dAHGB{EnB%AHTW zOMqQdL@imN7O8OBLFv*x( zY}g-4q*AVgjCl{NO41CRAKtHBL-g-(#&gIQB+9x_&}HaQQ19C>W;gAWWCqfy4G_1u z$ZAHK)B?QO@2QbU9^OvyLo{Lp!td$rJLI~mK&?YK`Q-*nST-A+59C}RX9QB&Q4gFG z*Q9ebpmbDTlg{or;I_zcU7O1rzgDcBCk0hgUghm<6SY;{0>=fN zWE=q$P78Sss_rrG`rGlEk)5>skuvO~rh{d}iglK(GARh~i_#wmV7NkW3k@J=uJ0|_ zA@89z^xtSrU$q7J)v3ixy9*-^t^!6_4HyYq+D+3~tj77BVG+O*tJ7B;TydX*YGrk# zdLM{2`7mm~XN*r3c#|g&Yo+VTny5PRo^&b?OkcU6x=A$n>;Vv5M^ufhJD#1#V&PTi zoEt-^zYyqNuv%(0GARv@65g7WnQ(Ies0W7lsKoNO zEJSPp&cB6_MRlWIxHgHiX|zD9`O4R(ps*rgDS!beBqoUPL2e1)ErSOcluQrPsHPNc0WA=C4|AEnZl zhXm%_mdB>rb&pNkXR%$k5<<9cp#kKIPq!H9aXX&uaq1Qan2`Aomd&23U3?z)y&>5N zrSyBw`SvY|CVX4YzA7YsBnztnPDe8dmv}Hs<(BwUx_3smI_nfX#?AOI(OqQax;z)bWBzbf$oj($6KA z!~>MDdP=NqL|Jt4&iRDY=33?~jxE)QwtP*`DhwfCBl>ZW8ENLuA6B|^evNjgWzh4} zAV}?f&v68q{hk${5kqhAAr^%|2>L{cGWH{u(6|cXmx0+M6h&ms4k9j)0DEKygrNQ- zuC8sivn1F1JYudZ&KrB?IhJ$r!=6Zl_Z>E6A6>Gw<-5RCb`lXf)ue^Zr> z2lcazpIVPUgxTxE+fnMp7O>-UM8C#}6MZN(1k7KIIM<6(ff~5mptB#8gd_RtB;iDL z5iy|>wLfbO0gdP|$rLZ^q9WlK8FuifD?bV6O#nV_tV7`*Axja%Wrs~;+K6T>)8E)@ z56?bN_Je2q@-C!Wx46GvYu#u4$dq>BXRBZljOLNk#`>$QEO-K7x+Al*Z$o#IEvqpA1w5 zNZbIHOC=zdZ5;5t0SF~)kOigHrc-QlUL)3m8AOu-^-+YT$AYQHZ9t2v&fY4_LE9!t&CoDNUp8LskY~f5xW$EeimX)i4hW>NJ)4K z()WS+o#s`ITkC@gSWr)6!)8!QBQ3|rRx3MH5}ry+xD0`^&lrpIfC6}UHxcQ5&O0ue zkL7Vr#7dOrb*f^ki&TwN0mGLiZZ@%wCs3IN{C=*E>$w+=lQjXMu+ zxP_-(C*0}b;m!`(9KagYs_VSI5;QIP4_Zi%llaF>1!67pF+hzDzYI{w{m5EqcEx^p z^HjLfxldNy0^M9lsw6d{75@V{R>-mZI|r>GIrfDcAg4N5^i>orlMOI9j!ZQ3c0LNe9%QJloyYK&kqMI)%K#}Zp=!~`wP%0 z0?9b^))HVt@wn|pq?ltBya8|dJDh;D+n?7C zokVP#>t}g!3(mRWBG_Pr%|#42tfgC#{tn*X0dpj-by5e?M3-663e!3FCwL7 zJ8cT*(RfmYY%8f4SnHiQn||jMj5LeA?y7hXvBeOkLO`eeerQ0I%4ek|wvYyN;9d7R z#H8GD7?IvO`6@LIG=0jUPMs^%TQ!%Xd(dNKLZe#>HH$Rci^w!F?OA~?Ub4wETfcFm zpiIrsoEtPJ+{*BjD??8V^gGCHzUh=Uq7KBX>~H*9}hBx3Fd~8|vniu%afuE^!8%RuSF` zw8=~@40ZAaM{nRM_o%$6aDSIVey8nE*Jm-3i*zUk=ohpLV{SU|lpC;$7lt!ETonb| z$>Q*p&ZE8D(kdrec(CY{-}09vMl}y42iOzlptLkmrIcSbno8hlepfzDf{w?)Qntw* z1a-8tq7#F4`U^XIC`hM;gKBIa6ZcC40m0jlc-)>Q;-G@UB-jV-w~yHiZmTHR0lSr* z6o_cFGfj+8LY3ZFm~$`{+Zn*plLe7dOojpUEAQCTdrp_8i>e?}J{FdyQT*5*3yK10 z{-nu%`>fp;OLsA>uVG)8TuG3+z2jScpA66xT;AESY}dsFvbt8CY<7#W`*aqB2-IL~ z*y+O?>~Hh0Ikd7_E%t`f4ZW^paX1sCOY*J@pi36O7Dcc{WjNSFPr9hOxRnp; zgPasFsgz*0##$9yF-(@@+*Gb%}<5~(PMHqCD&V{TPigx18e*j(kva@Nrzu^#DaQ8?#6+9y@u03#gD05 zGBush8PXKlKeiWr=c-B!`zV#4;az+C3hb(pAckx&`ubjnCv7iUaR09cK0M$@l6gxq zNA;i=;(0kA&d0at;1nZkc^G(2{j$;kzHM6G3>@0?eaiG>{KNp1@`@pQf1ymm`sH0L z{TndYAegKryBl_l&vv^W%Kp8yT6;49Q%WRDe(R(Io*G9z5BZn-hCB-eWcY` z!s^0PF!%27lZ1$w6Cw;{bk|q3@H=|R@P{J!-QUxNc{Af|yTM&<_mSzpse&2NCoKg- z!+IWVZjU2w;b!pO+In>cKaWS-OJIng?rPS4YsJf8!~u&ac)k><8aJ4tc-j%a5@(|f z$*GQ2HIuor!z>NwP2f|7C1LX{^@JY3Qb${WE67!M%v?ONiHK{}R!Zz2U=nX$zU@-M znrQ4J?m!QK$tCnMfh0oCH^NV|vhYzMYPKe-337Tae-Gq;AFm0NZW4-SCyiY1?Ot3~ z&^`Z;0CR6>8uV%4gmY~g+kE^zOcgV2a^*2 z1nKZjJ2)w6|8RW?%IW8eos3{1d4V%RxaUS zCbQQGUjLlV0`hIZdaQha$OJhnDLv`XbYIR&td}{7iM9D=HOM%}PZFgJX-3r;F;xfh zLV{y~HN0%=L&N#tK1Tc(XmOtNGvZGYBfban7bC_3>rUhkMr?0VfsvVF{eH|IfjbGR zMx+a#I!n@V+IsSj?<;_R!SYaa(C)r$-98I|w+O2qinkpqd-DiNQShLBUz1QxzttwO zP~VHvHR;&i@OtpftcIMeFmdC)k=Tm$;3|nZMqJQ0svi76K@W$-C)OYsd%mC9%m8C? z8$@VEH1#ocnu$sJn{9aS3<=aEEl*b>b}fV_<{ect-R;OYQN|Dpe*t9 zZK;L;b%WFc?prn1L?#v8{-fsFO(fF6VG+@Y(JTP{oqv!Nr|4@gM)O$loxp!L{6AVO zy5duSKO4)44@-hz_b`Al}4?MYMN3O zw=$|a|8^uzY2*jcsE;Kzh}s7RN4ZeSX;&qm#s|A`FfB^{A7HsKVvvLlHlsMbhRJoh zvY~hL16cS=%`ou1HHy#H=wqNs)kYJ#{ZtL8Gi>O#wdR`i_K`XKN2X}!IVkaHU_6i1 zBsXaSw%0^!tR)3Z;3)-%Ov9W6Pb@vvMQ{x6S&@E^VGyVUR4}J+n`^O-VBT~ zHkT9drX_+j&VI?rq_;Ormvn};og+r|IGM2o{|8OqwZYULkpGY0(=$K@sG=|4ARe<1 z`{kR@xR6eEKqi2LBRI{0EM+JCJ_~8MLu8k22bW*}J;G=mh`$SM^LtJPz#9VK9|yn> z0r(n)Q9NL0fePQV)8fW|7d;+m*hp``L8^Z%0KW|&QvVI{K>)%|zZQU47l2r6mwy-y zgOBsect#`JECcEk2GV%B4H9pX0-zXQ8Yu7-6jNfdjI)K>bb% z0Q~a-c(nYX8)W0VAK+)Uf7y_jSr99OXTZYH0reHIwxfN5|=v&MY3mnAZ=I|4oChnyx#}15*>3^Pid{ zhYcVdExh^b5L5CU(2W)7N~nG~wtTNQw1l(J;wRpaGE}c7M_qRCG_yu+O}9|63xWoy zJ=MZliI!^6qdSq;TnuhkzX18IgDN^8UK!YpnW>x=i^;;Jhc&thP>Lo;p@C@blx3Vn zZ5{M@`mi?Ct-u@{p9_S9M>Muqn@HKjvg$^Z%C@Na+9R}hzc;Q#4!9}>|Ixgo>Jl=l z07yo&-HyDqMn@ z?=|o&@M6`_`vXnoJwN5jrh&`}aT`!)3mFU<$SUZ_s}O^lEijP%!lg$vRJSDbKa!2Z zgfWj!jLC(qmEn^vFEkB${^@1zG6l3q32PtKgwFH*8hH_yi1QMi$OR zq$}@ff0intz<$cZHIuiYnJt3su{!*iu;;OIJYH}=X2$b`v6j#AF~MV*4qksH^ULr- z;jQ`e_51tC%{uA|x0n)Fcn_OyI_V=~fLB>-4daLL4=-liiL4Q@k|byr=&6-l}_YdlBi5Bnj0EN3$pTCR+D(DQV&Tg~e5ao)C#R zFEj28@J0l-B9K-?8c7H&yo@_u9s%Z~KJa5S@FdmaAA(5)kHtUyNRtOOH})fq0pj|8 z9Z2Fs=!QPzV=&(&S#ZfR9lq0BMiwU?T;7iwnwu8AEypq<_j#vmd z%k2t+_X-HYcI!AiQ~1I968PYjEiO#_d4Nc`az{SD8wf52P87dK?hjmUsR94PLyO~u z%ZrV8tq}L5E_BB!aG}%Kt$xq8Qb*gs;Mr7a^Pup|vm>c@eZpU#%}yLxjM!h71H1DaV#fo% zhw&_Ea~JbShs5js!i{G~FT>H@!3*%22hMpU%ne8frzm{cP~ zOUSI+Hfd$W=GuSOzT}*_Qa(|pN4LMT6M>liCVxUz=>=d%lO42P@4%q@Yq4iokvOMc zh+bi`Edx7%3-sG!O`3J{N+fps?zm8zQGCPxQ-cu@I^F+=%MQ=4+Cdv5&EjIKG53QD zr@iciCj-{M;B1q28@8J$P7eHsY#lo(BAPTrGNbhn5Z;zv0Jrw0b)xU_)VY2Pj_ zr{-+A#mJglaTscyzRIHaodX;AuIlFakY~XX{JrG8fv9VBWPhAnEM^_ zL+<9Y5LuaF6dRJKSQ5+F=^)sDGrl#x~cnR8-4e?pWGWVZjA-nx~CU>xFrR zn}xE-n7xmql%;S75s5DQMey*7vK*5Z7zFz^X`w+_Cc>3eBwmK6O31kdt6-fp2keu1 zM!#ptXTqUp9;6TZ8U@)>P5OQZ(yQCINplQ46_FQ-AvOREY%$jlb_gBE@0aGnlY3C8 zSUQ@*{epd|L)iLMx@z9wJ?A^S^oUAw2_v6M=O6cB-8z^pm@$;s3@L7G(|=d`V89Pd zKlle+k^Rm2-#H~dfUfu%d?w>h3EwR-*z|#WOla`lMS*S7gMqE$K|?QG!6H+3b3g=_ zKXM0;Tw#Da6hT-(x*=-XaF?1KQnmfKBsW;}c`X(l5-v)cs+S)9m&6eATo|VhrRe>yZBB{Y`tH9M`b*5!0-_n~wF3wBYQ>hQFHjuA{Di zOhfNmhqJzNG44&M-*bWNhTI(9$m9FgNx8E*tUV~nE#FG2>WvaZ?h|s6i#Hdc)LoA6 zUHSE=mzXxK-86JIV+SyvEwIm@dpeov_t^Y`_;kGOp_c0A>LTJh_U4gftpaW;$_^k+ zpQp-KE>bK5LKO|}rC4dcUCDhfsqAv$`&;aX-`@(_(C;}l!0>rZa1%%-ug?Xijv?01 ze0!>%oNI5(=JI`>DZWs*DrBAXQ1xdw!%_H`L;r8zq|q0;#L`!6kXR=@W?*$HjTIKqN4LbO=fM>zLC$5JJIPkHU?vwEcfG7J67$gP^YQo!p zQQHjtR#2`S1P}E90N78xp2q%Ec$zdo?z~+A;OfQ@o=Mfi;zDA4DxEwM4V#t<8$m)J z0<~`p|Hs2P$5~BfZ#NCEmad@G@=hb&)G~O?dLYmAg!`%X!dyMgLN9I11``2y*&8s9z|4A%6CqW(f|& zS61T5it`q0zvmXLHsY1w^*qsZ7*&s~vbN1J6sYb;Vxo7rTLtD0@}}R@>iZQIl2m?G zO5I({kKhwPkqEco25R8{1EJ}KO#Hs!dSND<$`fB)GOThy&WrUZGpT*;%EqoU;c=Id zI8r$Iq7J7E*IrCwGvMkI67irQe<>AH!kCxRY<-?BVE0DitpPF{*?qr&$_m^{{ctB2 z_~Cxf3;jd1zg%Aky|0=qNg)U5}5YmTla4{rQ|9tead#pQm_qy5Or zr1m;CrFJ`vCX@=-Gj)qBx|%LmEwJN6iFI-?sF+@l6Z9cqoTkCy%%5YnAn_NdfEcD( z@Yk61nIOFc##|w0)p%SiOked7HQg(Gv}z5$C1k$*KQhAMuM)m~ISCgDw_bh(>xH7# z8jAJ_Pp)2t8wJ*)(`S_|TR{J>V5C+IXBV z#Mw1ej90kdZp7h&%|0sem%jfDyuLRd?%U^MpKF$W181IEUvNXBd{J5oRzHY&OsbKTjTXJ0poHe|GG#l+eDbTDD#5y5 zbp93B)MUmdUt!3-1}l)29ftp4*&$aUIP;5*uN)y8Vgg*=_Iob)n8e6-`Xjs}4?3OQ z&m=0_i4N)VdaWo(Yr||Eu#jYcC*tP<{uBTXQZ4j;3CNUwj}vn9Addn3fjTLGm3`}R z&OVr>Gd|)FC*yr^iH?-r0cC@rEa+mPnLRB}S_Oa<0P>SSEkuGi2erHcidA3xvAz&P zS<`iPeY-pu?g#A>USAgn9Q=ptbXX&Nzb=l-927d&RVbKKWZgU=xn~tqyv}T=fRymr8jVKS!|4&hPbGy)W~!zJxXVdYtmV&EMjw{ zwV_^+RHq|WZ7P&5O}B#L{q&hzNHd`cb2BZ&pVwQGo{#0LK;<56nQ2LUUUJQ}`hP?% zxt0y)IE47WzEn0p*fsn_#ZZ!G8$P*N%m2 zZ6DV@G`R#w^Y@0`^^`57jNBUZd8oimU~*1p0~)SMKW!v8vuR9(dC9Y-ncSyYDpIJr z`KFM+ex_}jFR29QK4S^9ekq066Pr?jC>IZ8bQt&?xZ}OUIzx?HW2{+Cdri?-VytOR z`(vX@esih$U|w|9TB(AeR9I;m5Js_A)j@Xs$c`P>cT9V`FtxvnV)k?~c!%Y8r>uk! zkHLG$GV~b$1iYCzxyBf{KphI2ZFBujD@wul?X>8uQT25o*`cds@AJW`hna%h8f#F& zPK()EXgLj*-Y%CgYr`bCnY?8~8s+U1KHH$i*M!y$S++{x0Q|pAD9gOnU8Df*`c^*P z`oHtta=6>l=eg5oFcRh(Z{A&x4@jQB3=m#R@^AwQ^=7Nyvevr9B7Z@G)042@AT$S- z8%X2}i48f&aT%B&Sggv#2QG~O{kQG(J2COa38jSB$#*0Cn-9$=){eh}q>XuXX)!E> zt8h5Wfi21GFNO}>@7*RntU|h^w0#RB+VWt?(F68+cxOSGUplTot+(i&Sz%l@!*(Pit)irAemJ*x zzT}zMr_hCSy7@#J_jrz<^3PD9-i?H3XZS)jx00$ku^Qk*1_Xt`ih6m3rM7JC4d)%zd=lO^C zL5Y3)+rp4G=KNgHI~xHf?@PH5`@lavaB9E#pu~VHoia!xVocDwIQFul*gCZZjhZbf ztIsGDpahxK!dgMaRWPq`*@fe#gYbquzuh$B{Jt&}O!GNSwt0Lmuj_c%DG5mu?6WC{Uu-Qhw6hB>DE$9kyRmL#YD5&W+BDb zdCC6^-eab%jt|`|l?5c_@yr|CNSrr<4}tAd*+o-J!1ol>>6Rs=1K<&Z;d>U)0mJ7m zb3pMFYc^RfyGTv5yqW-}uE6b6lscuydN_+G^?E#6gISPccA?})T;j11s}TLh{Z#4+ zVb&YP*eC3IBW`S^x!6L~C4@Ti8qMIeD6_Jqmqz^Rqq5YzqD)bGT78dN;Q;b-0G%iN z{>B{qxKQ+FW@!0<0^BiFaBlcKy+X~KBk*Kl$D3u`G_N*b=|jdBtjmsUi8oms_5Wcon{E;q~l*BUDw7clbPW1@qRI;Y9d+YntN4<7}hPQzf{!YT_P0 zj@0cU)|I&HBm_Vpm_t03$GD$0vfP?+=c7@c*3y ze`LHJGMxj@6qM>{Z-yf%$Nn8TLDAQ)uw&0RDn7;^&X$-Z=&eD|qi~$b+u>pykGF%4 z{4PW1^GuWk`L+ks_5+j4Hp<}hGN2F#>)bUjVY)n?`EYT1>?>r2k*(hc*L+{uHh$Q( zrjOlh$kVr&f1osFJJQFtBk^g$xh)1;gsyEGTrPyZ6$e~Y+FNO{+x`P9j+CxSOvlw* zln$=-775jF72Dq6k$#$UgJ~PT_)>#+&FvZW*h_VP;pQ+0S7}4MRDXUa9k$I_-Wgx4 z2|4AH?j(6Pd05}@>+s$z_bJ>vOhK38yJ%YO_8aVCQq2yN@pgO-b$?aCyx9E>M|~1} zct@2}&`B2{pThG&0GeTt+n-|>gEDG90B}Xk!U8JK*eN&u5{E`6)L%3r-IuqJIV+&x z+-Oo>LYd&(C;af&BwL?-UF>{l4s-ADD6_)>a1UH{QBD3IN%v8@QQT_Z(-nfD!$r{5 zK|GQRsrPxh6~3qlV<*lJ^U-3h2|mEng)#AqqR!WXRq9*2nO8!00a8@>R1pQ8xB$K= zF!+8Ufedsvi#q>)A+p^*X=nNUU15x|lQzEX`pV5IjvBRIMgP=JI)w8odazgC9dGU< z7%M@LuJ`qUBQ@!Y(x(n|f%Sz!7bvg%c5t8@tlNK|U97d&0xDjyA8=Fb{DPs*^oh!$ z&g3Is*x(z`85`+0ATRf+^KTSBd5OxKUtsKHjk|r+wmn^8c#r8E|33fVg_({=>W_A@ z)O>h{y$X*OI^s4anE_kN(8wXY!X(peMl!`3FWtSxh|TwKc60~})v=5!9Wvv!_RLtMPH)s zpI`8GEZ>RvJlAOA#pROo*KeqK=|)-Mhv%ERD0X32NEpuB=i>QJ(8Fwl{mbcc@GrTj ziSrAxT?St1B1B>{xyV8%x>{AEl2cBVJRkJKHdOT*2mZdfl4p1StDNN71$-2FJ_}z* z1CB57IX3uS0f)rT`s8rk;Kk~8Yo!^9AHrw+F2R>Xz`0y(X@XDm+?9v^1@Bw>5Ww$; z|Dk*VoWR3va085d0grs+Z|DnnGvGQg`RJGmz8Ht#3vvf$XnR!f4C2ARznG`(u?OBj z*TLtVd`XRbLkwAvm1vQLl$_%l#CkR0`YfVQ#4tVKhLvp^P|%UH8HpuOARD}J%fZm6yoV8w$c*D7Sr|2$tmNy?J| zALoMaHxSGs6?#}#CN{=e8D3lVMR%|~G9;I5FJ`d7hdyyq1`u=mg|?lX4N##a_%5A2kM6Za(Y>o@)=`2*@>KXnL(yr0|56|3?s&e0FSukp zeaG|pKziBRCX*8-leZ@ZM#6!cvFMJcaUi7_KGX<`l4OWkpAHO-Va^oMPif0`nv}xQ zx{!Gz3(bd2c`X^d5(sVpKrKy=!v68m0I6!rKxkP+X$DYwEL68)0BfR(eV(KNN)rij z91%%D==@~>)EEO2m=SAp@yO3X^MQ=05_Jgwtkc@whcn?*2n>7}qtZ+!pA&7y%K2oL z+JH`}L|K`vIHZNuVE85tL&aDa%^lCeW|F7sKpn(ATl za3Dblk(j<4%P~TG;8_9BB!-Wipj{9L-OX3RGl37j`y6sN4h_UdPwmxWn=>7;i}Z*s zgg6bt;xzacU@Bt&1t9{`hv8iU#3>LSxf^z6f|JZ>CR+-(XN?_gcp`gj z*4VLG3vw3aBBA>IWSjp{81-XAEs&CmyXmLrL+`AJ4Yxp#s)q8vUWC~E1w-jE3m5%m z%!(B+@oUBdC5Pv}7Qbh^0fG2Gsr%BuV-%0V_-}ir>?|HsF&t&GD z+1`0)=ACz&V?RfUPU_fY3YQ42RJtv?1Zkr!f=PRRh$Xrtx_GN8@jMcPdXPBLi^K&z z&0VECn!A?mh$xBV^&+Mttuq4g4C`MxNaTBw=!F_9dd(6Od(kyrVnQGla?zC^g_2l| zk`O{kw?9BE1L^8NQQK_G`eQM?uG?Wj8b{kEB za!l`qhl+#wYKTWcY!WFd*qR$iVMswskdtN6>0+z~sHYPZlu4v1QkN3*D0Q0GnO>Ap zLc<`8GtAv+25lpdcN=?XYdEhJ;k{^|7H-8* z#uz@S8--)?zT21;4jt%3Jrlw#2vZ@j4H^s9A`L+vhH=H0 zghNn47|I75}i(KG_w(|`82Bjm>!kiH1v3WPQY zeg#t9gjj^|I|RWX*UX8s3@M4_!>j0S`*W-7a8|fIqUyQ2Q*}sB*7EQ58@s}*KB{9h zhJPZlatGW@fm5CAF?K9R@8$&1PA zw66@YA}wPXYCm7U0UGps4wC}y@47SEv2I05MQinh~;V6MRVe4cb(ZpDhxWtQe%3@lB#HYM^*lRYkS!^@wt)iZccj2ch zm?NeQwb_3~X>BZw1a?0gN8;a6TPTB)-U&kNQV5X^c0E2^&M}@p)3O{ERi_xS zs%iXWtRFvRn~rf;$kQt}G$5^pqs7iX!7xZ|%k3Xktl=KE(&8Oojs<_nb2*R1St)&b z1s0>dS8pLqi+}bo`W$NxkJAgT8hAURMaG+EQNtU?swsNMhQwgsK|Z0Vm7j0L;xoOm zFv2cx4E)Ezdzmg~1=1y2VyrZ@io_O4E{65TSwiZNm^;=N3kiidyf-HBV!a=WhkLMC z<&%k5Bt{=pM5@I3WPz$9(s0x{s>L(j z>R}Sbw!(XnmLu^pJcYKtQa7C&!==DE;|>mg%kx+%Vbn#V*SHuILJl;Og-v$v35cx2HK z+cgQj1EKOfcUeMHk>;X=RCrV#Y_L71L9Hsj1*R`W$}N#`D1~$S>tBI&zDx{3W7}|M zB!99QC*yJH#%Yqi8h306Yjh)}!TF3@X?+wK}nk!Xk}_ zttwj(Y{s_QV(zI`2N(RdfpOEhMwZj@sC*tMrG{8Lm!oZWk_*2Xz^_yHoUk*p8u9< z$T^%lxxnpQCd$z*mqlVqAC;Iy*s?omahuQ1;k_D;bz_zm7x?n?9j;~K9CQKxL(n3*cigH1)yPp~dEL~}zeaxRpM=lvd&aD4D2oF&{F zoH{bJ@7ZU`l1F{Nn;9d$JE_s{iRjaCvSWrO`VbN;By$|*R1RECAEL!+!jvdI?h=+q zjT^Mr&$MZ{B;M_!#C<|zR4RT_xE_@?^aJQOFBl~mAmla3IGm&fG*DuvkU1oNLWzHB zBjcVaBX9Ekd5v&>WPf=poIop{>V*SQ{70|o%4=XabrW%*MY)wyI;8Nw?=wD^SZ z;gHOzeST|QIz%Cj!N=Zr6P^?o21=Y4Y6e;E!VUvwOa{}%ogZH_GI*TLq1 zmi>YH!~C9oLcBT?pA;pFXW-e+YYdc_AY2$a67zyAW+J{I6vU(|kN4fF z-vk5KaAYy?!b>r+0Q%k-ZRGYooXd_1$!LcyA|vo_;Dxg>@%Wg~5i@#_0XCDN4(pJX z61Bp}*hE9{=_CUZm!Cp}%gqlgDX=*-IDV_hU#a0#xugX_SQ9^H!QXv^4I>AR8rEm#EwMC;d#ofeWz(^95;~>;vfV1N`35^oNEp8lg8fiLRD81Vm0*9~L;rHC>Ln(KhH(X=5S+M`E2;m8% zY}fi^+@?m9;c#fUV7Cgx+J(*Q_w4om%Y}3UCC~QVaoukGvnzb7U5E64cBwY3_;fwM zwxLT^H4N5oDonzB@76BD_1JaSq^e_h*StE?nuZ&`iV}Ogi>)j9gVy8xb?ck1sep+& zJq-6v9ke)W1FnGvHxD$p85%_Hsg#DB%?-{ydyCRjVyl;`p=)=Wx}5{-4=Qb-1Y8TX zs#bhTx~ziKEI`{0FICHM1Erb;MdG-`3BDx06Sn9e;H->w{hk~Cr1HUa`n4aKXlK9Y zPhmk~bl3;pwnkMES+$h-&M9GPS#(6v@AZ_p%S+G?8ydj5L1IF5>7&RY&3_Bw>HgNU61fdN*Kww`gT zX3+PLJ|w{4ekp9%4#!o;8?>iEf)SSMM<-W7QMQ2*=ldA(2?%q2gDh%Z-53hhWBHYh zNTU$13TO3+_^fb8A3bDL58eyA2qt}e{~%JPPA*RD5n_@!{F1OBX*R`qg?}bxC$91} z-DHheJn~N>$^QA-$NvU?7UeYrPfq6Lusa4NkE3wEP?9`?fdjWkSeyJ113OO=K23gz zsR0~EQkpT z?H1;yE`dt1lJH$>{v1k-mf9Al0Hjy@e{pS;9#eI|xfX?vxKs^aF4-+vQJ?2$Khlv@ zI7jBR-!u4BUc*;QyQgB@BPne?ppW zh>^=LoRFp(V&&8Ya+FQ+BaNylQVdi6=?K$DF1#(AO-qa#)8FltD}4w4Mx^pVAd-;sR|4fPL3wpu(@hD8<@wW66B>+- zL`JhUgcS2|?4A>@rVow$x;F>-1UAF%WPn*b0TbII1Z6xQo_jo!TZ9Lf{xN$56ZP{a zbcC=oBXb;EOuJPS)`#+fQEv{hicMNh&;0_c35BpmBz5`YSk~CqP%WujA|EMjpB&vZ zJDrLC`6F5-^krl{BrDlqM4AEVv#kjQkvciOq>g1x@S1N|o7!oec^%=`TIKkH-}7a& z-}7p-uqbn8(JSiywcpmsQ*{^Nu<~MemeE;r(_3&X4{HyT|6bp}itMU5 z{SvdT&YGjn7n`!UTQ2(Eu9d)pj8bIo8o}Ard`s6LB8D`x&^5hwLDwXjUPS~G*!y;* zx9k2-5~Kk3bWELIqyWKZ0%sH{Yli3hFmwjmU>l602FWe*5;Z6jHUsc@tk+3v`aDZ} zk%nzjA=YRdL?e}sZIH)-uptLA{@edmY)+sUYE}u84Dsq8{QC0P#=IuKr`6x%O63T> zwDorf&I#dFLxhfqPjn-2P#P>MfYhn$)Nn#!@uyxO@lF2Q6%9hgGed0j+RO5=3&F7E zS{1<;f*z4+a`}8v3M7e`$+2RwLCUoboJBAopd$nwWH@q*q69P?Zma2>baO0q|EA6? zGUfq+R|PYzMyyqAkgd~{F2x0RlCITvj+da;#82GEQCroLnd;s7EGIseQu3BV%x=Fngpy z5!eK(5TPVz4%gRj;JSdL+Tm{p0-{8~%{3#m+0TG}#ng>f5JgplqW1z>gaqSx4d!)l zw8+O^px5OV&&6|R#WUF#$Rr9s7*zSGCG@)4nCdV`s(Cw9+d7M^zO7R=>+BeKp*~>E z)?tuJ)*JQh6dht+CN71e(eLSa!1WLoIItr8o)7%gy2#>S&2&6tmcAQ-Mxoj~V``sA zp z@6G2F?k|x(pX4Ryvu+JLXLa0Yoj94AQ{ngcdY7zGjL?gd=_SiAgJy{E{zyBxD8^bU z;)prc5Pc-5y+9{4e!4VxyuQ1?%mlGfr{6N5rDbUSdP;B8ukd?*@fl(7vqiv=!}%!| z`aM~IF@h~JIzt#rQbT$$glSNlC5_wJS^ zWIgrLvaT~U-ZMnBDmTLOZfT8yyx9mbfB|Hr)YeYVC~c1f1*>s}e!a}WxT6Bg&gjc; zJGgGQ6xX&}if$RcZo#_W)=h3#44>3aYj;aSs!i=-I;Hm&DWqQMUEkm64ppXHRCY4K zbEH&p%_zhcKZMvF5Wn*vHjhT^rUzj=#2-PxkZ&V@Z$Q{BsaoPhMkxa=73~}%+Lg$W zcwE1hXh8L=^lMucLoV!=RvS{dU9h?4%z`Z#F=r|n5m{qoM1Id3{ePABdv*c`|E~0; zVL+E57Zc@pM3#dZG01^NoOhyBr}Kv{6!}A3mofC6=O?$DLpMtCEm3W>XrtxnXD*)U zI70^u`ySHU{GMgK|J?_E&tttGx}JXigXcw;W~~YUe#?Q<-gJ@|Svc zrP+$RmmM8wJOUbj*g4Sj*Z_cG^3wJV=zlkz((iOVbsCSPokmfGG^@UIQ6rO_;i6xu zbqcFT>u`%uJ6dbQ3fsNmNB@1JQ*P_lADz)2M%%g*kJ?5~ydQV8Y%S4!Qt1=BhaAXyXm-+EQqyQ zpz60nHy3UUP;uZ{jXu%u_dplwj?eDUo~%H$YlI;`ZL;HFXp}y*#)sm8&k)%7QN}Fa9P#Zeq*nx;>yBT?%~q z&)(nU^DZp0#Pc#y$)0q}m5*MLb&HY5ZTHYfB(ADFe$NQ;OAy;f7CFD_3XVdV`Hm+o zal_<3_MyGpFH-JuG}0)RRK6~af9Dh+-Y6O?e~~hlzX+2g(kcKluhN*A&MDmS=uop! zpXlA-L&9vJ2giJ<_GXOV^NsIy*!h(18K9moL+Zt~A4s+*j}fZ=;wsXJCY^HTL4{BH z;`FqS-LnS@5mH+P@xzul6A}w5{hr}{2qY7tNV}-O7gT(>buO#Pp5sEpu1PKSYtqI2 zKwgjisTh5sw4EC|TVg9fJ7`EWN{ZMESU*Jcqhg6Q)JoxobSG_tZmsD`=Ww8SzxLKb zN0B0f6;7b%UQ%QM0Jjz5Mg?_&(vyl~6(JW$&R+l%;q0N}x{!NAAafcr59_a2i7StX|*Ir#`#{fp#kARnphh>%-C zc1uNTNU4a}yNZ<;mX?&Z7sV{Kz_@qD@r12{o8d_d_JwAtxjAdCS!6?%Iw?`4rly4f4$8fcTLfv1 zCIWCGhi930hGhr;8GLfZ1yd2~2mwxGtXHMCk(YVESK?YrBdQ%&M4-#FkOB!-zbDme z4^&&q5*1;HJ1%5{bL|c2hN9Ab27rcooi1|Z?DM*AdreSNuvqf_yS@=zAE5wYnc&g?f4@XrcwnVf*h*>c?afvVBUq837Vjaehdm8 zzh{qNo{)-n3QH$s#%J^+Eg38?Ayb09htNq+s%lG1Lw6{u(S7gAeRr1c94Woxqk-(td31Y6>)^Q`k0Ua{7| z+~k0Hus~X}c2O5iFIh$Oc(#fr0u31k8JpCw8yHlbh*p?Hdw@xu2DaMjqJGc&Jv-q4 zVBmj$&#R?yM*3d``$hK(1p2RsK`Atm*yX~HB$8mUnUse@A3w3|@p z>Eh=!y`FddD22W}APYa#Y}b`dDYGmpjj^Wjwuia0$tKZArCDhxnAkgxN9ni~kM}q+ zSe52kviWmBvhX+}&7q`TPgw6P7_~inaKJ$Kh4g4iHsM&s7CO?J4njDZK{(oUI7d!M zrKF@a&U)}(OIZwmu=C1FU3bg$Gt!me=OGY#^%)x^Kn)KjO6uM&YL2xy`;644A^*Pz z{%;2UZwLOxz<;-<-!skM?mZJbriF-x~6o24Hh+|0-=F-yNsR`Z%1lyaiE zR0L|IF-w|Iv!sH2b(~-lof%+d^lQ?Kg-47Dwxr_ZqF`V={n<$%no_*pq7!Wz06gIH@+F%)yoz(_`P+3B583=^hs`5h7`eR66 z(79j%5>U;06FyID@L0e#TTJvNRD-k8u1*)&;H#y!tF`9<7*rJw^f$Wpm&yWlk4z@ zNIcR5_TZGCn~`Qf$;OC#eJCXqtX_}ckvJRw@bx;u-jtizlJa#PbWDhwM?r2%EsFWQw87>kXS*E|?o?V%9j?j(2`Q=b$ zV>xqN#~#K&t9N-6S<7gV30-Rr?EjJuG zKmp1YEMgE2qEJPl@jCoR;IkO3s14c+ln7Bo5ecirxeulmhms_Zo_1<)36tE!0+N1p^dYN59rtYZzh z(hL;$;O=5;GAdY~^E&@o~F>1x8`^y^hk;3QJ+_eh@+s0VS{a)PUFAODhjE5Jci~}4T4GGfF4R|30qKx$0?YQlT|g5#~znZQvC3OnLsaE$}0*J z8(_D6NQ>ow#3Rkr9%7$)LSlR%txpP`tm93M!Bc`C2?5zW!`=XJVZGi8OlBomE61HS z-8*kC=sLHj(CunbqNLx!CyE3F1m}0*R&l%y7D)0{$$Crx0iJNjNK|Y*? zdVU&AFCKM?+f$hFt03Y1HE|@D+U0hj;la9xxs%*U_e7=T;wg8!a)M(p#2V!|$0@g7 z`LN@#+d#M02c?%@RDb|?;+c%^QYV|C^Mn2RmwE@e@2<)OzF1siC$ZkRMf5EKX;vS zrzurV(!pH78|BcqUw{5nFzbBKOdw9+o-`GSRqV%5ZiMn;pqx=$xdA#~eGuL~s|;C)EU=BbiQffooiXdewdni>@1f?`9wT-u_5TJa%eUdE+2io0D{$?#Sf#hB3#HS7?bGJ;_KuY@ zJL193)jw1__qrUzv5Dh zDy6y^=eS%14~$S<$kgI-I^dq}13nVC|35wm?n0gQ9Mcx;_K!7aH8vQPo+rgfg~vD= zd=VeNOhBsPXd&#Qx%rXfWWq-s!8EQ}V-if`o4<1-T2@1 z(|i49dJi6R(sZ#|$q~>Ljx}*I=Li4|6VUeI+S3KW&V5p{W>i|tMH!@QNgyMsU@2wk zbvzh}V6RsfKI9^)>cUfQ|3sPdqd3w41GHcdG|}kF(%*8;d=IgcAxwpUTKs-!Ql;Ut zQWKiVjO#@ey`98R1C7-46RuLDK%o~*+Syb1cmX(ZU54EoMM>Dk}GvLGQ# zq|8}~u_Lj;o(||fS&#@Auy@wk^E*|PuRf%mqEw(5Oc%q0Nlpw*d^qrQ_OQdI{0M1i zh9S)ejvK$0M%s?pV?+#k#N#G==T~-5Ojmtj{=p7e2$-LJd)h7m*+DjfD>b;_Twh*8 z=;5+A9PoBoXtTP0R{iJE)h;r|7&6BH3^7HNhn#ZHQj!62a5^lbFV_d96<-WWFT8l| zCM`}K#=$R|<7}fz2O(}Is1*cp>_FOIU8D=|gD&j#E%n{56mdvMFsN$=utPhd33jLv z4uYE{E~++m^<(M5PO6q1WM)2wSM0(tF@DeL-mm|#0FGl}{MZ3lwy5-12UZC@wSc%{ zV^&^pky%XElI1c$&-N64^arc|)^(E0cbU1%+-&%N+!fPpFNMXGgW9N^)_SXJQm34X zX{VGEyXPM5B5lCR!O%uXhYZfb1jZX9%q=F8laOwSK)o~2zKXy7-}H5~&q@v0*RNV&|7 z1NrG%jTRc8uWruNwgW(A76n^J|#hnv&Si?>CZs?rv-5}}t2#}2S6xzP}3-XD3 z3N!ym;gkWjRpu?JG_o75QE*k<5H7A+4^G6euY=;atI>Jjw58+HfvsEJ6O?v}I|Hs< zRb0>&L-t1na^Qy8<^u({&l$j4EbSl;YuGV5+wFQh`%hrTzS#A|OGFo`x?5dB94-b6 zi>F80hJfc4gU#{zBEEf4WZGHHNtF zs=UxL@=N;9Hn!5_f{rW|>aA$gYc(#S^_?i~(pcf5y6(MimNf%OQ#148F6m{<&n|50j z!ie{UX)_`R?YKIfo6Dg+#W4OKgyl1$A8wJ>b6dF^uBZp?L)%LmlWJ#Ezx^lzw_ z@(r~L`Op2H4Z^aS(b|qaCgJAgPL~SyMsW{uI(h_p8FZP{BJ$Le!Ur?6@ZW?>GqsV$ zkkftntSg@z3(`vkPl<z)=E;-<-~CP)=dEwAB$}pEAh#g+g%wiN!+vV~My?nDAIE)g=jY9?KqI z(GWCQ2J1_=no1)Lj`ZnQ<8+ymcyTt}tN^j+_0vQ%^%Zc+s)mTkdJr8F9O0k~l8qDY zJ~rg3upS0HUi}`hV2U>+Mm!8s86(Dn10In^81Zsrz)XiImVs~#E+K@LAib(#FgIP& ztF(3GACEDS{~QK9hUAvm)j5p^d3__LVZ?ns+4_T4Rg=I!9tSR>stwzZq2yDKD7b49 zd$0=pDw)?#@Qk=tB1HZer>y%b?}kj@$L;T~D7cAP5x=0$t}01{Di@hrs7hwv{5KRq4@wm@R;?12|O5I4+0 ztRKSMxrqG`!ix|{;mCQ2O@w?3I?4gb42kr5rk2R#j4;2gwEG26Acy;92`!zTN>WA} zDC4f=6POg#d8hK)O{ftP7Csm;+DcGn5A~DUHj2LHVze(7-G~2|in`!`ZIS4TO9oBD zC`Mc(FB;A@R#frj{0Ing)jXvr4Q-$&_X@;DZsrfGNua zfte8}g6o#*bl^Q=#IL1`pdUYIO1Q|>q9ic#)0=JJP0I*?RwIUUB(@Qh%{8&BBP%9# zM$nX2aR?3nSc(I=`b<9udRz=3#YyL2Suy;E)cI`XHAz!9n>%b8?ED65?1W)}zxIO4q()Ofxs?Dn7m~qc zAUXetDauLE!_w1S1hwG11(w~iewbg-%d~VBR?7C!d#M@>6cK0t;)3H7_%d3&0xA(& zyygelCcWBZ6y*Tk#Q@Ic25^>MiIPWhBic~r80Yf1(GErM>q#Zk_|F@6b0NaAIZ1I@ zli{?l18`kV7`#>mvN6tj(a5B>)=w9X&WW-q4k_O7dy@MJbSk>z2Jv&P_A9E-xX3p6 z5_VJtkh2qzJ_+H6!4M)Lzd@e>SJ6CR&N#`;@N#v#F*)QwRUAO`QoeB|uX(3ZuBg z&ZeWzZFbV^tN&@Wv5ySQNZW3Zg?1Qfya3L^8UDYPq3y#!0Xw}cP@o11JmXM&I9NlA z8o!KVwDM{>tk&22QaQ3}cahSdU!Qej5j3|HO3!Hhsy-oe>P6E0i|}l5ly*BRz^}i5 z16SI84pQy?!z{H06P?2>drae<*QDLYNQr{>kdWCNn1e3#4^;S{{#gYRyLWs7D>ag= z)PZ$6r|;??1AB2wpIEmtZjh6#WW^y$JCI+}M*#VtZ&2W%CmSf1j!h2&(g-#y@dNN4 zrp3ekFPpAA&H<1O@1SB0C~mHJ zLoKLI9ni6cOfhTKe43RKtH5$8YfZ6gc%pjh_qf32XEL~8{SIql6|9*yh*!g!0S(M# z4UfelVbBv=JYN|3MAV?uJyMTrHqI5wo*Xyy->~}_F7fgrQ@`g;FGDbst8RleBmCn@?V#sqXA8+zGq@F&TR+FY z2l{e~&rkoOA7e+6P$CHFd7pCL6LghlO*6J++d=z?r z+pd4Lh>NI?t*;eUiBp9$3v=*8f@k3<-8(RM_nk73oTfsZAK_+1Ol!w# zTJ+28e`E-xx7Bc6oB2bpnafLGxU57KH#e+}MG#uO80*0XzZ>ldw3k`G~M-F}XYP9{m4w z{Hw(>%Jzf*;Og``qJxY>2jRlam;U?p#AZ~{L{x%E8v~BkGKl~c2WCVhVMu8Z7JYt_ z%7D~;KjTh7SW9>WEdJSC(Xas&>hsDOw;HsbSlr|%Y>504Xfi9vv)~7w2V8azF41sW zp_rdxP&Js#BLV%C11^x5fOP>c$&Eb9V6Of!kItYSF%WQ$+Z7DTcZCL&*x&IF;pqY{ ze-Xbbyi{Hg_iG;!BIJ%q+U%rQ$Cj%F zU-=~PzMb%leo*yi2Q1a(nmZL`E^spL-9bM~yRB%%WXB2~X>&HK_E0jxf4pNunxqjF>ohLimD@n=7PYxUc*M7EeAizP5;|ZQm{WG z-?eHmdp+Qsvd}NYt%_lP?iaxWZd$XjYGoSL+b`^2nK0~jKLIqwe;2Oz-FBLRSs{ym zHt-YI`Zof`egiJLWr-k04H0IpRM}+yzx=!G(i1Ae-ivUbXwxy`qir8X3Fv{dI9Zm& zS==F2RFkume!WqW8?5Ph%~m}YewMb`$tp;5T$C8Afrr{#XyV_!X~4gG6Y&byo{)4c zJL(T?Q+l`cM%3?yD>Dmh+YW3Cg1OjfVw?w-AlRt8o~bU34&XnmmuOkGK*!g>;dvjh zQN&ezz)v2uO{TU>A8b4D%*6V0Pnc#N*mk04SOw0GsDHzBU?aZru9S2PXMOEr+}mJ# zX8CqYk7}~GA`Xw;2q~=d*uR!k_Uz?DfCOkF%Bu@e%09M3AwP%L~)$Se~ux z^F&HQ?=w1TsZY=>F;bI#!onqaOfT58gtwMdQ={Q%c~%|czfA=7jr<_a&S@80c%$}B zD-XLj0j^X$n}J^xwm&BhTVZ_qxgw}Gzo?U|2ZjulC!VGe8^uYPWox4A`!-cA^KO zzc-IvJh{GCdtAhvy&)Cej_L8ZP^wXU z)jr?*s@n+L%Lv=c4sSNu)A>EpOic_(M?bl6>RKl}8F2b)=S6A1;mraHNavdc%bh4= znUmD}wGZ-DB$Wt+_)}M9YFVHLN}vC~YbXmIg(@?g>3m!TaQ+#>yk#+IZx)!Hv!o|S zDm3Z9v!9e0O^tnzB-hj|uX1TqM>!QEa!4DR-37w_WpTDf2h!{*{1md{9yG0XhKY38 zMTs|5NweBe`XL9_+=2Yi2l*_-JW$p*9hBx*K)nX>@c$%Q9JnMz2*ZwJNjjoLkpY|D z=iz!vMJkBVmx7E%RIujGS(>wws#-3by~Wy2oxK%Y+v|C%kKytf;pUn`UYBdld!X$x zcTP?L18K4eh^xM5kXseTxZea9zsD;+yQxH9-qJt%<*npLk3gC{llZNhG%D>jnG;I3 zL5g?|vidJ2>wcAXqqN9S+C60DMv30fbg;o?FEjVHthB+-IL32jWv2UWW!E<{_vWrV zxKL&J@>W=`(y~Qjs`G)KjN<}QnD|65VaWPD!~BZC)wm3<*F*Ka@0!ZZgjB0n!R-g$ z>jz+jx*=SFU})HMY!e?+qSC%5J#Jv2HXMDuJm@z*1o{hgY+e}{K)s&g-V}Je(o3$m zkp?OnLOCWS9dNvyp7f~ z8cRixo~_tg@l8cVQ_z&(T|rZRgV5%>I}enQ5{{!J>e*{##~>j6%~9E4ihB=23WQ7u zsHmba|M;ZmYjMcOpj1#bv2d8C2(H!fwhwv~9AEd|YCHI6eC{ihl2Jt?o^WvWK9lTn z9zg$rZ<#m*1-Cs8IlZ3!J`w!<8%(bAPg~!wKpLrOnHY_HF2X(adiFF)u(>y_#uF6h ztbDI$Gn`k%f5Ged^W;%fF|3TgINOk~dKifs?+~{NOcP}~c-8B9&i4n=EtOuCQubGY zqBfp`t8Aj9uM+;>6W&{siQg5@ubF{g5Qe|7B6y9QhjC&2|ya2628RW68q0#tlH@IKeTz0&<~svvPDtTmM6^UM?eQTZZ% zOUPNThxvGXePQ}3KW`mW^z|)D1}+Dn?4pl}O`#f}=XO8MO|8S#C`o2L#P0z#y(@gX zUTdr326Ktr?AC}zBpv|S3fy_G;tz=u@iTIx6^w9ucmq%xEJGv50y8_#I=YRxy1m(_ zs#_+8%DPp_^y<1|MHexAFAI7eid)mq2%#a5ci0b`^vY{ z;7Qk9lam;qe77O@H<$rdMvk)(IL;<;9WD{*2ce|#9NqBUA(F7T{k3Iw#T$xeGIOqyP{BfX?=(Nd3s6#klJ$XBhyd~pwDJo0 z;P_fk^n@BLjn~=Dt@04KHS~_~(#BXU2zxi`ak9{~F_!wNPq@5ss^a}7vUipUS(_$? zoBKdNrXknoP4Ki`*y`8zMn!j+{&lqlfGG5I(js z#A>mMO%Z&3od90vQEQJBNS7Yv&r7J~%q^5Wp%H6lScg2XwCF8N(!|nG^W6^9MqT5W`O!gzmuP<#uvi*tj2?;!B@ih z)W+XqB8zW>hCP@QT~$1tKadJ5NriOD1v~O6em?0;o@RNLm23&Ep;_~GKYrYu{BmbA6Zum)@O9JqKSa?d#@hu z8P@QXd~kk^)y#9&7O=^7z}X`hw~WV+2rq3(jb*$<#>RWba0feBs@k-rxg`c^jQL2s zC49amYw&IO=!pOJSaMI_EC=tJom?C*B&dhj6ks9i@oeeIGlKcigR76#;X@LLWEkWy z$#bYTvyKAAH!~6Do?l{>uaP`o^pZ~#fU6JLfE#l7gNukQD93S0Vhl)|Pz0No1z_4* z)YqidEwLq&I<7BA`rE!RjKm*7UdLQ?3E|8x!vQY0X?r{^J|lqO?Aa~NQz3m~>cK@3 z;6CQ_H1t;0!87ng<}10SGNFIm~d6=RMyI*yq9WKjEL2-wrJCi6$j7Lb$U9 z&f)KB#*rgo_yctdeE6e8sbMW_F?^3iH^(Y@-~$;Jn?k45#DK32YxHzn9l;@55#v@s@$#6<3JX7(xOcFRNx}A31q+@9Gn-i+RATub znO2-P7QELHESqxfkZIbv%ovJ8X;z2x7G-|Z8d~=~f8AOQ=5I>QT?*lAV{Fs&L#)|W zmN$Z9T!pm=E=n^7q9uwke-E6m&ojv@ceBjZx)3mCw!$sr8f!#ds}yQD4__rYRFIyZ zW6iyEs6!@mtM5(C;VrN}2XssY(3a1m13i?_6Yc${X%EtGjA1>8|r8aOZ=apmyA9W=EPTu?EcZCz>o3zSF#is7_tJa^h<0wo~^Cr-2VoQpKw z-lGj*YXw|YMJW@zpE^2*BOQ4>_xi>_&LkH~nk%@ro2kzlg^X8=rU|FuyGmBIm23x4 zrmm>=b#_s{NEBkFEM_y(SRjWip^AolK8&MyxQ}G{BbqI`?xPA6B^ouLoi6CWu$C`- z4OUR{2w%NA8~BLC9hu3a`V`=@se+@%=h+J6$y$fO)sH=dL`kA+QaSdJ&!ZQX@32sR z^a!8rh@*b#5w7f*P8|W6uX-xpAXHX=3{8#PSrAmd6TY_sp-gybXRPeQKx*I4rQu89 z(-vM(k1(974)67OCJM2;Uc%djy}MEstHEo}=P4Gx-KC9PbQ0-|ol)Q#F#n|3@Cv`_ z81bna!lRKh1eq`rrwOBkX|s@+BVBWiD@W;0$6WaT(SZ*eJ42@tV>U`T*V+WfQI7pb za;l>5U12AlZ%}-UKLn?=CFr$&&tq`3$y>>~#e0Yo^#FtCh3jj=Z^C1#yMY;I8)Wdg z8PJY{!R>-~V3%DxjhYKK5&a9feCUG@S1i~)I;yqtV>cVR^cM3YN)2j7=`pQHTqb3*X3m44PYy zw~MmM_X~`jl&zA=8=r4%mmA;h2xHK&_`08sNdMI>WX^(3ExtlE`u|OULTOW--^T(N zj{pD?9(LT<->VG`^Tp-B1+z)4FSKi`NpWe7Iurn*&JlytE&E39+n9s(b-sQv%%=(m zfb&@&lJ*xU9sog|+g~sgbzTDN$GaUYV{8vKHoLaMcu*!1>x6NyC)!ThH^waJpfT0} zo-z+P0IL~9J{ShzX#C1^TWzN0m#Dlk`QOI?hPc(PuictZ+AHtYc|*J6 z%o=Z~2YcmRrR{?s(RxGOiRN(xgq}q2MgU*kM(XTpuF-<1SQ!^3)De?p`vqJ z3b;!jx~U*-{yQDPxcNU=Ds0Dv0EToDu;dzQ130oqoI6>N0bmS=X$mreuZCj3kJ?;X z@HJP=#hj0JJW+SNBaC{w11l8X(B4ktWbnN47y(nm(XfF@909855SN_0bwkbd-7pvY zaqeUX6;=*sKF+)5V!3lJE4STM$u+v3;+}IExDwY9Hx)W2KhowRt0M_caB^u@0mgAv zLy(4@EO|!v0(~iaMWct~DXaHojpP{t_xI=$JzSgsj<4Ac*WSq|%ix;@8YI^D$idO& zg^E^wmKlj}!`JkFf^Uj|Ph%SZU=SS)UeHVgj#04j zpCadOy>B2#^}lk0Pl1Z=6t;mAJ86u3=S!KgyScO*EZu+wb3#};;fEC$!LIMsfO3+k z+mZP2DHyvOy157C!~>@{C}ht6K3|59cR*_pFnqfq0Hg}d(_4~CMEHOi!$nt}=?X!Q z@v)&%FPt=`JKoql`lLzb#G24#nGfk6` z2_f7nA*7}t9$Q*w1v@T{eZBu}!iye1Jx2|H^N)jppcj?~ZV<#0t8 zuA_MRPRXEz=o7xF(b#g~G7K_E4RBNU5p&=RY}uA<_|6=C&lXAFTQ{SY5?}?idq+SO zSK$A5_$0=CPc2+O%jNHT-snrSylI-`L`mdrb>DC}S97iRJzM*di^x~PWLy%&a-SaT zjA71Xxc8v5)R=;tcfdX=zgRjS77ZF+U_N5XYtG<;V41xERc19lUgv}RZ=}hm`ywnE zu)cGk(FJ{28(HM@jOnAa5fG0ef+&cZ9eq9kL;_o4RW2U>g{umtbE*-|vfmVbtkr2= z2m1d31R5^w&oa{%jc7BHdA|tjlJHo9>dhgG^P0#bVYP@_0~g)*jD%%Qo{#ZQj%J_ z)}vr8WX3CG?!IsI2Pc!Gd;If>~9 zu^c1x6+A28nZztSe-3f*gZv5k#`Uz;KFoQaT!5|2g_?kJ{Y`Kx)_X-9M5C*yH zIh0l{)>kbC+V!;wXjUW8-3<`=>p=GA$upNnvz~eTzaF@UXoccrffXE+l~xFGJOGYm s0gX@r3W`n+T%ip-&8&8XGGoc)g)8KFw*Yg1Jy14)1sIi+&#o{A0ON-4^8f$< diff --git a/boards/cubepilot/cubeorange/extras/cubepilot_cubeorange_bootloader.bin b/boards/cubepilot/cubeorange/extras/cubepilot_cubeorange_bootloader.bin index e8553b4e508e249789d04847e701687821d65db6..8a41060950c183f114d261d669d300c8bc75382d 100755 GIT binary patch delta 22329 zcmagG3w#sB8aO($yGb^E(DVhNE$t?0p>0}7DPR$hG-{t}h8D6-+U)%%)pO4M-+O;Izu#tN zXTEuT^Ucinnmy#ETHMspixi$Ev{Ob$a#?cm#iY-YV-oZtP3^MOG$TFIA@QZYp=AmG zkDS3JNL&^`qAVeCydR0Pdz-tJU9^#z3Iq@91ncaHiK28oCJ zkm&72VnZKlE{I2|tOKJ|1|Eb^>L>3ac46tdqh}>F#?a$5SbLngpF@0p85Zy!WJKME zog_4OzwMk|c23f!>U*jd>BT6@BC^n^Huap81Zf?METS3Slm7eO<6JcG4rRnDfG7C` z-ogD(0+(7)`h}F9YK4DO=sz#j0&#QbKMTN7szp3B;|mB$d^--bk}w9sT<8!=-G)d? zM7l*(LIV-$(8+X5kJ$o^h2q~mp5Y*X)X}OUg7jK?@||f%@E$y&$b*`ZnW|vXvuHGDLzR>Y4^uLzh*7XL zY%@X}nxSdPn1VR0KMy6XBBoD6m{#_M#Oh8<8YZ<2(o|NWTu@O$cv7 zC_*Sgcoo8{5cWXWGe*-iFc9QK)Bo~&uoEE}R~5-OO~-%lj^2O_!U;v(;=yG@N@4c$ zqHE|L=Tocea89%{rsk=-&+CwZ(C*dx4c*Z-r|KBa^a&F0KQX-ykN?esGJkggiLO+Y z0+Hrn!wnD0zUG3_t)xOJ9UjvsRYf5zGALD8kT{rAmAC7CxWF;Xz%nPicxNMj_n6S9)Ki5!I(LD`eQzLkzJ-jiA&#>WbNW3Fu*l{fq zUleAlblkv790RM5(A^lQr3PxL0@A9=($O>H_xyz zcMr;!nD8x@fSW*QOJG8Wm5a_CAmL%KhT!3b&BU>#wAW^(?<}@jBqmV+XiXW?Yf8eo z1RD~M`;mT73C$t#h#zXvpOum(8AONGDt1^uhqyS>KnA_&?`)IvXVd|UpG8+uM+D%h zL5!xC3Pd+*L&cZMYbV^G~8?bp!?E4->0nc`Q;V88NwO;uLI{ICZO@ z@m48~RqGp&j)QK$Aq!lD)^VYKYzfETXQRc-f!s3uo}JIVKgmWJj8#}v`!C%?} zGKO4Rt{oc-FPZF4M2k{yW|5uS-0f#(SOA`SS4@MYv=8({JV3)~N@E*@Tnj9ynxD5Xev zFKXEEy%Lk$9xC~KFBwA9b#WtV{xt@%**ARU3_pm+J9hDcZPQ@KWvOp3JkE;}nufSG z37PQNywYfUjU}>OV{d_}8zzk@Rq!ai&@I<*1TtSPhNJNvI6K;Yq8X>*@fqfslI|$o zRXymG7e$S7|3gA%x&Bw%w@@R2$9wM9zag2pIXuk`Uq!*G@W`suHx%QqY%z$H4m#G# zcnhd2>yfw~`no|%I*P>we%bd;a0t*DEgk_{GCVE&T)_&SCL?(TkHw~sJkj=Y5k*9n zm7r)_f*m@JsIIdsKIvK%#k5o6G5H&4ey3-el!YR^I3mIRnH}F7W-gTU$OEUrQCOP? z$v(zJ$2d0eyLc6kQsem&UaPM%(c;EHF~3o&G1KC+0X}K!sVtrvlgBH&Hef8i)T`vn zJ2$W>y}*UK*sw!hmOaKZlUgLSw-`FSFu?Ff3rcuAW*WSW3(P8LD@=4Fu2ft(IOwfrstL^3*NL0K8wc`6nfpuMJ2l7DU+D;2P7s1mgja_ z%nelYco)a3y;x1dDw|JkqlbSL^9A9j^syJRIPF-d>YPo~A*oW8m#~p*m(*#xFsJ-v;aMSU{1? zTm)JY&ji!?swT#pijLcq;*WlgM`^V9rSNskjniFe-T^=OXo>+VO$0^Ll(qjlj99o(|KVi)dWvogM!DYIzSL5UX!^-Jci5i!D%6n z;rP6!yaqs)cZ!1K-X~9MWW2LN@jN-N5nx82z7fskH6ih%J~%>wArw6WB{U(ZG&#Ld z3-wSUCu+u>z4#as&kCmoTVwAF>S1L;Gjgc>aM|~k5IrOt9~UMMnM%E+ z68Zv3f$NhK@ZKL*7Zcv4m-ZWmZgA)HKL}`cM_k|JKndO`N6?@wMIP+Wj zO;BxoV6TUqFp4rwLy}$gogpM5#`HE_*O+DB*^`9G*aoT$bBU09fA7G%)6SVFF-AC} z9fdieS34P>5ylVAh@CSSz!8Ke9Y6SZ~5F3TZ zlg5vKG(cEAa)N1r(#hr@&rd5&Nmuc}ARisXw@d6^=E8C@9u4eC`HkcGX@HxLgrAd! zMBVB~>A$(JdB*b+fjP6c3QdK4E+Eu*e;Lf=*b{(6Kh*RB|q!A^e`4gWnKzDJ4Vi^CQk?`;!v1e4_n^ zhk>D{3+q#IbQylX=O8d2iZaTfX_zUE)-W)UWBdqCH!?v7h1QgLkt_X}qhVi*f^v@w zlei(-?*}pLyd@SDq|EbQ^C%&l4NK}5IK_%#QdjRs>>hZ&f=3}#b3^bNVHan#nh%iE zUMy0m0e#){ka&?*n8mZsN6ThPBW!3S62Et%98=-=nhAGKwjN)Dl8>H>w~w+b z#d8wg1=|LY^O#^HDOsl!FG<2U1CO5;o;S>)uJ#IThS4d14K!V6%~<^O6BdO1-#`8E z-@x;uyoRtTX;4e0kdZop3iJz)q>f~QzU2X-Hgz1M5dS3$XH&;fpKTGs()L2eRlo32 z+Blf5U(-gYIoo;tP(J9}Bg79Mh1Uy(!wpowFFE0oG>DeGXsObvf<^!^|E!!#CP`_`RjPxWH9opi8zNC|R4PP!(mSpm;LTb<# z2OEpFk;MCbFT=T;*Hn^;Sm97ca{9yaacPDrL8)v#E=@BfDydd-s3*&a(=^43gQ9+S z4Kl zl8Obh!TOn$lqWXncmsc)XamAoGm^Sx5Y@~b4cjDbOWghCol}N1%`q}V&L5_u1zlFo zIA!U2GvYwp(}oj4FR!BssY$uqK2pxQc5_X;^2};1(ipeGncFP;UILmFYO-b(zo@;l z=1iS3L*E8RvLAah%l~!GT7PF1*;0~pWmbKiEmvD0Hf8WP zJoKF%D}iatRT+iUY(C+f#Ih~jkwi>`cIh<>yYp#!6%pG6F@A6{TkMjUy!<+YNYO12 z8<4?CwiQzDkl{ixBHxuY0(-|{u^dhfZJicQ$9~^Gf^e!d$v3MS2yan9ueqpkoP714TLVk#6|A!tO>M65Us)nl<&g0SLleTaYHs+vgkRSjip6?_CgPZe=q_|%j- z%nl6Tm719Q=O#xN=-1W-y1g@SnRVM7Yv*Uya6vYi6fg&xaACJ8Sy*h!b12G`pq$be zL3LrYhztn($Or=t^<9fto5r9hja{fHi(Yz0iCggmznkXzeNUVsjhiEBWEMH3C{>ne z7Dg}K^gj^uPYu*TVDcL1r3@d*TkEWA+kwK-S|^r$zsQEAiLt<*$-W=tUf6}mf%Zdx zPv{gEW{iv(T-9J*%kckJPHd&u-d8dY&#M^5jA<22DT9TZIhx|!QhMziOm$gfwRWef zuXRhsZ}kNATc&ZL1_YT~Yb?QfpvAm(W{x*>QZ%8*<>KSe{A)5{aA3Nc$OJfsO>G4v zTYJ#TFCirHL{*?wzc!2;QgXL`2A)}A=s}=+*k+wMt>5>x->^2Ol+w+^9KUPYKuKpM zDXCxE3QbUOvSR&aGii!6`z55o@(i(lpAgCbf@TR(0~X1mV9Vf7Y*4ICDSsSy&7nnP z-Er)znpw$X3XTWv_V8pTs7d`lDyM#F?=v$#%!1A?^LqrUv+Hn@RQ^lNo*Gnnm5J*veG{oZ_dS zB7HPW#I0tjVbD?)kk*36@U&|_q zT}8K6uC0W$vTsot9UjPm_u}JnE2Bw5ig)0)|q(Q*50}gryEhGX{%v6T||02?e5<;S& z+_VA-#}X2a?j^8@1MOmnFv;|=Fg=8!|C8)2Yia(h5}zlhKuYc;M|9tSmJ&85U#l#6 z0JHhlH4Gd?BF!1i;yNd~v*W4dB9F;A_*g%QFQgK z3>s!7QIQyF?J>_ZtgC!JR6-b*Hr2l+JI3-DPftux)HyS-Siufb9Fc4;ciGurpGxzmblPsev)(LpPXU$%YG^#vUz zbdNPS$QZxquk-xn>35&L>mi+aw-sf+?I!h6#vyJr%F$DK1j-?0`sBL{jAAt2kI7BSY-|hy5>kkkQdob_7GI;v+P_sGEs3tP(xL*Hoz-cb+?fG95ju zj||iu19eXt?;faneB1wf#oq_ddgh(Nqi8oTYLvrQednP@8QkC1ho2JuJx-557w|ng zM-J4TbENy)MWv%B`^dCTCGF_RIN}&J`R?!|m1~INmoiT7;g0A_e|{cB98gXNE3KV4 zmguyT%k-OL&FVU9&$^X{bq-HE)DeE-&hb*yH$Uph@wgKZz#Ti_#rEH$T#Cmg`leVdj)NOAoa|zwVc7V7FM|_x!of z1w>i)!2^U`{=(7A($V^MDbCz3X*n>cR)DoT+F|=nHjj%iiyt^4Ay3xTmL^7k5lMW*`3N1;`Wi7LRe<3rJ>L9&J>G#b z&0$22Roitn-P`~(3Y0Q%dgp9|kUy~;8I|-UYv$&}GpOWdx=U^H| zS_2)OTW!uh%&WY^(4ppX(Hx%QcWm+E?XvH#|Lv}DSnF5)ufZCp^m+WF-RtNVA^u$G z2zhQ5-u14uKm*50f0BU?sB6e}xg21~W;v}a$%4eC)w1tm-yf=jSK3s#Rb!8~&11RI z6&^H#pW3a;Z?%+_cNPtuBheg8Rvy(!J6NrVqf$W4GNE(`Y~dvmWm>kz0!v7wZN^x4 zt29P8_tdM<$RcR$1qewzR%EaOR9+wZmjUahie0u!D^gLki!x-Ek{Yxk8x`(a78*Ba zq}*gno88YE^r76pvMMiDeeBkFrt=O1Y|!sXq*AVgjCmidO41CR7ydJz0s42jlQ>_k1?9S`Yj&9s7DNLkOn;~rWkkyQI=>>S3?5mbY9$1}F&XUBl zk|qz%TRYazlftSfzxwuQ3$;Vr495eVVjcn%P78T1YR|*|O}CSD!#imuSVsfYbTIVT zvB8#8CWQfhQRe+23{NvUB16cT8+aA=^*_-X`5&}quGtQ}>y+Z<-GwoS*8o$j1&j<@ z-c8e3tit)7gQ9^w)@H6cyy{*R)yf)3^#Nc5^I_DoZ&W}NO370WYNhv-HBx&>I_Xp% z*a63YvMSjTaE3te9-@F{y-Dmm77H)B=Uf{={kc&0!UI2gNQHmv{rpJ{})Isf5S#(7hwOJ2|ZLb7=^DVat@syXf$7Xii_YgR`mJm`=8=; zyq@oev|(j3N7$6R^B z8Id;!jNO}x%_D-o&Am0nLEpyE|AyX;_shOb^2W0Ao}Lv5^nraocW^@q#nU{nZ4nm9 zmWX+aEvWx|74;O-M+B(2q}&CIhc00p-qi}=I?M&4hIy>&d_5k$UV6y9SadL|%=J>S z`LWf@yD{V(kV>nrxRD`gggNbEeT$U3uthROCz+fQr*ldXI#qy zd!<3sue*`Hvg9eQ4^(a_oxV6AJCA98c#6~T@YDk~#}zx7>?<}JK)wqYmLel=$CG?+ z!_pA9vGBpN2d3zko`nr>K!!qTeZG$a2bRSV1}*nMB@*A44EE8SRcxURwksgAqnU)A zy8@QbH$d=13&8B1M<&7mqyz7H%0(c+(gzlm+5mhmW1hPr-TPfm<8vQhA3c(!?mm5zDAH zq7loM8}2xxMxP~%{|Q;yg)|$M_SNa_2kh@#GS2;C7i>b7b@oQyK_BCO!+^r^ugpVz?hXN&G)Nu?^%ne@iCX2++3c`g}oPFNw{SSgv;o`>d_u z_Y$MBW^YlS?**Z{;B5u6e`7{McHvMQB@`77!{>!1g&Fv3;g!M((Vs|ud0 zkAe1SaStqVf4ioM7Jq35oao3h!Ftw&tF1QKS0DUuk48d|s-P4j?vfPz6??5E21FZH zX@Xi-%XG5pqU=i&9xpQBXNB!WLoEBDW(ACfSY@OpJi)L|(}ZqyV>303M2jfAJr5-vla%`+$9JeY7E(k38dz55;9BfTZj&VW_W2;QAz`> zhxcf4KA`7=W~!EOdGjSEK%~g9sYbiCF>FfM{o&=8r7Y)h=oK~?ZA7w~B{36DS?-*( z7IvSlE%JI=qEPB_aN{Bmf;E3!I8!pr0mks*mn7RZ0VH<9xFYfQ^(Vb)QLGE+Qi9PQ zvdxeCj;}3B`&p3i-rY$gm)hZV0h`2z>5KRResb27wv%3C)P1g42)U?LNfP@BH=9?5cy1@>rDGeLzv% z4BcEzsw6d{ReysVJLK5@lY>@~9OvTAkW&>!HK#(m2OS~c8qfRQB{1HXFP!vN!W0~; z4ihiaGeK%NQ~e$PM%g@x+0zJkVVigH1PjG{Tys90-Et1B#Xcur`}0ZfBTJSayIr(Oef|XaHF3Z$)fS!bVpekBSAa$kNXBKfmjG{x z$JG{*>KT}>Cre{N40y6EqInx%%fHjbs?}YrQVW#6v~ePjvdrR%b@vrq;Hj)Vr>~WZ z+3L?d<)TsD?1`x3#-FJ-+DS9NdcLT?ByoGOU@ODBlPrnCzA3SeELVb;i5l6yqcH0t zp%pS-svYmyU6_6`3_6DQ9Oz%ZJuA0#mzYPng@pO;2B|C5d(gB znRaBn3s^|u|4%F!Kx^E{GaYKLJl+(-n9)vP2y{75gPY`xi_o!WzVRaZ{Vp}dfD0vo zWp?eh+|$e+E*DMgIjtZmoGX(y71FQ@lP+Eb&c4wrPj=Amk)bN-H@__mcfTQ}nZ_Eq zHYLPTL5R=*jg*TyEFNdH6NbOGDBnXu#g5t{Qe3fH<+iQ(oL2cEHm|Y`~`{8 z%mX<9c7Zu4BSX}vl^4yH5_ntKm5)=P<3nNbDqRF~w0l}72BZ4tPWFQ^gB}j&vAs;< z)p`PfcOvnGGeg8-1%)ZF@i}iFcNW~%P_X57JJg*NNL92uLyT5KmHq^nbFgtc89>vc z1u@dlEEA|n-gIX6w3KFwnlMs90xU)_fjSdF-dDO#S)8{|I|B)H7sCeX4|FNj1gEtf z-|+_&fTi&A&W;j};$SAskmBDE!j>Y0Es9`^%5t$E;75h#X+s=@v)Iyi_SX_X@=(A4b^)48G=`r% zSHN0Q($i8>-ovbH4b5Vjj!?$HQ3hoDD{DC8Dc~(01OF{Q8~z{gB=k7Tu^U*~4l1|3 z{$Wr4Z6%e^NkvWWnR}!g>LA-5+1}J$N;uHqP<6Ebxp@%u>tP2RSm&f7jT?{qjNez7 z@zbF$2JJ080sO48V9F`HC$}J(U-j!=eiAf@9#(oOrO_VOT%lVXTF_TXvvfiy9d+52 z04f!w7l-nVI!*`mKCErd)^$Q>NJ|c~UDOtR@2N~4^nN-&!@vIaPq1sofCy1rbmq?< zPpmDv?^hEa74mk;z9Cs-d(bmUypoUNlbQ{1NRfpb5B^_QSDV01PtRL{-+HE3oq3#} z5Q0+wWEy?2P$6OC$}X0^3G6b+6zj=W1_-}rwAV9x^zRpFj4p)i?r z7=S;U$;cxwx`P}ha zUx#3s_WE1Qb9k&1(p6psds*5GK7o6WPQR%MXT*TC9P9*}c(koOk$A3K!9{Jyr5XG@ z9@Un>=s{EAHAT!Jek0&i7^X)CR>I#g;@8qTehYui6Fbn43~u{xn&-G%DrokrP`8lbf(G_V?u^%8%j`@td-d6ASN(#ki&nOQmDLll^$i~SgKdM^F|lz%U;Fm8g}8JRw7OX)EkYe8O_OzLcO6*RdWBUFWQ9G{+u=2$U8Gyvt)*I=b#?sDD%|*2%tt6QOZtU^fyMp2DH5{fayfvj3gAqa z*AN8;7~|?#u^-r_&sC~c@bVQVJ(z-j7v?{hNa0@L*#}2ERss``KSF7XIoa0^%)Y7} zk5x)IoXNi9hKmQB!3J_^$ndMapRoJ6t0^OCdU_ytH8v{T#17hYy$Xbt6Q_tO&b1kw*mF>0+y%1Hl$4+}uC4C3w?zTjqWyJ7aM*No~JA6;cjQF#}h;M^z z#fS;OrxR&|5x;2EfXSF*Wf`+a;iiP90U5%l%#sY8zK;Ckdke^aE@SL*E6WmB=QbX& z8yYE&5qI{EHXN`)>1J0PxNks*sIoTOMLWvu195|-5&ilHWv?7XX$}<+YW8)*s_0kS zBo>-|R=O-5-yc;6j;U3UvjZk#+_w@tZ4-EkVyOI~-Vt@+1`E11B>rU`0<7iB%r*vi zkJ}(cGoq!J*`u3~V!Yml_s@_(Ez&%{0#c&S#h&w%$ZEx@#xCzi&pj%}O_ z^B-H4e>;Yzbjm|$#D|g=r0qk&5gr7NK^1%kAMVBB;9xHQ2n&r7!z64ni_@!_F%Gw9 zH1uv^2n&C$jt9qMv$&$#I24-HY_Xu*k5z+4!+~zwt1nBhADzR$Z;5k%10@!O#xuV< zwNV!`swUeLY-wQIPAmAp67ME>V(BR!f@JVKi;;b%AW#WtVOnlmt0CNlcVk#(*fIK_ zo^}aoh!lSkbRe|YBm=Kt+-5P06!fpnLy(sqYHUO`N*l$SJIE3RMgVqO!-gpXzfq>1KJ_`PKChh zL*O5Vz&`-+btDWZ6Cl$61MzMM!bxuoL2L*? ztamEkivtuS$_k#*DYhwqMuq+iUg?0yE2IFZyqAXxJO%}pxj6l#k|AlzLqXq(AQU*H zcoh`uqyWG_9fC(IXI~>5=Y0S_v;E8Zdr#!`(S3- zp2ErQjIvtGME7Os;86lm*y#ul2e)_e7`^1n6sqUDO~Ebv1y zx&N&>#?g-qwD8KW1N_YQKwVm(F2a7ye_rt=f)LJnmqKyupYSn4&nKnvX1gEj0J>ACHi4H61)1Ay~Vn8E$6)1EJ)Y}2!>d=19OyTTU zOqGStAL0z-p%_gLSQAm~smnN<)*b}=64pn0RhWZgb&;T$uXDWEND3#HRW%HBr{*Xv z-sev&Q9{Q`!EHA0n6`wBwZLyWMvJ##Be4<@1{f4NIkr7!>QdeaU0>#>_UL#!Z|FGz zihdJK2|-^||D&L$ONWa=3;iaZ1?H{_y8ljNdC$*d6jMQDg|H21wwa8EjARXTWE_N` zg$s@3pzzsz9n~!fSLct$gM=XqCM2Z7w#)D-7Z+QCzVm*DplXb^gBGs`g~t|fk@EsS zd&=y9Z@|MjVb_9tFc#bkV%0p{xtRhr=L^3r*n=MyHa%R9?-4FMY{m10VYbh}3H!2b zI^H7WEG)x^h36M8jNIQ#ZV6I9aZ4$2mC&_t7)}w?i;Q@@Fm{nnb)UZ&P>?3fUo;et z6rNs`i{pgDi^irp0O@z#3eW{jgZvNRqDVq}*J>Jc-&>B6lpDP_Ji^+?1`7$5-z2W? z-3NmwieWfDi;$ON$sG}MsN(+0(SyoS_P->wE$bplDibCx9!g1)P_cLARoM$coMrU55Ob?%uN~T z@}PdWOsO+LSl4F&DZIR=eFaql%DH?j4r_i)7{4S1Hwkm#|HEU?EKyL7_vHhtjdeuv znuHF(9i;v8fL~fw6H%ceU4jXVSD7-Ag6E`(xP5IZk3-eiPzggL?D56x8# z>p{Q%&{D>$1?4FgD`f-lL&^)FBCR6tPl78X@I$%-%Q#*q^#5h%NbAyAIC?2pSiyD+ za8SUkt_MvAb18f^ZKPcZ@ZcP;Ck)b6@CZ)(I6PDM*!~=TMaW%RIR2M@BHk)p`TSm> zmZ5M~kUNB-Ydh8QO>k=^uB>&m9T+WQf9Key4M3mJjPTjgd|WNij~c>veG0yEI;UOs z?G$nz)lrfC!mLLhim3{DI9Jq7uVd|OUB53OAe2_=se6OM6IEtvXizv>mB;k^4)}$e zRokeEeZtx&wOZh)%Qx5~c_*)1Qf4>nUboqy-YWq7WEQxqUV3sW^>$FmT9Hm|3knae z7*4$r5Z103o&4KU#I~*kuI4Ft0QvDe3yR#OJOU@YyZqPzio%MVI`d#7sRSB837Art4;8dIuSc((U zB5t>{R$9#MesZHnmoe6@8ktLK;kH=>%~MH^6E4Kn7BxUt(jS#;-Hb>xZIazoBUP9| z*XqLDZ;&7HM?MRo9r)KhE{gjZFw3F8!2bfY7>?ucYV-0E`xiCeIca<1QY~E2AZwlB z!Argd8JxsLfBlNT6QAt$A>aBn4s|i__g$8EO7o%0nXaAEJP6C(jCW_)d1>dg>_$+o zNHtIZ@VxO+yK$4oK4g=&;CL^vT?toS!nw`$d+G(Sdc*wdbuYhGudd%>(Yp07$3Uvm z4R9I^<^VjNSX&0y5vqU8|FI>pZ5r7ldL09PmMxt8q=!MJ1)niH7 zGPEA&{`|t8dQ#1nP$NHhjGK}RMpi@Tprc1!2A(SYMpq0gHm&bHj~gf~4_5X=OU<{{ zxx2svXEP^ zwb2=OKsf_9B^5D4_dkNtmcyM&Bzm0Z!8t3|c3fIy5}Z4w#U|lN5w6rC@glrcK+X*y z_zlt=urTJCW#6(-gq=@3NPie;5Po|?hYt!-%ZF;XKCmnpIR2nC7g$_xP{><8lEQt0 zeYs08rzZ$IAJb^&1^@Jmb4v3yV1gO+SSIyIK)Cm@|7=Ex5UR(@hMrp(dfO zlE4OO-n3u9YcUB-I~(lm(va(_Ygrtd5xRPXg2K&Z36AUiB6!-78-nES1YF(-!vZo4 zP{!szD8nUHIZsGRlg*gdY%?I?ytK7y`LTaV%u!%=5tQ2m@Gq?RJAr?JP?GMrq;Gk- ze*e}e|JJ^k`kjT83+*{(NoZTRb^lg%eN6p!3*+9u3@({E_#KaKD;l7Ll@iggZGuX^ zYJ5XtOyq*?fHvfvt@|GxSHEMvW!C=U9WFupj@O_#!xQO z;MIxM*4q`_50b{I6n?nDzW2k8u+4qGPx=`?uMw^wDU@|%Z0Ucfn5?&_7|Gf6x?(Qh z3mzzuUQNUXX?E2o*P~F>mjnN=U#HRMhUC&091z(cJ#1nP8l4@eX|buiXYfj(s=bvj zGIusZ%(ktv(sH+>a)U%~yRw0~GjHXAMbTxaZwwm4+%eBwFHKtqH}AnGbe3fTA5n_M znSF#+3i?Xrf$M!Jwa;hk|H$)D0S6urQv(YA5HJR>1HW<{9>-SrGc~+$^aXo(sYdsz zG~2{LaV(np?4U?F436ZXLSXdt``+$LhqrtC$t^unuBst|XVQ(Zc#xQsPNxn>@l(@b zp(pkt(B%&0Z#{%_-Br}+TFc-n=_iz4-f5=WnkhqV5^ZRyudL##loL8=1H+Y7sSRw^ zma1>6s+ts2FL?+9rt|EgEV!SAL>v@uJ)4dx zVaRhCj$ZKaB8J=>{bZI#_g)3H6?lTmaJv||*FN9VeFNMpF{2`JE*PdkAP|2FD)>q; zA~SBoCa|XF8mjZ)?lS0tKmbx*?DIX;hwM!H9oN?MZkO4D(&3(|VTsL9-Q}qP=7gxM zP6fk?=}mZ;F#_CNXz&q}bFDTcUWE#X-I)bXi+ev2I-cY3y8>Qw4`zh%Yi3jBeqqO& zb#Sjb{`tQt2tPhisCzyI7YXj?=VPNVYORjK0b$14HE_H7$F=u_ec)Ht+Uxp!nqEQU zunfB;d4LiW47nB?&-~&c7V#I4MuK(_iBAa29Xhy=$e36I_lj)VDd{S=8igbCFP z6BmLOG2r_OxVEaMy})E4u>zkKfs+3Sjo^|IX-S^U)vN`b_W zVdtfficJw*0DK~7ep(&ghEf%_L-tz0(jno@Ivw0hjss)h{Pq~2)_35}1~pQ93BO15 zlr7{!F4*vD?Pl0iu!3-qlU&FE*Pcz|J4ygzcfY1?xfr2<%daEfwU4_r1=2O)dsFt~*-1Nk$_G41sGcvl{DdUPL?tZpaDpo^RIqJw-31wO!XgIRJB zu-*YHN&y%n-YeiG0R=%Cg>ftcQBd}|A$Q=u?ljQ99tz>-z$Tn~07`xlNQXQHAAl== zr0gyz8wO=%-&|;LU-P4O0U!l{{3uil5gop%lPPdHS-2r~*c+jxtT7|8-~^tK2!_%F z)#4>0FMxVM*uKG#tn1rrQMF&XL0Ky8GwNpAz@_5`%2n2~bpf9-D4g9eO+|f5me*f| zj29+HztN8kpn!#oe@eKD+v|H(c;M*<4bQaG zBMkP$MuV-=CN{;`>+1wb(-OUAYoT;ux*c@zEnnO~y77&en`s;Tw9%IGbOK)q+V^nV zOk48Pl4qt}{x@nS7v4??(Jxx@3&I00I^e(c#j!x4;TtO>3c$r2uBI&R^{Hjy*^TLg zX9fSeFH`~AB6tbVL++>u|JWD@_m{719HH9)H)9##;+DcCEi~;V(7wGSQ5+U}eIsC2 zB;N+XSd)uy2@ltd#lH%#*36zX9_aYD`n`3OBLc1>j@ATxD0H_O7yy1W;Nl1A=Pl$q zI*o~#F8QjP$n}`zB894&4hk8YW;!MXQcCccCv1c4UrG_qQM;J@@|b(r{ExY)kS zK0}LJhuU)*_gmtA8fwpIJeUw$a?_*b!+FtDW2XuRVuMOEfOd-gnhtVu#B}VkziHXu zg{gyG6tl03!Mkj~xfLaZzD)iPYy;mu2whj4RBaAj8;=A{xV3J#9i`!WciRm1*t$I+ z^`T2-pA7gW_rr8SZnZtEV7JX`FSNCQ1-Q#2Ox!#X?oL0mIU~{E3no2qydBSj{hiuo z+1%WcfH-pj5-$r)n{%S40ka|B9AB1wqq|523i=&_ym_cY2{%=Geb;(TX2O5tZF}qR zAqlQMU{KdfK286yI;-7iTW?=xQ$8d4vib>!4)SzpX@ao6n3$GxT^E6;f`zS4zW>4y zP7hX z+uak)5T4mg?r$Pd2Oilh*d#O!Ea+Z4QjuO&Qn@gS+rLoq8GBWRC@#aWkSsi(@8GA7 z1SR@)3t{USzEI1pX6rt%Aa`C99@FdlS-vZjZ;f|2VFw+=>l(>LNU1#F+j1(VG2qJz zXgetH5ZWL{h0iTSx9gqzysRSN``-Vc#J>JrVMH5qb}s0a&47bg3ZFc8!g3gr*t4~k z8D|f4p>UedZJfuC;SC*cSpsL<6HoDO*f)0CBI>@i|6;4Pyxm1B%ooD!XA{Z_!fZxc zgq=A1JZ6K&5FG7DYyB2tq)Yq!3NOpd{VDhDXY=PL_tAwC@8AAn6% z-9=N&z@HS;nYLx51K` zei|A$WCFf!*o$m+7<~KKLr9b)dUpoT9t!v-2-UBYQDuJNAFm`)6F~{`$_y&TFPOJY z0|sRKwh!@YVex77!!8QbZ3xx|ibcv6gKzj4-_-HWeoe&!~+Fv+I>}`YXXw(Bjyf6x935CM+ zhe97QfHP+Fi3#Ae`=e_f{D1Gl@0)K&Oy|HY1*N;%n|dQmxz6v&nTpPM1|5I8LG>Yi z?*WNfhF%T&7QnHlY=_HiJg$Y4=?@Ms;2SRqw}b~X76VtzHYnh`IiTeRcj?Q1!iD*K z)8RUF+6!bIkxf3}nN~MOA^xo$D9GK;KIxh zCkBRiuNFIA=8iN zt;&GPyUP-GA*qX|m0sE86jQ2qSLCQw+o|B{Dll>be-k21~T4(GnE2n-!Ag02Sfa4rIPf^JnHHrm{Y z^9KcJvBttemoX;(Q`FfSFim~uwDM}`Elg~)OH zl#}HTb`4_8owWIN&sSbfbWg$3qL*1R`B?cCQj2=B9e!@t8ncy6X^e%&!R;}$|1_N#n)=!n;xVg+nH ziG~m06(*T(Gm|OS`RVTMW^DZvXU7JxFfKg8+Nrcc(|6yrFn+2BaNz*dL-To~&c12M zhUO~^_9SkCS@zvk1qSB=P2?*BgSxl;fncDCyuoL;SmG{F_bn_qlfZW(KF>3fID2`N z{FQ53Ub7S#8=>Bg3a)y6!0h)-)@A@6#XGeH9`8@y$Ikp!~a13GvEv!(v8a{nPh2Ln+X8aC9dhks}{aLpCCs zg8srb(17+NIg$5+ZiD0md;gmwfjClsl6$DDuw&M?`KYt^5lW0f6LxwW3 zA;He@`m)cv!<8`+DK!=LPc6fqHM-u)+w`eL;l^Aa^;8K+2*-vi;~0n0ztLA&;gV)4c&P~K^o1&>2w>?;bLGr!SP~BID-b# za47BR|4CyT!rBx7x3td*XEMPUxIx1El2dFGDd)O@Mz8N?YcxecI8HnC1U*%71*K-v zn5ovDD!7ePRj3t*r5yq{Dl^hcIyO0!@^BtW%W`>`&jIN-ad zpVCD`m`lW75N!MU1HSkBC9pQujKRY{1EmWxqYBg^yu2sb@d%tUtKnhb0~!@pLL{8% zFjp)jv)KmpOeHJI6vYwEtPaDsc^GP_jnUop*_%k7rUP{lix4ip>w6g133*3)tYeDV zhP%E8`$=s`zk4D3M;`SDY{`FMDfnOy6wViNUXSP7`si#m@R0~bG^c{;3+ZM`X{Mo8 zMcGgo-5KCD^O}fVGT_+@9VTPIVAF$-6Sb@-;v=XAALkBT`tBjevmyu zz629>1$=PkbAVEWpuPm3{~%m@UjD{Y*dhG-#*_FVVfLHPV71_W^9OuFc8UN<>rj}E3DBuHK+`)dw3nj6pGBCyZ!k6p_I)R2yfhSCOTgis zg!CVw5+n2^ysO}ygz)7P^f-iJf8?v-oxq3x@gDI<7#RwWt@yvTNQ|+5qZR{)r#1tJ zDv;&`u{9Yu=4t>pQUmcvAnpf>{RPsjKyh0rZq;Sr_zJ|jdJG&(f!G#^J%Jc#EQ2Xf zywiYzqZ`O?1!7ZU;PM(EpBK2{Iy5&mmjO7_4N?aJMhpy-*_Zs?%&}B}Q6eD1#L1`3 zP|wg*&mi5%)X>z_Fv&R8gkiG8G8LouaSR-vff%BXf#Exp9h(R=IRiL-9uIV75=4Gy zDg%dM(&W5lVqTUx3>@XzKu6>;aOeZ+&@2WHS0H{5oE2jP(#$|y51bkMTL96j4V;hw zS&<5*6@hXfK6}>WbIY6zFIO;dfG|ktFqBp;)>kbCdg^Qw14m{faE(y|M1DPx-96cH wc{JmZ$#a+6GxkiryWE{oW3uWBW#CC_o-5>eTY>4@9%xbkunRG1a_I_V046b53jhEB delta 22090 zcma&O30PBC`Y?XZy*J5)Ac-KdLl#gVpkcA%(i#%DEYaf9#igxLv~#U>#HCYh9TQxp zs9n%&TLe2}wVhhKNKiVWrO?`T+UfF3tjwUaBdx7b(Dp{qToNGv_XM5!egEhAp6AQ+ zoSb{_+1~S>bKdiA=XAKKqi(9{B84Xj-IT!|TY7?OZoDwIrTdvdL<<4 z{YbP7w)a=Q)ZV}LrKpN%UN2%g+O{ARFRsC4iHnCU5|h~FnJ+O)cv5zG ziepe3i%}XvDD9265X-=G-EXMpe(ScT1YS4bufzVqRay*D%@5(++jxB*Xp!h?#b zg)Djo#X+0|Ap=65#)hgW1x}VTsFabhwQM_zD5Dm}L0}*t4Vtfpe6t}u0AVf!w#BZo zVlC1TbYSR1a>ZB(Y6$UsxGA~ZEUMva5_~1lI-t*Sk0bFJDd^J#V?$U%Fc@T3#6aH? zYzrhd+X8{i7K`XuU=f3mrVgbo<`>%<_y)+sKprOhB7f1w=C+~sP;Y9`JObVCejDjU zD2TJ+xeLPg5PBe7g-~4@yly-xbi|Ao)N;liV;x_S$d9e12OLjra^l>vj;PwFoTr^g zPiE%N%{%(X*1qFpG{z5+XgyW##M5qgP}XlQ%Yb8pydv6$^}QaH<8kTXor3qDJjM^J zO931}7R#Wt-}=XHLwbkyw|@2Z^&iwgZQJ|RweoT@1sxld(Ke)ItnrTTnzutz(02?9 z3h&E5m?gI&z!S8GdyxVuhB-E(2?kGp|-rnZF7iQo*pvNegzwBb4=_Dh*Ou1Dfb z;V%lUhLk>h>!0iOqRH}!^lmPxs~Rv#>L`FZgdW97WwNzW3>uTm)h&s_>ujt&)*4$L zH#^=|DLQiFmuYPWmMy?B6|~o8p>M6Qm|R>T&#tdRPD(mNA<|;-67Z1fXbD7-FYDh;DJ{F?(zk z$8bU4JfSFTBEA>?qlGPD;fgS8A`d~RNsAr(o|Y~{;`G66s3Zfz7Qq=7i?za+Vfqtd zSO&H55Y*NLfo;L!<^TrB7zu0G79=8x{7(y1m*O%ku0D<0!y+hzG=LH<%VAM{ni2Q6 z&76((Gv_?7W4zUJL-qC+q}6b=h(`8}iL;wWrj%>A`)srr2;^Jw+dP+lf0B*T8>+Dw z>;K^z!n8O%$msKJ`8+n1{9xoAh!&&#S=KoC!q_xruiKFr9yr3Mly&n*NRn0QL}J18Kq5RS#QdRz(1&e7EFK%gVqHKc zUX>VqSQ#mj6p)3APLt%J__&0{dj1%1nd zGHc~P;qnz)w4VWBE=U@VY9hnuY(Q*}FeNfomOBQqqOd4(B7R+{iPYmT;mycd@~}vP zY~g+V_izy^-2Y7c#Np%>OQqcGLNGwb>TKsa5(dnKJ`o0}0<7m>Gm+%y9 ze9sfjN0u)^Ktgm%9soyl-*+3D`>Iq-Hzj@@`~sTa@0ly<5YAKbv^RL)Sw6Ctrb{F} zy5d3YO|bOrZ@}NX5IP_fSP6Pi=D7A+uAWnHC@qF7;^K7GMq2zeVB(&WYE88GV}MJV zb0(Xk3JN)S-wuq$1A}s|vUf)q$|!cBzOeAOy=>SCj=8r(LWfKM{ucp;a~2nIxL_{4 zy%u<&_(Dmd8)+&eW_iSE{v7|1ZM0XWn>hYK3AXtRmx~tP3t;23tL4RiHjh7t3uc#i z-D^cTy5_M;Oyz?TlM2gqFD*6%92`EN;aD$bX>o0!xY*@cD=tQz@UKMYJkdg1R5G>+ z-BFfVt|4r!HUH+u8p(rUzR;p_Q1W~VU1vC?V_SZ1rmb2o4(8`O0S(N+!xBkTx5Q}~ zcnb)RMkiFZ<3Nk$!E{*qkDDfR(S4<{;QaBNlo6rL77KWoVBZR^h8HdxfA?zSY z7>P-`cVTdDE8~4YmH}YS4;HquK61#<%SOb1j zD2mnRpBVWQtR0lm=~inf@%9kPIO4*3dc!xKpzmxTbJHOhrtboBSeMx@6JK@$m`CB& zSWEQ65gjZVs5uxaKOyLQO}G)8gFA%8xH*(FR(K*V8;ioLaraJk593DKMm1LLP=r?1 zTu!!+62)Oz1F819>&HE^eMJLk-H+RgpevsWbo_$KH-=@6-FG(Yj$tD-qzxSM5T-(A zRktL;SpD5knvWW6yQ($?eXi4F4zVqi6>Ab9b^qY#yMxylDKT4kGk!8o5<25&;mbly zLZ<5D;Tz36q2n5k%!VXkPC_F7Tv(N$jcy#q1?&`Mb}uX)8G(0ulJHtWGX6+7lQ4D6 zeXz)kPOL*(N}MbN6H<+FXVQ#FTz4Aj6)hBp>##NsC~e6QFvxnj7Hj0ynC*|NYVRF(MY!_Zj z%1tfv%eXQp^4b*HPi1g%Q*r@c=L5&hKDP}9Z<=r;DOPzl@Fu*Q;5|c7CCBQU|MMQ} zXSjt>+9abUviDEipyAX7q=wgp^5kjDb_56yMs}e%n4dY<#L5`%p^DUuolWN?)T97v z-Yv0*mNLuVZg0~4cY4o`fd!Pj2rGNo@v}d zSbyIOKPFGHUmBKiJ6ln<%cbGMy=n|o7uIgjcOdw857Le1{AT!u=Xxt}bbA~+q#xzz zwgGH}qniNJcPfm*QvaTQ!uB|Hm!#SzyzdbwsZGO8+(?Ovz)IT&{)p`af7y1>GZ!$y z4>H^rPN;F=cH96J?ppr=sc;umh`e(t4Y!CJSMbd>N>7Q`{8R(oxZgbB9-V$rXgej~ zMkrOg{sYovEj%p*v<>*FMur>B)h_%iWk#wskjCGH6*>l3E0c4?cO{s%YMfKQzDFq4U&ySKUEQ)k%2P7{j@gg&`lreG9TE;`mW*%LrV?ZF0MY;uwVpq#8(^`vg zLYFz#*!8AtQYUS}nHy~5T$g20!VO(~slre9YkLt^T0WK7f^*GeFp-AvACz{Xht@vi z$>bjJAk7~=NdKw_>tFUz=^uOO^mdQF7t!Cso)v>Uo|(cN{fufb(k@87_Xqr#T(+3CDo{8G4)HiJ@(2wCZq7$ACs z!XxSTFmmx;Nq8mw9;(JJe4Bm<5~d9b>nGfUHwkY~m>70m7td*IBfd`I!i34VO$eK) zr`Ak3F==811tSp_F(AyyTn&Y^l5i}ucrhg=OFb(y0MZ{u{^{8vJ*4gn_559ry5-Z= z`z0G1_I(jVI`TA@BU5t37je3<<+IiD@+|IU_&VZafM&$ClILOH=dgnow!NK+SmDJi zjZl`AGI3wBHtEaloP^PIEq%WX$Ke7o;%Yp*|nV2Ofyc_PQBhgdc(79GYTqPZ1#T;(r|CNVMR->0L5&Dl9K*mBydrm#MO7fgDK(k8ZPIX(AJSQ1Fdnvm2V zOk!D6PfMK?*AabxW$*0RwnYXe_WV1vTKFY9_a0frb`#Q!<&_qIw+)4nGWkQKjCFJP z<}Wvydug3zE8#`E<+wBG`?Njid$C=Zo%2B1b8#bEzI4hnbzQLG`ms0HxzC~}0WIh;L?@8};x zo20|jYQ%C3g!UOSoePtQU&nd)0}#d0z97$ZL}n>1>SE%-x;WbZ83=& zB)7^d;%xE!E`T0S_q%D$u@atWv##lYOojv1Ut?d2iq(b-9xZZ zwFR$Nw+OZ;#@p#F7v+(i;jr?$72%y>_scW|d@*P>(nQSU+pyRo71%~MROk>;LxK*{ z9l2Fe0qPmA&3sO}I-RIZ*pVh3U}0;9A3Ddn>88tIT-4Du??qv>q+CWG08Rn zh*Xma0f9gvwM4E`0H^s_t8(jPVP)Pl%Go9y${SZS-kra>TS0eLZ6!Lfsy}GA#(|3M z+`_)3ea+2%M^x;^mtgvk z=TAYiq{%o41+1`d@^oR-n9SsLlA#k$8r8*_74+6cnCi1c$MFs*wr3%kb9?4$ zwmLAdal^n>Zp9#IZ8Pb6DOzb;E3ScUJ?QJZ!>|$dJv0x3zPEzZ*68wZ&3wFIp?&~? zI;76BVD7L_<=1bGte~_@u(IsH+{3qu))S44qbk~_+e-5k@CjJAJ5)Vw`}_{FSU?t8 zv}DnL)D@5%^gRwBglodf2?!R^VX+LL zXad5wgYpWbx!WumR~E*VY|f+sf+q7;nmZ@Q=YzhBLSMnX_Lql7m0&Q_eVsuGNHn#I z;dHH*t;_qj(H2rx8}wZWRBc@g?^SBZUf>U9_0u|&<4 zhqU9$5^R+sj#_L}>Z3tl2MVp3^QCb!^#dbSW{6EX{q9j^F+=OOQF^<6ebD#MfC*MS zTL!WOY@T9i&_^_m1Y4wc#z>SF2hZam48SuPvYc!ErRdharx&J^W)ed;yFKsrGFFPOxFo1Ye+I#5*mA%oR`!y}lZf&fFWRQ~95hl+7ytwvkqE zges#;b(0BSEMhKk@vb|uVJc$R+zC%XEI_zcfY^NUXNQdYC3Q!V$f#s4 zDvNfH7ac0(NXA}DyWM7lv8mPog;Ir>eBH=S51M2jC_Ij#%#`Cax4fT;)^EI9@2r9K$5EEOd|>VI z(aNKs^84JQRZkBA7%8vp-H!fu)fpph&*NwCWZG>K)kw4PA0BFQntQAmRB7FUZK@6= z((O~VcC4`9nt1%*S8mGf1N!3&dLwE3KCCJd_RZ5#C4wtD)Z2I_e0744QvsB`#z5#IgpF9em3ec<-{ILkiJ z|NgNnx-Ih{_1E`FdwuUOu!kD-ynlCI^$em6`@rS*b-UvLQr1cXu^ZQJ8K5=*rGjQU zuZ$9L;7v^dF&OkgAZnvM<BtyymMXo7a_`$xQcexgI;$Hh!f}iKgl2I zTy0I}Wx)EM^2${YelHskqfgjFQozQVQ7Pb$5IZK9xj*XGqQ> z%K*4N5VtC*PD)P-PFE;9Ny=S-i46VFFdIr+!^*u_{;@mOGdgiEyGch-6IpISpL3|& zb4h_ZM*$w^83&A-9oQRF_)wEXC@9(J$RsSPMAp|F*rO<5@-_E*J* z&NUU4y=4h&tkCbhiTrpT>lRC4)s&yTnP*1(;@V;7qfK%uZO(}fzB`fG=hv=e%1 z`BH0&4eKkUFuU5gf7mKWn>A5@6FI!g{0pp$ zfrV8>E#4TvrB)u*c}bf6@!I~9u?<_k2MsJGsv_6+)1b+%MyB3K_1Ew%eq+PN>3}_! zG-nLR6`kfX)TacdV!B_gFDD-hfpNr*)>hOwql`dTXeAj^Y(Zb9-w`Udh9wG4r8h~r z-M!@sG(%BY=K-L2zuQB0m)HCr!8$YEzQKPqG3a~VKW$fS@mmt>=)R(}F1a&7?E{_f zrveoLtN_dL?UlqitXAfYK|$X_|I33hMq~)@&a(GyUC>MEWvMfK` z@*H98w`A|Dp@ze^2PpkO5G<++nsA1nNCSoEBx$N;A<&3V;DL~;YS^z1MR3Ul>u{&^p|ZJAkRIe8S>diFesyfzIwrMZzkR= zJa}(Ta?%LWk}mTS(p350Odr0(jL4B;>LYV2u9n_70eIp`~wp3-EmAM)KA)^a-T zDUc9mNmMdg6Q1~fG96R9UR+V+Wr@-%t>Z!uva!mUZRM{JKQ|K8RBBa{zj%o1t! zmKFUpy?P_jIohk+2sEUJq}Ni*e&9%TB3f@29U-oC9$1O%%0_$#2Va8!1EK#{24Ad% zjWYNmSYQU$Bhb~|2O6xY!+Xjpj^=SGu=Ikwr?>z|#>aa^6)a^Sg2~H1$E0 zL0=q|eD7&@=&I&aSyxmh*s^&0eO%RSvuL8SY&2wy9Gbx+1MbE%eQpe9u}7?V{5c?8 zcm@&LP}-1hIIs|U?Z_J!GADi_Jy?-PSX8ltjPb76H_dg>YBKEhN+t zvGYtQa&)%!z^o%{tOo)it%Sxh5D1A?7e=6MO`x7AM*?ctX2#!9;1qxb+_2kBUqB5w z5AD0@0q1}`yiXW1CE)=fzGyODCzKaG9XGbPa^Ud#IIgjb1t=IC38{{Tk(fY4P` z@L*$W@VeSM74+XSZnhJ@jl_2c!492qz8z^swSA2EY5-+KfK`qWKk%arm=8oNE22Rf zW=H?`K97d$^$>F~1roHfl@WgvmYHJ}NGA-f~<5GBIW$B_ycHC_2 zBI>T3V9PCsD*qfI3cnA^`;dCaD&~ZaKf)g~XMOh*FW8Ro!apq&Dhq;DJX=5*)?(oL zNl`s$j-LB3P>gMtoejQId?i z1SOY=zY?Z!GsbpEPp%qr{<`XYyjoqq{6Tw-c5=%~kBd|Bd*L=4>tG4Kx~48Oum z@|+gVaI@@Rf&B=Ho1{z*HxSFui9s1?FOc{m*jmFt!^*Y{`&I(3>5D<%3nPd(nc23& z7OVq9jW!$V!$Fv^Q;?qV8qvzCPp_5aBhe%=-Yw`;$uSo!?C|^rJbyj6?P{S3iFv1p zktf?Y3_BOne=2M)oopZWrIOKv7D~Ym2E5MDB@huAfCG$%KqCCz>NZB4atbh}h1T-1 zjy2*M3lPrtMn(w;Yl3a=Bety?N-^SfNyc3U<7*U1I;`9XwR{z%Qxs5t>hFh-Z z4gIbqWJYMBauBTO!fExrY<$$%gct4n_yo}u5SZUe8BRY9Nh5rKOQr(H#G zmpp=vwCggD^DoJUR?^l8lo$Y7=FtA>40~WCc)Q~gIm~VY& zDd|5~U+VRAs8HHL@S!3B0p%dEq6O^(8!~7WkVs4P-FhouYGUkQ%=|&JH3=Ys6Q&o5 ziXErD=_=NR^C>~k&x3)+Q!a4zrP)6U5^betQmNgffhB-Y%BAnU{PYK4RC=qOK%BxoW-b$J+4msdBvn@^pGn-X z9U9+s1in3~Qo=W6k81}|`8!oZ&1lnpNaaJRjRWKm$)r5w2OyNGv`VicOqIzV%@h@38SN@<>vc+r#NxnfQkosu{4fe< znO$)rr82wYK+2A22mTv$G@9^eF+x=g2t%rI?Tnt*pD;&Uj1yVaU;Ah|>z>N#c@3~{ z^`&^$pnFO&nm}?guDi3Qz7!fTvM_iXDx;y)25Veqi4v3clyF<+_2d!m}j>C!;5HH11X-}Zq$GG z$P-DsOPGB+KJ6lXAZVfM@w8Lsu67kiKvTFjC&}ECpcza+dkr_9DG7JKCZ%hpWF>UT z;3>@xqK_J;Qm$UdgN+B)dR^%~9`aOIdfFSDC3C-%L@Ho_7Sux(t)5){HP6r+h#i0+ zK|meBAXKT=aJiW&?PSFDqMCkz#83iF*7NuNKurOaTsWzxzVzV|@FBYht7Rz}RQtI0 z675QDeJL3!raOio)!lsVebaW`tuc*9f^z8`(l^GdG~14vWqOMkqA8wk+z zOLn(M9y4m^7l(Uscx`)>6rDsUMt$kuLxY6fc*0QP`YQy?1eo2>`$+>XeBVu=0V`DOfToIqwX{n0wEM&@&Dv#dvMlXn zO%7hAFvTv>j+;(L@l7=qXjb-8lp0if261dSNlAc#M|SaD zN8~Ycag-FFZOk%>uQ{>?Ix4b6^_?s%s6pO!B#0RFf+x(5o1Zy+3H{Bb#Yg&NN-%{7 z>U%B#5khu?xj66=y1cG|P{*~ey5Q^Di1xVVh0Pzw)_F*e6GA<{+u;mRt~~9vFI18K zaj;per7t#zWtDe@8A`h@U8Tjj6FB(Aa@v+xPLVjqTK3fg^}hCctr3Mfwm zbYK@C-Ky6AFgj`AtpmgnW<#fkjA^=-OrBBdR$uzgFRcDc&nd3hW8p4xi{SrZPr`ts z5~f-{>Y?(xn{A$=n{q0lmr~6dSaQ6d)B*DdLmkRK8SIQF%(uGjcL@y{jWi&ggecUP zl8T~W&YtF6C5G;|`dDUj{-@kzVx%Zkk6_w&G{vRQ-yR>IoG7h=mE4@!PRo(xukae0NMbnJS>U(A+`|w z%5PIcHdHP7pLIPW*Y zqm|9q*vEr27=taz#UjOoB^WjTh+ZFU>d1hXQvT*S`Kw9k z{Z;L!{#7ipOs}Wu*N$iZa-(?l$zQo=L*IWW78&N>p1<5EdiLb6e-Gt-w9{P9>Q(7j z^Oqa{jBC!1*CrdtXKG9zF};hmG1kT7H*(tjlU|Cf4N~0;uj>2c>}a>Z#2!j zu2wSQZJ}sE^q7}^n9nWYP<=V{_iJI+U095<1?G9759q6V?mf1=`9}63P%Sg5?WLq~POItZvzD zj^?mCEHHSo6c#u zYMv603d0YiPAK&Eud){RFZ(ql3mBo*M*L?EUWsRLEm*rFh7_bJ|Ojg=oj>f zlCbH)>5C?Tj~>Yt2eY})V_uc#Yzo0gbz<#^uM56HPcyL_iCJfGDBgXhx|GOcvqOFj zNc`eVVT)=G!)0xX5{Fe`?oSkoP9&BKV;)MytwPR2iB!KNR6LY7v$`d0whY{dbepIw zQsLx)eiJsx+{Bf%?P@g$Jg=M~s-@3>WmdOD&DMj+km4E(${g7Y;olF9e>`%K5x)oZ z57->VD-t6f19^-Qlfm1MNFj{)No&ZkhA40Zr`RSqy%14>^y-#z+`Ga`c_KAhw~6Ba(41b(XO?JqQ;^wak%xJwdyq!yeznU_!U zjJQQ2M7@bqIsYM{>JvnNanC;_cJ2W#xf(+?3kN4UiT)QEkZ9P3G~iktl-0?Ak+=yW zI3wOSC~MTtP#dmx;llush}v@(BDNI5aR`5VI27!m2g{<-4?jZu+G50dAXt_lb}xh~ z2qbd=Vg;mA&`>@|WFS#&V;YIf%?L|-DhHkcJ@D9|ET!Y7uZHB&hVpo8_!K4s-MmqA z=_-^^Mvfha7;O#cq~n96w4I_ac^K`pWw+t~k7fPvzoks{B&CBoVG1K|mKd#~PH{Bo zqk`Ev1MXiur0M|>m5}&p4bw=AG))78{80_oqjXBM3-AHM14EVrqB0}S0!K0Rnb3E{ zfWLJYsJV}rQ@WT&lm^CldY2tsdKm%GYQnHnB({RixFK;>q9g6{^BZn$mY(M! zs0B|ku*Fu5!1#jlrQ>F4jjWzNKs8{XfjIA<9@rp(4+Do(PeRcAw02~bso!X&=rU=8Tz^A1w&i~p&$ zb(nO_MBA^BiFOQ1JmaFp?BLyLXn#AD!9lMLWoUp5Pq-9skJHeiCMe?=t-MYSv-OqX zOpeUjeIz%i&KF);0oAR6+zYxtYfj0T+eNB>7T&F{$^ln3E&evLovR!;2T#2t6ReFT zv)mJ`_2!xGOVa)(lB1+osa(W?Ri|@gw7|bc7M9E!c7K7LSem$$Z&$4mgRZ z{QuURGYtA9VfFjJ1h0Rx@6kWXK0^=#LAI)9qYSp4pwZlpsIDoJfK>(*yA)m@}YxnXTcmSSAcVqQy&v z)JJ2+v<+h27_S0rU?Zv(iXPS4-)$v%Q>@i3qpjCA(c+W-#Bw>nu?d`33s1zAlg_O7 z8&A+;5_tDmz_HVD&Lv>cti25#OKv48cr6Tn{bEgTm3rG-I9){OGaruyml?KB4omsmc0~CsXh` z(pL_2ucyi>Fm>{9sHFhf$rLh|HsTuLv!#`Ikq~3E;6DnBY#-x)3W>|+;rE0!AS8by zv@TmV=E*^FSdRK$vx*X55hgBA#zjKOasyr>tXr#FdmRSvwp#|G(p)I>Eu7Ct=6@pxvu+295E?Vaa1cqZP1g&gBel8@zveILV{5wu&wz7Ox@ zNr5~c1d+B7YQ8*#v_^<84e4RyAH^fUP=v)!tq)h;~Zka@YN&<5rk}y1J5F8%}lBaBVx*cS^DF|x` zlYqtF+N)c(gWCL&Rg5uqfa9Uv+zrd(&v8;*) z^iwW4#$pEE1-u$}@F<)4;p<1}Y}%Co0q1)?;h!H|1Kjo@09G#1=yYfNj)`LnfOIlwfxDo*HIRfJ7K&J+4E zbsv$_QVu@o+w+kmcvIuq&wu|sD22Zr61G0^h@3e3FkI+#4f1YbO#lh2|)DHn{aKCPFNCLryi;fy6WoiL0d;C+Wn<(6N$~t}+G|aa*rYme?()?+&6FhTNNC3SKkaO6Ce4jD@U7=qNnck2_dnpmmRvlgX04bg0}zb{ zr=F8ne4#bLP;`!r9swGirQmfYyWvqjiP*xH9Xz`V92$52Z-+*q`U$xpZWzb@67n)x z9uy)rCa~v6MDSXh*DkEskVOrR2z47$CR`sOkY)sbg|md$-4p;U{J_pL^8&z~Sdl4o;}Xc~Q-;nh)>5-@hTHHR0UPJ&gBxSfBZU{nCS)T&|46 z(|5oV*7+QtOKL~ny752*G*PSSN>RpZu5Ucm;MY#jFF3}J4~Me&cJr|Bx?gzgsU-W- z_Ug7GXUA&u^V^>vC0*DR^gYmCU0MjM?vYidn_>9}z^|g$5%s<4rXuwGSBLYK891&_ z9biR_K48vvId9e27rNGpak6K7)(*_I;bJ<|*F|UE0!0KCDVaL<@Z%_b4cG{f_>1EK z>9JYSwj;HI%unw$T@cE)+zqHT@)^OkoVPwJNS7-|Q{-;g&)4GSib@gw;rFB~T zR{^h&SMPwM2uQEt-jEi<1o&`R$XY*%S~)B%Uhj$`eI?*{ztVXPJ4PvJPd5hs#E`eJG;DKhz zFZ_PZB>cYc+L{{s&x3ypNpY)2PI$oZC2R7KVnpy%ar-2uW8UUhHqY+G+3w9Q@JiSx z(RExeo=~@G>?Tuh*rYCL)7-J5jZyhu9I?9>fd2c%0r?CWFkas{h^mMF$})ZB>{c(O zn&4{n(yDCu$Dn!o$dSz>@y~-uc=q>2_77n5@eqsj_DuLXZP4dInI`c?$5Q``UK1=Y z6D%(WeA($R@b%IIngo!K{>Otex47ZWhz*+;5{rAG^w?yD#sFOVDT&cE zIO-+2reR&JN1Hjtt(cTg>d@>j5$e_^*;`#mQ(yW4BqiOcI?f#_(ve*fZ>*IT_8`Mi z7uMW>^oTp@EW|vJ)`Koe^CO^MgLwFV46O{ENg{;drKU6;IVB?lMt#^a5i75em={=rYLr9b#CJd<}4|M@D7DhJG#l#1u!iFg3A`cEa> zA+>ggw8B_9Fn+@hi9W>ivEfyJVs7o;V272_#B)_u=G#40mv=C?mTWk(Ty6dIT4aIB zx?5uEih-WY;6iek_~;N}$wqt=f{M^dyligB#|;0~Gnab+p1S=C?htTa8-Wu#2w?{V zW6RE_oxHL_t$kT~*vLR>*!zZf&~UsB^cTw5{W36q`hE8fWx(sdhscpSQbBb~1jl3; zV6`JLMoTBBqL?`ufQ86Gq(7V#&uuqTUWyvmZ9=r3GFDZ0G;6BmJ+z+DSgXVIZ1tY% zFRH8C!sh(!37hj1gdWeYkAR|4!by}wJ$Z?&7zCuhef%Y8>@l#&xghR@fXb>%1Aje{ z_jChRz6W{*bsG!YX@>BxP09AR1{ECdd~=fnd@RleN~LsE-HPu$vgtLm>|!B+|8`)l zI39)fJPavAzQX|#eDYh&p6`BV`)f7QNNsDySQPLO{%Oe9&?dp^-nj|it2k%lhkScr z!y--ze&6L&$5Hi!D!yxxu~>Z{5;gwuUNu-Fs&w#a$oF*M7ouLO{6We%R13=3WDbtb ziLT)q_>!*C1~z%fmpnAeCKKEs z@sU%&=!@MWDl5Y+=99TPup_5%M2FQ1LX_g-kWV&*cqRj^$Qk`ElerMA$WPh~HFQtH zF0ilWCDagwPc3ljM5FY#k#KDpy$c&6z^Y5v05_g*u_3Vssv?GF7JN4TeMWFStHI@h z_t~icapsnXDes`LZOb<76=Z*WRYsWqG~x9>recfm@gE<>nL_GTE%l~fFmK(0okIK8 zso_Wc@_ODm{b7QzaHH`t?9TNW_EVXOlI7*E@lM)Ao zckLXWCG^|1)R{qHyu*aY2oF0Z;y(#?MpJV~ch+?812s z;6hjg=S9I!KrqxSOMDb`d;uR1JYaR(A=p%q_yEi_los$kCcIViEdH~g-=>GYm2N9F zoDTA~F=d}$qh#Q10NO6PNoUkp&8Z1MTrvo!P!#1_22vQFYtDS4b2wA^}nsi=b z>+*k?4XwNfXK$NMgn6?;x*+w*Qs|2sfPL@CCC>#ZF1OE_WSh%&i{kllA_ z5Dw}E>X&F8rARe3d3^6HT-C&+eySPgS-g#!Y z2;=NEp=Z0?{xhs48Q_VWtPT2Fp%{p_0RL)GI+1F~*(KtiFc);9$3j>+vJ2-Qfl>N< zfcU}5xBwj8BV`+*Y&et+`W}PkUT=Sb7a*qqIh#YZ5CP;1sO35EvnpTQ9S_ zy5&kZ-}Ab#W=A3xgk3xII9+&eM9*~ zpl`CUZfEZA<_D1;TyCERK|K9d=)APp5)EQ=^lWMZJyFLi`NUSG%?d}9qWET~0FL4@ zTiz{^EjKc5O= zf3o0cVa}iII92%OPg8K2KtER%@$Ud(hV&~2eMd%w_0MI*3=RKx$&Vf$k$lsII=0G-}`qM ziW|*`oRmER4hrU}1HPlff`i(xCdA*Opdu=z|vT`zcX8PZ?jfx_n zPv_7CJiWoD=cApCU~Wb~RJRe3t_i{EcA8b8>araC-S6H(pkc9d{KjI0;^# zPHqdZ$ib~}C$+xU?^L5{}3wI{dsfX)YELdhe! zl9U(;tJKa7iQj{(Pj%a%Z$t2whq8u4U&ze^)TvXT03};$4bV;%r)?!CAf?KHZ{nG# z)`0H|e_RiB#{upbXpK)gUI#xZpx^$7?GpR$gC!AN%sDuL1!5C8-%B$g4*0f$;~G@* z(!&yyB<~AXYDJ8@0mbVQE-I}2Y~s(sJ|u-Zx)m(A5 z=Z>1^oy$p}IFw~`xvx={gSH6gSNvsL9oV}mId?(HHzwHU7b|UfHkLPm_gl5C49;aU zMxrH3uzUrKZ@_2q%e^e~gHs9i%5FH+++d4xc1sb)@8DvTqa}vod|SbVqkS@&H}2Nl zeBKK4b5zGv0(Av^X`qJ+fWz~L=6bLOv(z-0RX#WawbygBWc;}|``8s!33uF+1s+T9 zdh+@3KAPG9PNbO5vu&{51tpq*Vm#xS$(`|-K}(3iFVkW>=OI;JAJm4hwGob%qKsJs zj~}1Lk%oM}Ys1qZrO1QQmI(iP!9sPk3P~@P&3pMY+}31^gOhr}>!3|tUl+L9PX(fp z(neV=7NoI43YkLHEya8!NAYlk$ofkxTXs1>l_)ASae#KZqz}VfzUVjFK*=MtytoM8 zFQ{J1NuN5b06$DMY&8Mj3qYQ1P7Gdt>`^3265Wu=u}1^GbYa;`R?0Idy#G=X)io%5 z{nC8ueGvKT=Hi{gy1Ms3Uz57GBy8SZ#A+c}g*AH(wT0?j78$oQ)0_={LUugOgElKlNSiL z_D#lFLb@<-ArkYYOP(34kiqR*0{`E-@G;ZPh-3MV zvhU8I_8hpwhU||KFoeazy!}&Sx?A7#vJq>pG2f!hux?~X=!Q#*gxB`RgVpkH`?YwU zaAAKUFl4v(XQtHsH?No>{U9+tKfug{1G+G#pX?I~UoNvh&yf=-+a0^jv0UkeX8*RE zX6GlM(@XOsaj)rBlc^U+>^D{R#+KN- zZA4@sDId;+6|sSc{yk>Jh0Sph00?!CSe&joc5q)N9BFn2M#RW~dMp53%m$Ejs6=rG z2JE=wlgEZ-lAcvj_Tva**g046mfxPdRoZEbF5&)&QPzj=BJ_*>8FP zKeWbA-+tAE{gg<6x?nO|=m=?R;H4(I5KA`hQ^e0&~{sM|e{$GYANSss0@RLOcPXC@jGGcb8Cp`Aq~l*$d0!!T>{M=XRHH7vA<#VcO!? z`@(Vif3Q^Ai%S6v=@eke6K@ANawnZTRgw*0OoU+yGl4sX;!uFvRax>mSI#AT7wdY| zd7>|p`duGZDEtvaH%+s_)y8K6Oie@+Mh9^csGgM`Id|@Vx7#BBm8b+dX7;LS5fGlZC{+eJVnWE6aoiIa$(IN&4YQRD8vTYt-^L2-8lvs=kOMYXf_U&Xgq*?CY#Yhx zx`y($_p`O?(h*MqoNqx!sRd5k-fszA_?BnQgG=t{TlQ%B*471$lmJsg@=t>DxBNNq ze-p0cxb1r#&XpDLw|%b-XIc-Mi`*!Ue0^njB5bq;w%fkF!)f+11msG_=^tbyIp7@EU7RGljoMc$&xGKEZm}0*l zb_5#)8cqu=w9rJZ)3E#eWo^&PPj3m_rPVh zeN$m2kawiRTDpvFx$T=YOoi^=gNp>+68aCO<1<41YpGK&fCR{dWWm3} z!Ii6U6+t0rbfOqP$ck`)5NsX`;i8w%A(t$a>$6}6=*rFuYhQZ`t^@hywRLbO*290^ z3_1h%pTEH$3V->_n`unB%o@&913k;5;lc@WZT+0Ng0vw>IgCXtM0!cSl?ownh zZVfQ(F9$Ww8x|toBAxK$>!;>B6OReSC;o7FJhpq`R*+p;h+PSBIeE@N?1hPl?T3&9&%5B;wEu5F+7XCrq4=N< zaDTKe14kwhx9Tx)RDx(A1{%wd3zR!($iR^e6i)?WOCZ}CNIM!caD?Wj<}v`A4Ip(O zV8j3%!&>r}1vC@BnPaH{<79(nD)pP=fGcHy7@~%OVKsf(O(Umrve%y%)k#}F#ODgNZiew{A`(%;r$8*4iE;}bskEq7VE1P1MRxo z1T?D==#HMw_%F#ubB6xjd( diff --git a/boards/holybro/durandal-v1/extras/holybro_durandal-v1_bootloader.bin b/boards/holybro/durandal-v1/extras/holybro_durandal-v1_bootloader.bin index 388ee7ac7afb5a0f3a9e53110a7ee7d5923ac7bf..419f629fa409c553651f7c1834633093755a2bfc 100755 GIT binary patch delta 21983 zcmajH33yY*`Y=9o&Pj5*(R2aQh4v(Ap>0}77odnpnzW}I*s>@E1X2p#AbKf+R}>^E zpp->L4tiNc5nNDIXrW5M(kkHYy$R6YEmWk65}+<8v~W(6w)wx4;=T9(Ezg(dnarG- zcb4*os_|zRGw6FDe=>!=y;t-Q@hOdtw@KoNPMd=t~~yK zD;ZXb#Pxn8CU}uJ!-vEb-qxOq7h8Lly;vc3>CemC#^^*$ord_lyyI?q$Cy81koZ|2 z5<{V$s}Hpn4n--f9itQm0zxQ7eGsv=W$TWdlTn_&*P*xcI&wdQ^rPiizTf0yvMp9;xg-$go=jBAm>sn|QP4JxfpXXl3!og>#Bh~^uDJSrD z?!Pj)lo@5G<+POP@NW$M=ciD&QO;@Elu`kCnNR_xn8kzBPeV-7+pxc##8D8NVMr)t zJ0dyZX=YIgU4*B>Fw@MvCNp#wOmAcS?c)KGNqY%W=k0QDN`-i&z${V#-kairPRxM9 zPlKIl(zXLoPMJ;{Wj!yeVW=t?I}MQPl#$SgI)xJRDNTmgbzYtcZ*H1y?nN-TnJ~C2 z^87eFKYkk0=jBR*8MC?90p*o{KI`m|ku#V96+{3K2>_`OY%m%ci2knz0rqZVq6y$C zQ>Y`g#bm7O8IG-)t-^njJ_NSQesRNQ5`Jd%FoD|c?6iy1c5yxTNxxiEeE8V0~h3u zJd22GEWvg<0PcGz{~qEC5MRiPg4ViHVk~FmF37tMdDkKS72;nZ7V|RCz~2S=XUO;& z;$Db*^VBVaZ-5+V+F$+{xQS2z2QX3#-zzx#u=3$$Fwyx@^>nY}iB%0aJIWDV|3t%Q z4M18yL>`2@j1jSE$N>qVuu-h8tyFbHW>~pn^GF zZsRAl#RP3EgHrzJiCTyB4(%U3>h+I*R0r*??@`yQN?kHa$S0LPg+`E;DUWlUZ(I+> z0qJePx$uJWV9}q8jVwr{gDHZg7@Gyt2vZlE^=D~qap2eSO`%i6d4nyiIgwAd;%!L0 zEvMV?P9)X~c9oVJT+(^4j0ySXK|A%(PAyPheHN)Nw5g6ouuTMvE3FU%#<_x>9d0Mj zno^j~5f!2%8|Z!nEIkO^h#5GhjP_V9^zB6!v&8y2 zkl5gZR&?jTP5Zn216md_w9>dCt<{D^IF{D`_>%V5#Zs4E;0b|VC_%@AUm9HDyr z-V&bS15$-BB4kwQ!~oYEnR)pJ%BC*IS*auHmUvsJCEn_F*A@>B{=A%-bzV-J1Xy1W zSl10=ecfHGf1t%BNF3+AAiNYZ9BYMlL-a?TA!(G33q`CE0^5Ye!+s2-W@OBaVV+#eepXE#>(8thCtf&n?IA+W6f26RniqP>aP7AG{!@ z#fx4>pKHyvVMEbnqs@V6@po@Vxdw6=D_8P{9f_>}fGw${)3(5h#fSP5;MF|7c=(Tp ze1&j6JjVV?e`0x90}^xm2@tEq27i3;*%83vt6nTV?N^AKWJVuSVyGqc6fgoLPLP$s z_^^z{QGI>xT-#jK2s?oWX6G1$U*ABiHUhC~NS}f5ErcTw+913SVQeg7Cq9eVAJY=a zG@_J%G&`UuH{E&Kyhw|7Ffhc6GRKqoL#^K3h|L$Ck4RRO4nb^*&=4^S&k`<1=qYWa zFc5JciS8T1(e(o}gz6#7@CSlxNHYFP@C-?hd{a*2l}Bn@IQ|zK5}y>(BNxwj)ypK^ z(+T+^twdr6JcV~|Y?#hZ;L~85KJYO~3Mhp=2TEct&1xX&x4qh~9DZ65;sWIVe(BIs zWbin%gE^ChA0tQD_sL9BXRzioUNZKU>*7Y#IwA(KSvRB#h9AP??YnrOyN&-l-CdFU z_Cau5l2Ik%I%H(TWAn?RZ1v`dPPMHKrZz^-D^u_&t;iK<+z8aVObkO4x^PyM?RYCr z#S_x)rWvyK2;E&b5*8?TP;5W#LN3i&yFCcw6FdXQR7T*F|(?1!IoC8%nO2 zbVu1LL=+xTUW&4#tnoG&IikAHJ^o4e!bql*65kDc3El5-SIU_v+=Ij8ZJ*lkJ)x!| zS%=(0cGQUKP5dri#iNv=d?~Nd)f#E>8Gi}CQLZ=9Vy&M~oO&{or}FZ7W%mY*#b>=r zzT)Nv7Nr$BQ8ycU(8IDvd1g|ZjP{klFlYH0{zzddkMkU!9#219} zm}J&;;ySbmRQ`C3Ibs&9i-7cgfE3RVK8+cH3xz8&1vppG#-#Kz%?!c(z&d|TKXJ27H?fa&7+6r0CQi5rDqV$*Sn5IHm(3qrxr;rM%D z_RtZN@&c93jAy1I4f+`!$Zv)%Kj+MiC@#MRi68dC87Cg<6W#eu439kOAXGvityz;t z#x+bhI#kQP7QksLeyvM5_3*G%z5Pz3(h%)RU&VMz5Of=`HW+Lie|7OvoBm;>Kd=ai z4++DEO$#|Wz%|b-p~R1c<--iPPS`t4pZns#b3nl;t=*;ODDgrcN;}}hdV0lo?tpaG zpT24zEbcG-N?0D5PLr+VC=$;JJ;N-qc>_A2UT8TGtUod!z3vzOT0Km#4j+c!7oHqG zl{%{tJ|CWmzZH6hPlBx@TQfB7+kVAv($=reAGavB7xbd#Kdvu;*V-p6(9EcC^egss z-aUug`i;=~Q2#zSUIM==%GFJYwt(~%nNKm=+j3oP3P|Tp5Q<=%sB+9DKxvtG@Y!MG zjFiXG5u*mV$JXUwAM6>4dpHMi1-&U$X&;1-`+dYroZ$kE>kv;`q(ttcxRpt|Eyk=}Rpz4VKuvv0hVX}t%7`}>>DyUJz z?;rI9$7}Kk#OwaI0Kx_k&JYuZ9t6#xC+l(@uPL2=ts4={TpDerGfiK)h zHwgKU{@>genh6^LoKF}M5Md?OJ^s-a7~MKx;5eY+Xg}J+@PpJ+*+5!S!OrXUEw-+( z9k3p?UA4aMt^^d6d1Ff%zO8|@2CbMk4K}k0nn9jQisNJRzPo|+l=!s|?G7#7Va9uU zU4zXA`4|Bz)eqLGhZM_yDwHQpEX?(%*lxiZjQ|eG)G#3R22z&9Ht5$JGSjXBsUP-` z{FW5kZFk_;XdvALo24NN2EEtU)vPWd#7l{PKOrPV4->kQlo9nlf_GTrFy4O%JxRG# ziBC`uHNvhjJGnG2&xbgx^-p@y@CmjXZU$OQ5>6&(YmBFqRj^sbVRwvrfCj`>It?L&4^QptA!|iG7x>Xe)zEO zWV{R38_>kP0}%wKK`H)A7Ut`D{Dkn9em3=kcY8`s^56U|*I5%5Pkq9I-22C=4}Jhf z7UegEPD!;X#d*TCl!=tLUw9#9G&3Nr@C$7z;~0hL3JAWGanz?pQ z>=YtKjtb$d7j$v_fb_aBY2+BZQFv^mo|--C==PD}6m0JY(v~t5J~UbrK%BZIMjR6PhjWNNX5p`H;Yd0s49nn#`ue;68jz~}+_Hc)-)~*U zHUy+OLV3mnJXLr$V+QUQE@mW5*werNuQ4{g7(vHa34CV|z60Pj4K3GYvR$5(fgVr^ zGF>mEs_ac+r8YQ7pAxbRaWQNAa^YlWGd(T_c)H^-WoLxhh9{#6kH+we@X(51W{+lu zUigrX5q>meO%5rgJ!%T;U2#mF95BeFxG_Ro&d-drmm)KvZgKe z{)(GZhPTW%FvBk#qN9Y;%vh^m!foP%$BSJ}jR|^Uu^>X`2J*;0M;T`We}!h@%HmF%eM7I5McuPrPoyV6wvfa zB3!`wC(iFKEz<6x{}?LBWy0TOj8)d4Fh!h$W@Xz^rgsoa%+S zZ_vQ;(J!4FfIS#QmD(m~{W)k|IQwv9A-(33GO9gn$_1It?^K1iUyzw91y=;Jc&dmM zXP_4>dS!^K?lcCETduZ+^itbYzE;79^K(_<7ldoZ6v{RrglEU&Fkw`-Q47j1eJ{10J6BjEHWUWA_G~;q?5YO0}d^{XvJBGNjgF0Z`Z92<%XBuX`GH{ROx#Wh{xM3Gb;O~fB5ukqsu7m zT+H#iDhF#iYDi7p+IHxIg2M*uHk(LSq}#KQ7m#KK8KF2h`g#4#q`bmo{yV+=+87HFm@GHXSn%lK_p_~*n}sX7rxmSb)+$6= zu?XX=1G8CIG`s{`CD_JfR8ZfGEjZ<$?rAb-!p21FZMT~AcehV9aE?}EKsp*=bTw-h z_NZcNRt_>ur%oYV6kz}NR=H`&5*1L+{N}K=M&Z*j6XqWJq-O00@ymLii$Pg6e+#{Q zwf>M<^}WWG`&6fjZm(Hu5lwW>-?VGv%FFP%s_w+?jg8$0B110?E5rJ8avrg|vj zkRqXQQno5f583sQy6hTSPB?R<9a=(^juj#X1zuuW80dmx(_qDb8WN@HdIuK5ib*r+ z^qcj)wKaN?q4n!1z5ellG_KDCYhG0nko<5~iNyiw5ZQl$Dx480#W)05SHMBfz%u0eHA;QvYnxS7;^Gu9rjZ`=p&rn!Az>)hWbRCn2*B+DO z?CN830vGAqIIu$=*2XptYy89$9yzij@)pZh$(bT*O&y2WD-gy)7(ae6ZihH7e=ukv zo(!R7>|mG#aNHVR#k5lylq*Sz+J_(2uOS*t{Yw3sPSvpX9r7w;8ow1bmN``mhz52} zB^f=z)rR1trv?735RgEpu76XWZ-l9;qs3$z8#0`fA>4@!7hEX)oU5$|#kBR9&>K&h zZd#D_$)R0Xw9`t%*^blQr|C!`VVvGh-uZNYgZnQ}zVqZAHyPYJ?I`0d7io_&40oY1 z_THMqP!B27Cf}KVxUIVl4N+Fybf77%RwLlQmV*T|I>-@!(EmJe)Aru-!x(Cn9H#k& zJxq*#rRW~HrdDOYz4|c9u=lPyJlJ+Lv^{BpYq04F9slQsza2Q|o_i9HprM)-naOF)UZSPG#Y#%fE&d9?xYiKbN z-ehtwcUV{U<1-)^fF5 z`~y7Ghv(l!&}QI64CC+n@YFTknrTofeMoxjwSPF+rTF2WL^R+ugWxP?S~Rydt;NC5}}3L!SE|Id3@{ zV-g>&dquwYjT4}{GKmZ8{zo=0Uk%eJ(rOs!oH|q1AztMffeyA-h^DY)pM8r5zZ8(} z_}=OcgSG#&?-f|{lrEotq-P!d9HdtVkCfFb@ve8|`D!?3`V;lEKct>)pUVJ-Y@U_n ziDo1&sS8M#`tC~9FLtPKyV@3Ioy&4LRcTC(t<{0Bg33agYV55C>Pn{X7#grU9j|TtjdE`AG_4lhus0 zX@z)OK&q2T8Qw|oLzG$sA|T!NzVE)QLhXY%`S}`4xHUVR59C}RX9Q9^P%oSlSL842 zKp7ZvMLzS!L6G7mUzBlw5W|%Qdqfa9bNnyE4*4fq zBmRxnj5RL-t2(7*Sx-^)p*6q?YXBodmi5q}z^latH-|(4Q>@8Yd1&Q5Dyp5;lji+O zWqSd9R|j+Ql|$O;J>|{R9+FQ6l@EriJka4J8U2nR2;M_fhO8%%oy%h3IoIrK zgQ!0r9A23JpKj9N-@Ts+TPDWY|L#4Q5RjhpPS{jm_>RmvKDx%0Oe__XgmESJ8wQg6(bsS=w*}ulTG466bBe0L-xTw#_(iJ@L!`dd%lHg-z+Q zYIz!D-krq?5D1X|sx=MN1W#~%l5PNlVkjWJAgsPO9gh;;x;JaY5B)$rkT+ju`5RUu z$pF*eO30$N$sqi3FK5^4fK&_QC%AAv{qa8Oc>fceme=w9QmH(mJOFm5K+c^;Fd&6M z2m^yG#Ay(hKwJW`4PqO_^$^!Xd=TP;5Pu2rmthsX4l8gu!285P$b*mwL6Zj7La-Qi z$V=DQ7s0GAT}cFzKSxI1`o%K2>6{#%uNTn@Ai@=&L7F_z2HWnY64R&wX`8pcWI%d8 z_`lh^@&16cDX_7;qPO>P1bVbSseNEWDaF$~aC6~i*_wcPvvolC*-GjOqzm^`v5C3! z7sV}R?4DH$IL=LlqMCWM_Ch1hSua0iS|r*TRmOU`#PsN@Wjz>54#;J-S6xV-ILefI zsj*E?scw^vQHe%}%xN8RxK`z-qjBzbc~XJOKx(Xm)INF0wCgUUt0^VZvp;~+=u3lA zbYAO%DGvRDsRyj~t2ROiSFJRFob&6KAOr5ilO&gZNstMtez5$3DY_-+VBZ@Qn^0<> zbjp8VX)NK}au3uX@jY2@%i%0y8?Coq1>qgdAY9&6u;J|maSzQ0b8SAE2t800Jm-^V zi%1iLZobKW3+rnZf;dYbSXi11(qT6FXM_LY!GCq|KQ{QUfekEDCb}u03xHEs1;9=m zTQ$1ujGR|>29B>Run;F!X>43BN;?Lp0c=K`MdrdSvic#5tVtBiqAL~5i~%mCG!dYL z7beHshnL5e?5-xHHpe=9Nqm`Bv=?Z5*I)<*S}}k_El4}3dT811>N?$S>wxs*00{El zCpd!4KIxH9h^aR0eHMj72>mbw<-LhmLgN~Up9f}-P!tg}yNI|z0_>4p5JLNoz{VGD zM(d6sUD2)TYP22gS#QSYiD-+r<2_r<^hLA>=OW>j8_emsSmq_N2P*foIe5hxUo)^XSgC&j8q&pkLe(qu&hASZAWCz zIkF%8HK6Q9>J3Z!8g#Y;w)f2G=YO&ZR-w`|a_ZPXjg196KBfz0=3Y`U1$0evODc#; zMm`gsrvyH6M|0n~6ZwC*W17f8|9XIECqQwn?UR^3urYvTkYH$+aMscub`LR#s`nN5 zNn3=s3g1#7+m|LJOe=~59mCS15%_|zsVE(PAsj8581;$#C=BZNCCAJv*rSnnUI-K= zB>w^?g@{Wp%RI2%6r9&Q9DH95Ft$Zz0`rkDfuC&u94s$LTq&pXcsG3zi4S`fpd~=! zX0S1a0AksuerYoxl&nD(G+A3uu`T&cSO*poZ6>rw5t<&0^o+-d7T27)QIw0sdu7J6 z2Az=|m0)#-^p}wSwzB1Vz6pt=j}z-krmK0o3p%rkVB`XK(SR<~pSOZeyz<)+G8b(wLwHWbbS;1cgHA^%IL9EgUt*i{t zNvcZ$DN%T-SU=})vVJo*41xU!%8`B@X%n^(@ipj60q;i)8*&Sts9&dU!CJH=AoZOh zqmAITO9;k}^ZfgtL3GM)L0yt&-&lfJJA{cd5o=D0lJP`J#*>l3 z3wCpwS2t~M2rXnmX^oBBKvj)&93NjB(xsO16k5jR2o!*(c$^O;z(d|dWbnK0xM@C~ z$GK6fP`b~hj;}3NH&KNQU!Jth%sOLaoQ!0gfYK#bbbOym+6?A3b&GI+>3s{UU=6n| zsVz=!f)(;EEzSmnz28dhBpl&9neh_|G<2%LW@!$c5_*4F#T7ZzaSTR<^#&`E!e+|M z#FOUR=PgA&=XMr*+-;E{GJ|sy2?#a@_Mq^4X`&r$w<9mh)@=fa`-ICy;vefzcv2%- zC(fk=gDq%V9`_BuvpDrfLB{)bCz4WXyT=JU6&tE6<_r1BnNvDWcnp#EIb$H^BJXvc z@aQ8aJKysd>CVOwLq$iI;{I03&*m434ueo{r3bfvt=j1^vQlse>~xN zIMUv`_HZZam3-(x% zi3|s%qL2!a3yBfKBP~wSRctGxr}Zbz;g__kce-g+$c5wJrNaSJwX^uR2eY#4zCtvL zKr&8)trQqhJZ@((X`X@UT3!|dGQ;xn@YZeoPX6s~HYB8*Rce6Lmo(qYqfC={eBFJ8 z7kSFQ=ghSVF)QRVcZFyOX?2G;a1*|2G}uTtzqn5~UY5CiSg@Ak-HGM|R}9a-%jAX? z;$3kKKrL~`^h{^Ghlw2BxxFa!5}_RO_Eaa{v%4tmQYZ`)?>W%TvU-p!Y2l;RjGH%C zDD*g&3>yJ~ANSZ%kgq9a5N;q%&y($@vZEk3em`(*9fx0u_AF(5ejdSSNPQjaIvsc|!Zy~l4!b}LLEf9bX)MFZ0h!R))*|gY??FmmvWa{^WPYjGZ)MLc^-FP=4u(G21)(}rVMTDCjtw!x5g&>%D>szDc zn8cmMU%0zKV~59m?k3$+K#rff4cc>Voc*3BH1w-Rm-`!7GnkF=a3QdwCO$87M!QZG z*$%YHOeulN4khZ3yYFrA9UP0<|w?SreFu` z3AssukVd=G#i$Ty(iabN4mM>616X>bFj|hwG=hfZHAhBoTUmyv4kh*DVQHGg4;=BJ zDuC`!njN>!IQ;Q+H^cfH4|FR-2vT=;eZwD60Gh%oZgwr-dtsqsPrF|6K&z>zEgM1< zYBV)&cawJ>@qc<}Q5kZ=Qx!?xvIx$BW%Q-Skc{Gv5JOSNmFu*4e`+E8h87mu$GxEl z@i1W*!9fSNBkfOa*x#zJICYAdt&YaF#@p@`aTpV-PxfsHqDv9P7Dcc{WjfjSA8}KA z5>`EE2z61wrc#2%7H?B+$1qs|X-nU^UrGV(aex!-1jLuB_20X%f|;eXx2?3Ims!#7 zwv%~H)e>SEJnMjxe_{1sxeIx-ThD*Z&w~F4-0{7R3hV-YxQoi|Y+T?jxTU1xZ&Hzy zd*>YP0oout0ongTx|ML^!Li%<=WaqKLE9phX6$HR(Q)8` zm4#DI;yt;AN&L!R_VJUTL$pBYp_B$&Y-^QvRd9{}OuD7xZ_<%hobjNbQF?H&+@R&O z(C`9HYnJvV42Eo=W7Ed?cUPs)tjItmUEL+4S=&Blw}|cnk1oPk2Kzj`0(NP$AzNbKWdc z$k?!=o27pR78^v9^<;O$&ha@O_pF>h+`_i$++U(x+M7Q-_Ke}K4%>;R$ z2Vv*6n@U-IWGd!f|LtBuJ7YqWv7GMyoECmVtBt>_!e0L^Ls&W^!M+b1+4dco_NzLK z5&iNqFg0xA(YDS6;?`{eudD5sr}J}pw6hdm5nNn7#_-w1KLcFjLUl;b%J>^bJS(r` zxA528F?V}>={NOi?swH{7)x+`OegZueMf#T4qIG^C$bZc!XEpp>wr5D2nb;_Ct;mX zI#ZjM3MyIg64+_L>pH&ZjA zHxQzyt#It;X}V@Cnb=GuvRWG@`udrq>z8i1)j;%3UgG+5KUh^FE)hr~$9ye#W@h6< zg8l(*Of!`9UiuE``yO5!to^Yt>w)Bvb-tb@<%K=fzX$nuWAlKt_0Qgn>K4nAo`!(* zpjUYHfy~hP-Yz%Mx6JVh=N`BRPZA;?Oqd*y_@GlMm5yCVtUif@@uw$=e=BiAC9($+ z11AH&<~K!xxyG<6M(hXv=rfh79f@{f@q@`pe}DjZrxP5KbicdL0=xQcECQD`c8b-? zh}bLae=uj^3Sj2(hbVOs2S$2e`c<8HtWw5dOxA4|xaD(tD~PZ`6LHA>gze8=MH$F| zrulPMVS~a&45%&FYhftIPZGTg=|gAJKt0|Cq)A-4vaz=vbXOj*zA8puDsrx5;y+F7xo`@A{& z16BZU6}HYww7*~e;t`ap;z7f{ZbU8pa)-=9dr!+(J>^ulpAlM-shEVztVrTvTEB<#Q|If4^I;LQd z3Ya1ANM1+pA!0QxRCn1cdY`ThNLL3GNo}{}Is()Kf(>|a)!CAmG<56tx+~X_NQVuH zibafeA?WA=1Ee}dUvV?q1toWa|2^-xow zQ%T!rgKeLwqxaCD_@NCZyLhS&>w%36qc}jWkrCg9>5Y)9V0x3l6H9Y4n2#9HF2U3o z516$bz@epB$bJEytF!>qV!F31W>rk{xB_RWo)#Y#A$U*p39vBqpJ>L;cstgD%xu%;?sm zb)d4aqg%GREAp#HX7lfvV_jcDjrqa%nOB$6tPR>%lWg(UR4{X=7QSyD>LPez=_zi4 zWAMw04oJoUpb}8CwB54QLA(pwcVk#BIOl)doib7rG5rK6IcTvZ07t!Ho7p5%FuV>o zL0($0vr%;@bqsInA}gi-Z4@N;V?gr9A&>?7Z463rLVO0wQPu?4^2G5@hWO5CVJ;J z()`Oo_#FU|_HT%Hf)EaRV-R9P5MsSU`ED${d_q9MGg`$q1yHBZpUx}oka&?)0Oj|x zV1-Aa!cr%vn^ZbHRe5kgIxzqh4k}&-6+5W_@J|Ne(TZ8u$j)~kz|ZJB+nAJ9*+GUh z1)j^D6}`?{T67Jp2PND&NPRnyQNE{WvMarOr}*IwgcpAqWIMhEx~T=a5*!c3SM2je zlyX*DeBT#djv6%Ntjh_TYSC(J8CFWP!ojKNOtW$}qKO)i^e6ILs=(XoXCS|=&_ox+ ztAe{RGljEZQ77DZNUI+YwPi$pL}VNc|iJ?kGabgz%D1e zG+!Gr$N!_d+y;tZz`{A9b^iDS1g1pL*y<~KJ0GV?Dez9@PoUN}p_5%g)Pg;Df$+hC z3OruuUtqy=g#zoR_?SRfPs3Y;2dc|~cX*?^I^u0Fx%ozY&n=7`)a;SSmk{K@IVy3#CHXGIF?*cFa;adF3K5FfwKN3qiva&NLIN}y(o^7 zWns;t(d-HDMB9Px5L#$lR8lh_4UvhO)#1#0`CV5Sj-u2dcFKERJYBBg|Wzj9Y|f;Qxc8dlxGx z`+I={s|;Y7g2vGSxDT^GFz9er+d@>LNE>g&;#FvxlwCZsL|7*7(y zTEb*t@w?XAruCpNe`pEg(SR}(i!}i~a52h@px~?}&&$E@5x5xbfu$U;6|}Y)qb*Bf z;H0ITp@lD*f$sqhb3G^~n9E_SXantxhk&y^?oh~AK@i@wjl(m9PTOkyqA+VoQPNNS zL>N^%3;2CNIdO0_1SDl3cxR*z{0EOONffRvG2v&0QIF^&cAWxOH?6}KkanDs1)LBk z)IOr5qWXnZk31Az8}#n2YM9o*+SrDEDG40hYjxB;1H$%N6BRcgT&T@w`lWZlS9kfg z98+I`4W+xC#7lElV2AvG5l`Fz|384Eja;$87Qs7s?c#EqN&BkR1|437`pYx%8Ua5( zm3nJHsC+z)+BP6O{rE`g4ZpDe@tmZPM-b~-f!G;OfIkeNe<;s_B6bOn^hmtgC)|2` zG(Ie7SJXY!*!OXen|);9s2jYq6-V5p8quys@=>dtU=EEEt>H84JLFZB+v@+Pezj}H zD&<6l0p0r6K}1>l>w*b2W#@s;|F9#jI8+6lRUAk@C zDkS#!@3>LANqoWaW1|W1J1y|L+X2tdIY5sh&*b83G51e5PJhM)PeyEb%GDw7Gww7~ zps?C$e%ysJYh9#XPd}8aNy-Rh@R7SNeNnImGFbn+MwIzMs4~+9TBF)??oU8HD~K!O z?K{mDfSS*#I0Nty$K{3GZpTh}5x0B!Mz=P7tV=aIm$brdGmmju8scqV0_^Vkg8;YZ zsd{;lu|u{2H+tNOxShpKP$ThfpBfh<(hMoBm#a*mL3Lv8Hz*IkTh2lZHM0zRoD}yX zV4OpLf&ckv5uDCpb*5#dw$t_BIKa}oL<4sh$S%O}B62;LQ~}!?AF&xWscpkIX$p^df!m6|`aI5UZQRo+m=CrB z73j1tywVubxW%k->0XG2T%`-()EJcdcmlDa3~M0N|ETX{b3#WY-*1=v-a+@v1A#By zADe%^cZRivv8-&1Ys9%fKD(!pG_xhx$#-tUrli8rbuc&>=n$6 zmcYtQ?R(e#8_-!ktni1Hm~MsS?gF2WUmelkn{KIs>4T1j+h({c_ql^OobNJQM>`vC z*V*Sdmx&t1GhNGiE3LSYPM139^xL3Q!6K!Ij@$n*N?isQ{gCK(TmW~h80#^4p;2(` zfEg2(i*N%JiI?E13QBGO*>8|%gE2AR6p)sFA{_tggLH$xNr+me&3My^44Tdz@@(U7 zRrCd7H4Op-f6MiO$w1HXZ_0Dv$ul54v}`nm`-H8_oWg65W~k>5{OKv@kmsqvu#)p= z2KBICnEzTt(@k89opPQQA9b>o}=dYj_R%Zw}v!EH@;+MT>F-LL$cEPjjXQSA~WQc9T&Z1TQN%8 z>-^4L(9pIt-n@1F*67BB#@%M@1fH<9wwP?M8*Jnvs!Cg zYKvjnRJ?d3MW=$pQ*jV!z0y2?g-Edsh(0tpdg2hvtt#$2S?y2?-`!x}{q9ES=02&d zpW*YH;cA&e*^meB6@v_#<<=AfIka9?%;CM#1b>7_9lk-HRr|^HNECT?@c-58H2O@R zRQ9YL5*y?NMpm!Z+JL+k87q2+tpGCHSMwZmdo!f0+iGgece-je$n>_W8<^X3R~%Rv zRet8ikUZwLX~ufFa@}cp3b={RG*9Hi%dj}3kFZk%QdwZ|mKsXwlNR-V=zge>18;{J zeg%IJIEG$eWWwJ83HE157@M9w@~kbaOs#!co@Hd9Iu?z6HqeV40uSg&;rQverboGdTNCIb+3xIHN3UT0d5ldzG68Q)i&cv z2UhJhD=y{3=tKIJiNjE6*DNUMlPI|RhQ~IU-RJ*eeY+NMa?3JtIP$v*Z_@{sQ5jCc zXIJ4#s&iIbpVSS@k+>50q{YpLQSHbYTgPl;q53`~Ci#YW)L@~g(Lq+9^e_J}!Grj+ zoVKr?AI^^e#u|VcZ9P~W#PAlo~LHOd0hPT(xFxTN?vS0S;?L2S2cB?j!d|O z#F4@mPwR1p(EW5Wn+dm=kcbC_=+$YM5+<%rw|k{6V68^tjeasqIo_W^3kA-g0l4!D z9B!Yqx^IxfCDu_S&H)Q_^qas)nyatNha0t^+5vG$b*WFX_8}XS zcH6l%t;cCHqcpe|sb6f>*LAz=fx#wvsgnbtCG;jNxK~FG`59^v8!`*7759B2Fl#tq zdsEkp$5q0-HM6K0KH;M^>+lU>!ZUwY5Jr8Q(Edy^E*5S-GY=bt8Edta!Y}-7?Hb%9 z^sF5p`o2%O)7H=@#d?K2yLrSd*$vaLV8{i|q0CQiV()(LNCYVOkoZ?YuxsHaN|QaE zs`Lq6b{-c9qa0c)!6%eCOgK{5;utmJn)g3AXt-TqXPZvj6t3AeHBbR?+K#Dk&1OVh zdR$un`?ea}A!|&-?oBvnH@FcN^b@RX7Z%i2Csc!e&@X)roLz0pKH$udSOpY^Qv6bz z&{?+{?-ORN(_=RBO(6-YG z220_$bz1u-J{GKf^E#uO$<1WANi|w?8NW+3kZt6ODVXJU+Dx#&U_c?tXQ{GBI2McRxqJV;gsQ3iLAsyeqyus`6xlrH5**bv1wad4*rxlW2|l>JN|QUo4_j-h^$XvW3%8xQq11=#H-Pg5={DAhQlVQD zh;Bsfz3~eQVs4h{p>Yov+YaQSDiuxmpCu=h`8+)`N?>` z22|%^)*05MCuR2xTi^%OO4>XQfr6`QJ8hXp5GaCqZ`0pYccX~U`p{VfqUt$J=*I>Z4Fb6Qw zDgU?yI77HmMWlCGda;F+E)ywK+ae27H_fn@`;$v?-e0XlY-iEPOA7@K%eltF%^jEir59395y^SgyObsbZ2O25ysk_Kw5#6=R z_L_NrH>Td~rkFRn8NAE-n@dqj=*Z}M-#U2b9sv(03dx%l`EaKaRN0n>-8Php@7ZnD z+hQ8_fB=Xtlbz8oS^8nlptQ~wTDaS4u@za{z;@g17Ob1^#UBcLH>W4~ykLt1Z`%nx zSk9?!=FP2b@rW}OBJqmwqbwp3N-B7`9xcgKUczy6|dCmHJS() zj<@Y=zz1b%Wj_X$yDTO3k7%&i4A%9wrB>xrvUE>B;nP974lY6v-4_wNaIW(b@Kmsb zLz3>lI2<(IZLh^8mW(JP98`e^;a~lzn%FnK0Ery)nz9mD6PMvkS8Ba>$ zLw-n&^vUT57DaXB!%GkAcQinr6=j`uUVY49)&F&=wau-BiSRf_OWD}M_T z`DAk>LSOHmXoC2c&EP2m2Zc7MJ^>%LCKeR0T`5SXDy^xGCCoj;7iqXvY{UCz?UkWb|vgD9>|9+cTvzbOjuV9w0}MYD-V zcF<(!LBcOxgKMYI$cqok3^>Szgla{M30jxLUs9FWrnI6_56B_4r&TJ@mdtErZJ^XD zoLjW~{BiRk$YIazG*3Twpc{qJd~WkxK9ARTy>9lO>r6PwyKYeC9oF!MuWdhBcbebo zrWK}(p|*4J<%OYEyTKZ6BaS?eTA?!p2RzbPzJ?ST(px@-hh^sS=Nm%1Rp`A|Eqn+%-fysdRQtO zC`ytZ7}!GmF~Z&lb7n|4T}dqkk5Wu$SeKFkfR_t~uSdWDjGwwKpnAh}yv1z2BBKbIg&KJBd%*Hlh#*0}I)B085U7?19 z#4kz0^Dhp^lZCflEaxhGx}aSTnbtH9?Lw))x_!W}$Zo=q_$3plNVZLPVKy}80bznL24@OOglP{2 zuk@RMD?2_BoOJ)`oD2WoI`Mm^TjA3hwEBBCNPd2GO!0$dF zGfUCS190z_Nm6#goi-lt1l9LluFfw_l7;9U52han4w!9H!1rB1&kaVmD?Y-6Nz#L# zpw@zC$uc5)x?h?nytHHd&>x#W@UY>J-C+KK(nC6tA-)rd%Y@52;_yO2+M&hMgt(Uz zutgaAa(dD$|A7_LLRhfBJ!gMGGLSoLy={RJKwrn)wpckoLtHu~1xn%;nY zRL^G~@JfZtvEe?duiz#X3(t312Rp%)XoXUrpiM_%|Dm`epdsjXJmRCS8d9D(RgdG{YcIAlD&=X4bs};HtVs zg;c)jrqc9t0vb7@;erY2&)z_mY*@$Q#x3TMizo{m^MrrBl5F=nHpEv$cbI#PM_FA? zfV=;)n`#dHK!%SpOyYLO8{Od;23!n79l#^G@CLusqw>c@nQr2OA%0q{H?uHgjEPed zb*>%^PTx2zdoP9nSewz1XMhNwjzg#!3;S8~k4IgC;`>@oR!ZVEsd22$WBGD=at+ z))TnLA=W$U0Ts_W4tglIx^QqXUNK~FFa^jzWZ(rDjGc@dkeB!9xfhBaxk%+#7n*Le zrhR^D#~a;4@EhhY`M3E8&(CnqYd8w$S2g5epGwlfKs=^o3t($G8aaqpm}I)cM5b8l zqkCR5VauO5J35Gkabe+>n@S6GedjeZug1>n-GcJ4BzxXtwejPZVKT-rpVHP zKG<|>MseV-n$DxDAXzU{?p9 zbnsz1U9TFRK|1*N=jwF5j$jT99bDGQr_9J#uaFgq`S6h~Y#r<%=L9)wKLJezDbf5_ zN%RRMetQBAUcDWzV?@*zN2cv)t>^`VIN-sOG{ity;E)b2sO-ogjKor?kONN7cU0@Xu2(5s|9QR&U)_KqL4faH!FLr1W|0~_q%Rkn;%yACEB~w~Oc@=XTwi57 zWghXg!TEarrc-7Gd|xL#RpCduRkjgN7u=%h-Db{dzJ(!9f|xufItzl&Z0nrVg-Kz2 zp)hK9krpVY65W1L?UX^=KsrsMoKza)gpRdTi41YfdTv;=w+lYd2>HROrb2*TQX)`bl|HExomHsiuBXPI)eT7|xMT-?qolx7W_t zLkU({n&KY~RZD~aydQIShyj$#eC&?&aeqent7fwcrI6es{UhOM&0Ks(I@F(9g2Zsp zuB1TB`t@K#9O6n91C*|Ow>ji5uHV4;sO%twghm!w-Z$sBX7V9GcwVStZJrPN$b0>y z$&LLH3sj8aHRtM0lz`Z(b@thWtRCl2+qU*pVccf`R_T(Aq zu$F;)3wNZFeo`6fc2|?T3#5#?3p?@OuvD;a?%ii5ZSe4k=^*d&wXo;acmuq~N#F+a zTZl=~@9rh~8yGAGa~yn4$Az>3=^}{Nk`yirU9V=uQT#4jojIff-$qe&X2nHCNuBK_ z_{60~(C^jbb3*anRJaN7*xuyv%^=+|K{@a3z<~56+$YEf{Y^CE133_6J+LEJ!PipW z1}H@k>MZ!&4@k#^(|e!5HNu3~mSdA}=(VSSM@W7BJN&B9^ZHwG^SVo`D0j)>SrmMe zG6udj5k850e{TSA%pjj4O&8GKk=k2?PxfVk`R~TQEhVvK`Ar<$xt(TH*mjxYovuf= zfO7%Xr=_&@tV5w%#!shUKTYp2(;kWjcaut`Q5&Hmy?;tFOup9z3i{?RDgAuVu z;rRmy^Kucp5uV4wedz}tTl^RTj)B0DUk*aTf;an*THjJ*O=VS{dCK3iM`w>6ZTw5l z*zB=mvlr$r&O<`&+bQ;l1&ED;Fjx{K zHfH6@rwS}nQx`$k4?GG6@}-EK_E*G~L%jSE#8yKHgD?U@GK4)~>55xESicxd3(#jY zsvAt8Nl-`zp%+r$nVkK{D)9Y*Kyt3!jZ;^QNnHV5-B^d%XX_Aq+A&!E4W!=@UVdjT r-X?h7nT&rHvJV!6rthhPdc0HEdoVfTBCLSP&{8FE{nv!A4(9%UUk1z6 delta 21988 zcma&O30PCd7C1h0?@e-9BmqRiB4hz&)c{&?t095Q5-o0RUD_H&`>wSi7ksQ-DOHXkHnCEBu@4radCf3 zZ~2QYy=z{KDvRdzBBrCQ^Mdg_>z_GDq z5JD-^JBVc>T4>pFJf7F}*=;&gpFKC;dS4mdgX>TR>V4gg>rtk$cfWmZ*}PKd zw6C&4FDhxX$U^5~@Z42l7L9b+pXok(MVOTUR|#c|P)7JqTCkceg=J||>z0|z;w#K$ zbrsYtlpDX?RMxR9o;Qg{=Gx+|@%$b<&=$|D;C}*)az7eqn+ma6ltW{aEl{w}XbP5N z2HNf_4drVgo(Qo?q^MBqgkTCo3R;4k9E(mDZ#6(Yov5HpB2AIHl$cMcGkmVhlB_Zs z24S3M?nCov8-cvfxDFoHMO(*M;&^ReS3yCaeNLP;nASo%C(atlYejf3+UG=CF_bYz z7WAP=Oy2hyb0VPwooJjJZ>5e`7RU3u=^3{kJcjG=l=*H{NG&M&Sc}vUCqhVr5M?x? zsT8dkPuVc8VOvmm3AI2Cfq~Em1+o~l0BO)%6{P1wSO8%*1hz5Rg0)CPkcVMhiDi)x zR1o6$P-9}LNmRkx1b7>qUBH9-VI)2&1-xuvR1l{KCXcM5k$|6g>%7Ghn`MR&Sr%o9 zVzMoJf0A%?8J52hx-E`)k9t-pHEw9E`^BcO;gb zDs|w=H{2-W52v}$zD`~iZN>U-H_CQ9_3%u=^Dl10-z$p&kP_jjJW($%B`eatF3gIw zj3v%~zF{jg81Np20stw4QVfD4J62#6J4*xC|J*Wi3j)+Y^E}LZUi5#q5@~ogY>$yQ zP}ii!&{^SJCLh+6$fa9xEfRaBbRO?RqDeTf&}vBSL$`i>OfMSEpGxoNkhUrTv80U& z(1tLQJ!u@w@EqMi(W z*+(jvCZ-E@*?&eET`Y_QHb0w4;$Kl$IAG+Z5X3Hp5Z!3kWhAUNMZ?AL$A8Ehl#q%uOC@l8MI*fmJh3xgqg zCUE`JJts7wY1DKlbkGHXZN%aRKL%(S32WF!BqE9YPxk|&MD`TYK&)jsEUHg4;@)Ol zg2f6UW<;`$7H<#IdbMs+ss0HAH_0-o{IhGaJh}ezR$9y-npmpg?zYmR$De1x@A6#U zJ&9IIpIM2;Sl`8K2-9M3KcmmH=J7bQ=%RtQBU)sA85T9XVXT^xH*81@^&jSwN;>%^ zRxCa;kO1TC^~J+~BD|LgCq_iuR6~iDFb5JR_!A&ji0K3I!RIXjEFSI0VvS!WUXmDn zNJ(ZTsV4&nfO1RnV0=u%;>3XgcOJhOHMmiW8jyby!d1XwK{#Snkp2w9w-Am)Xoc`T zgoV+FwQNVMEG?1D5=sep7X@UN^1l3K%e81P10Y_IG#quDOf^tzc7m`vB3ZU_1Y!$? z-4SDPz0ee)rwSs3e@EO+q9mn;b`F&b1+pMJD+vTjCHd#g~U$C(p+GfVhHHQIJaVv;(8HEsO__U5bNv#6yY3bEPOyyXlR!F_iP z>Hp}Bd=}~Lx<7hVTOa#q3oPiZy{ei^5_$td^?9yCLbH*kT|z26F&}o|KGTR!72gVz zntUVnJ$FIyQ;A%(=PFo11RVl5Vz z`2yZAhGJnY(qcaR;n@5;=lY{;;b`S95o@IllN@HSlrz&=gPacg`l)TC+Z0aeb>W=oZy)0tr9wD z1Ta7LGn}KafWs4J!;|2jUwEM?!G$zs5)*!!KgZu^9R}Wb6UW^v0p~C>&FQ4Y!+vad zYL&e3HPfhbc*0DfIVv`#)^F$VehtTZFiVRo{Dp;1_Zo2#YJ>kUbk6;kLx>fU64f*o z7YNbO=8@kHU_*`R4;R)*ZVYRK7IDAuNOa=8brRVJsz$YzfkoCUX&i_7PM)?RjjEZn z<#$&$!m#>YsH8-3h~a8sPoD70l9&!yO5(qU(zwcI#*>0hTIJ$ozlKApwD_aY89ie} z96ZtDIkM!$w}r7Ili6*juR>q2EAAO-8c_lJDByiRK(bc}2S$#@CgIG;0-PfZj!cgU zAAIytvcA#auV%(b?@eh6c%y`=F>&}_;ocZM?iDu1OdW9`z;tQ26yD>e#5aUbV$$(4 zp(iE>zbA|y6}$L$K+}XLXtKO6I0`0cxcuh)MutP4nX)wK^Pa%$CdM;Am@WzAH$j=) z&#pyk@|%%(dH{|>@oxj7d$@)wSZZP*tw{~-P@+M2ag-LH5*(wlW8Mf@9htm_yS!o* zuYVZn4=)F{Q0N^sC!}pi(=@+?5?#Wq*i1$J&~{krX9Ul~v6GD@w;L$&-JxgT4N7Zs zsWg;$eE_8$c49rf?mKtDd)A*`br2}SdA}TXR+iJqmz+T2zlDFsnn&IM^)ylzld-+AXmZyhv1Z(9FBcV%(ly3C?#OymRJ zfA|OtQT@$VRmOnVd73OEwvn=6O##oPji@`#F>;U3wk^$^u|vbF#&d*!GU#1ONpt%q=aNc#F-QW z64#zadPO6};aaR!1HGL(035hpuEiQT92-cF>*QJr(&Gn&XA+)F_=}Ix1K+__Y(wHK z-!S0$%?d3NhlGU0(fD&=a$+`)7ygpC8b2YlCFa=f_Q|*s2l7}ISsT(g^~4+)$k+a3 zCa=p1Q$60ta0^JTj2atz&)5wbPCbE?X!5@WC5%ua=}rlw42@OYGj^SZQw2*L`A>-v z|0zL@W&fwdE2M<5ee}eoPx=XmM-D1=C`tkJmd9}Sl_jTbKYmU^#}z>KJ0~n>|N$zn5yf+3>+6~tg_hfDXY~7!PxTJ}; zOM^0QdlSlXIyGFVM}=W?z`hT7_XqyrM!MmW-wobyUvGi~W|v(@4x0ZxV8*}($%biK z;@j0rxG1~sl2mgX?|HyMTGMc2*Hhx4Z-sRof7p70zifTgJsa@zP(Q3|j&Y{hlZ z;Ev%FYX_WI$TOSLa0|JS6TZ7f=_&D&kE)~V_nP`#!|NF;ZKVWU54CC@`-pT|1E~do z{%#*t&v3(~S_EbC)WQOP3V#!5zzE>fjE*7il|ahMkq-T)_e`{F$omJ-uKeZ{{+2s% zJqmV30&jLi!f@X6bv3C<$iAS&w@wS1#8J_Tl3!uNzw9G30z?Ex&>{RSIgh%}CtQy) z;MaxGn$kFv4{5B{KbM!9OW?1$K`aro1e+#Do9*+t`+$9sSty&Tah{Z`VgTlRAJXfe zAd}oDxHOCBRQa%mK5l4MLcPa)aFRr?VYuoFkXuf$*U4i9VXTI6zoe;kuq3_ub!73*mVQ9q_^t5;+U+9?#3gN&R>~>`GW7(}qR> zubbeIiv|6HE``I@!pf9|REbacEG0Lj%HMpIHDd9&5J-u^{}5tQr&6*ZVQ%U;1`h9j zVO#254D4J<_&D`0s@f*pPCW=2llq0aF?RvLt}$ane$d5n8tahvf`G@4$Dar}WA)Ta zV@}*RHk^`$Fd^Z6LPh#2sFW-T=h6$qC^13mT9F2jT@6-9DnE{D7$ zPvjQ@pHnB%(&>!2J(Q_V6!|f z1{lqgFkh`gT-Fnj6HY{P%kjwa-xiKzVt)9LjuPI;%AU%W(jFCs_2Il=)SJVsVzZXh zb3ek8Kw+#ANxgwYmNj-Y)=KKu=zGe$XT~-!%w%GJc#l>IBeHYul9g>WBF(TM+trLh zNS(X^Qpd6}bmLc5rfyni-b^^VPC0H1ct2|icwcA{)@RQzc~(8N=_`jkUDpn$pAUO- zj4lUGeV+^W$$H~VuW>5pnC=MquMI=%$@WRquQKZ#);x8g*qp;%bJMr>tOK5Aq9R*R zjpJ-;zO{D*k!)I6=$qcOw6}n!*ArO>HopD;$>1u0m7VO+ixlAaZ1BJ%WzFz>8^+E+ z8*HOd)F8PnLH~N8>I<%Ctb|1Gn+DzmV;rASQlKLLD#oS%Eu4hisW@fWYq-D!7&OW?Q;fk7-%?l%Q zGsfc{J45{>Hsh4<-6=daBwG6bttzrSAP}ge#)y>)E}VO)DQxq2;rZOj_dA*^Hh&Pm zruUg>lwI+7=*7!5@0k=ojdJB}>{QTg6`P5!tKxC(X0@dZpIgwAxTm3^=dhCPh$+K* z6~D_!!+5@OkLGT;^LAu#Il!C66$ZS25wv;wQ6IKfY+fXP?}t+W1%W^fVFD|h9zR7m zI6hHc*(d{0gtYM~RQjNB&-i#8F034HPy{!DDoj|Ew}=}YGH|`XqP-aC25wu4fK_Zk zXh(nv>dVk$MCTQy7-%CXB`D8tG;fAuMLwmC-aMgnFHF$)GAsFQYdv z#8i(tTFu*`+O7p;@$H(e*=)zK!3TlY+l)be*<#dpQ=t1>Bd&&HG2rdF!$Be7SV?2H zfcKpMwK=*pR5KUPTcGblpq;2S&zn8yjq>R?N0d?8#W<{F|LjAz3LYaW6MIFpRkxYu zDL7}bZfCH0+WN&E#IS%EvU|zyX9)$+sepNoL3AcSf{O9=>O(QXDUPc#9+)h{nYnm@ZGbI8IRl5>l6K+t5`OmpYt_=kYELx`R@ z-S*PJu!;)SytgeNxmAtSN`})lnKv)%-9np5T`eJr6`R+-8H# z{Bql^d=3P}g9P0WAHsJ9yb*&kPZce@_38$N=QE@)BzdWYtVhExs!E)s6K7J3Dg$2s zz^aXkae8qky=rX-Xqkv$fwUt_;z84dqZV1i^wFSA1O3vpxzfmK`o5tG6U0WHe&?{l zm!b7rD7{VpSit+E-w1o3Eg>8}@VvzVZw_FLV2g~-5P?$EkRA!457K1Hvaj_Pqg#76 zFx(oE!{jVGIly?Vh&g zy6Ji4-O-?{HO|v-kvSPpOmNv5{e@kJH}91ayY@=4tz$PY-Tceunca%91>LlEuQaOG z)E%Ky`ks}-8kD{*LrtD=Wm>!PCKI|yN*8xbMC`)55c@jBjyv(ZNr-*vPB;MZ83>V( zZzF&2K-ep(S`$S^DFdY!?HVQ8mB^WVLcfV9Q}yfhn>rPv+V)CShBR&uY_3HMOnoS7 z(QGmzvc|}W0^V1K{wyEx?gsw;P3a-SupUG%Cd=`-949qygcFTB??UM=*SEbW`rE`_ zWB40S%zdZ5I6QWzQ zNd*AE=0q84>92;&t3L3xLHQe-+Ab=6_^6stZf16Gl za=9NqgU8b@qo_if^CZb2BGH3LSI;MwHldN2GcX)KPRb$cZj5huqbUPTd$6MCvw`_Lz zLJQQfrYqV_<G7} z#n#o2(rkT~Kh*711Ej2l1`0T`#oR}M)xZwjv|Smd;=qa;{bC^Cg+O##yGoz4g!2jf zt}?otL5W7H8-bAmv}N{GI->1a%d=&p`6xcdm>q5u-?f9hs@+zW5RNi!MzP*rK`Yxf zTWoiVe9(ZhjbcbODYU7qz5xt0;xBfTrRvyNhP4}KMe}LgFlia|cJyE6H4ciOyE4>~ z&eaxcWua|rOTP?~n}n6LV;|^SSC{4~V&@g=U$dqZPTcA@hjOX3*0pS^28_oFmnEgEkW%c@_NroC|*5N{NX z)jvvEYoCHi5@{6xnO|+p&g2xH(dbBvQJ?JF>PNytpa;kOsQzkv!26~DW!U+Y?h&A# z&p_&_P47syhmI4f{?vNXhz3OIe5ml@V4|M(v-|czAwp_vAimp@XhLF9b-+7z5P`r! zbZ+em+@|6qt&3Sr?jkoDb4hBoUy|An0(m|DhhkD&c{dlgP+}`Vk!VOZN{WOwtRE!? zP^rWk>ZM3Sri->gx7JLhYb;Q_p9kupqiB)A3K!6GA1SgFfZGLelY(la^rYexMOYij z`4eCwnBF(Y2J=?4au1e&;)-<-FWk#6G7xl}Y`1{dG0^G0q(E)M0FQK!1UAkF?2j>Y z;J8G{Dmneg$w$cQpCnfU`AB6)gxnIcTP|9|%08u_RfszDx?S86L7=e|V0X zTeQiVLpD^o3)F7Z?2HJ&!Ajr#7D3vmi2|I+;aTRJXITUct|DsD`nXLs@~E~;(#%iR z^cF?dZTbncos_7ISkp^`+O!fGyCYQJ!n?Tjb?c`9_E^%L!7o>|nMzPk7;qX>d@8+- zyvzs264zUrQ2o>r0$sj^6iBiLyy-rBu-a;t=pDm6iD6q^o321N6qWG<02JqQxyg}p zz~{b_zhkIoDt}kJy6{8Ok(O~>vhNwG0P@!PjwA%U&-o_rs409$V(pz*be6?;7OlB_22 zlumLVW^A`)AF7~*L$~`VeP00VrwW?zi=Rq;`R62Q5}_NPLQKe4B^++8^P;UizfFLt zR6&R$$7)dCfjJ+ZcOhfCCS=(V2K7(CyHA)mJss~Bo}QjPI%x=L$zXX2X|7s{WJ36C z(m-Wnn(&Y58e0m|CWE3c;4PIlXtEv~@OlTeoQ~T7l0%^s(8raP_t~vLJ##;mx^kke zpGqiKll%WKCOk!`CDHnT^?_wSS?geK^1#wqB(2)CyqBg|ttW~>TV*qWh75y@O={d5 zG|ZyMOrkx=q|O1eZ*9qt_fY?f@c(-7|JD8%%HfO*yZ|m3#4BmD( zS25Eh8mSB`4Fw|yrt&Bgcj9SY7Y6gx1D0I=9FQzLl?ZbvWx$ID7Qm?Oxg&$dzE7ol z%W?_FDz?(m)=Ut?(LBP@X2LmgQYt4Ut%=sdw^}RW`NKDVTBqx4oqJaLY3z9j#PogE z1_@BWfVq>pwTD_{EzLbEb!o`|ufhMT!T;;Qe=+#qry26j2@H8F0+WMWV?di|74yu} z^_gbrTL@RPCX|__UuUX$O&&@+*-|b7HPV*C1e5|j*HFNFvwwqz zpmo6e7SZH@O*ia)7KK9y{V)U>-b5@}T_YhLk&jrgsTo-ae+t9!$_U2KM~o<9c=>g~ zG9){z3j(3CgxoR^2(?w^hoddWk-q5W(xpg1bz4mMJTd2E0oUy`(HBr1&P97}y1}fU zi}&=oLpjXRCB&9FSE9hKNX+9ih3N(3@mgVZ!4vAp!t%aDkEyxJ#&6@1b~H!dI`lZ$ z;{C!v!Gvk`O@Zqw%OucY%ea{i{4NsT?+4p*+7B&AGpsvf#8><%EgURnjQEicrNNpZ zick^t3y+%A$$y-#EGCMre2^7cJ{-13jATlb^&pk3hl<*I;;<5xVi$fE=o9TgjZz@rU`Nri}By@PhR)FZj%3$|nRWcy@r7Xy?nSi~S4#GuMz<;mnm`Fr4Ykbrm70wX>w zL~^5XyD*+h$KL?!FxAp3J-Twh@%ze?CWVU_XZ|H!U%7JS@^}JS<|D6~#<=cE$mO&g z4;J@A&=rs9cuC@b4X5bs5Ch9G#PG{aq~>Yi5;w#44VZwCSS6)%xQ;#ocBOt9s6&wW z0vJa_K#9pV4tm$X1kfD;@AE^5H=0;5;b0vYakN>`9uC05o{02}$ADH;e0HrU4~a&J z@oYk$N%q-DoC4`DA^q*_=BxQeB<7wX=A0}8&|grSekL3!9=~c3PBoZf=%E;FS->6* zTmn&(0XS&!cc3l4PE|7_PCNy8)Ix80SjQT0wHYYx2SdY@hc&{<_%YjD3AGsUx+LQ+ zgK;zpBqmmFfL6W<&`AntKUNrDqJQ8!Nxu_kMz{#nEYfcwZC5R7%1#P-Z_olY#DWgcgQzY7XZKpw$L#awW}$ zbVW-z9NY%NP@2cJARgzdn!`AFmr2^W?WVbSC?8pc(tR#fd}T3Jh$qvWs!=d0oX|r# zEny1+yPIG_E>_h{9{b(GqSCvU%?EnXy0Wr3xe<2TyR`ThK;ru?)IMU>c~D~fAgvdK z&eZXyrqEfT_k@9Lo@H+YxUgPt1tzolUWu7{#&qkvxv2NtzG9ENRf$qWaIYc(0l^X9 z5qzbIHdrC47bWX)0VH_B9wSk)?X)LV$vSZ!CFuD%Fu!=>1#Vw)*3W{357s4;TxyTU ziN=QN?&eN$r#v&1miE)0OyzXvNQgDcsm{|Lz4C77QICP{YzWCLZ&!mCS5yn-S4=7q z?JVV&-=*j}?a5ZA+n}gH+3hM3F-z40-rl1G0>%%nqn;uVp{m+LJ(|#xKD1zoZ>Ntm z!?wuBp7yLz_BR;Copzj4(q}LEssZVCb(M$|TOu-Shr2{%*?+;miv7WT>K3w{K7ZQt zq%s@&TCdE2|3{Q5uCzWopX{^MNF{w5{uB3UPli(EA{{IS#8FOt_vI%(0-Me|Ed=5u z?jci&Si^n*<;E%7gXN6kx~0T9D4QPmdrQO^n(d(DN@o(h;Xbw9ylfP% z?z0USCCzaxEVbY|bvLbycSUpTyG&kKA>JS7fb|n+NKbbrco=17r%;sMaRyo-IG{Rl zeSJ|%N0o^>)k&LglRSoQBXo=l7`JYhQ7ayuT4QHvqU z1Xmt6vJ3AoN&2J#@BZ42>z5?`+l|Kl8t?BQAk}fS5b@sP!sw|o;k}+v8rN+! z38rZ+UwaTOt0UF3S`7O04?L2%vxwQF<5N25{Q)z*4^KX2YHv|;1T=+nW1`G84nV^M zv;(;QOi`%ofRw74m=WJDgOn`=gd`O#r5wGE2OALV_1faQ+$2?7eA*M3A#=T#NE%>( z7VLv2n%p`1Ywr1PA$BH&*$_}`AOKCOG+a)4QVW@Jy{Mv}Co$AO1Rh}>uv?bEq}pKZ7HL;#_Z5?wVmfmHrW8Y`d|cZ%9u$_X9iDfC_KYV)Ip(L~ zCp{nLF<<~`;=baaui!cY^xUGIEfGfz+PQ_H9voWJ5+y|^5{j{}_#eSZ!Y(}Vb2kBi zf?BQaOs&g}bKdjVLc_jlaJnyWcj~sTw?W8@i@fJQ zHoe`WpeM9|a~^jVrXs%u>0=6$3SmXFpB7=)^um2t2$=D(x?%L=`keUgo3P23E7?9x z1qFL)rSb{aiCdaAOI@%nZ6Rb&_FttiN&~X7cr7%UDXPNc9Y&J{o|pC%;AGz}e*)}t z#+lqSyBpI;JZlGF*-*U+j=9PG2YXl+L}ZDS`A%Z&NNluc0=iEXB?AWRHy!rEn<~oR z5Y|mmD$opOijkotCmtp~5|}!B#8FdWloXd`$S{fr1W$Ri?R|T^h(VEf!eqbsx!oJz z+fZD1xJMQSwrBsot_whRkd5F<4Q@P_*VYkwxaJinyj>ICqHb8w@JVc~n~X7@jPXB1 zOcUi{r#%alWI!C84r}O+hLDWX_K?it_Dff3arPJvez6>9n?yPY^DrTuAcPi=`Rki5_oC_dBw)8YjcxXOx2R*GEC3*6~FfztN+Str^R9tqL~q3+bAU2by@%84sjf=E1@IOsz%>jW1ERWNW(tAkrP79{Y;FcEjS% zi#V#`=K8kYT;kg*>G>!SjrJAWKK~Q)8T*Q}e@o+(LA_P>HK{zh4{cO%HQXpJu|*FK z$*`|O61j`9`QZ4a<1&G-d%Qm+<1}{`+`($Nke>{>?-j{`9b#J!6M%1G7kwPnQHVx+KPZnSNbYYnJx%%clMiV2A~XuejzYzp}a zrJjjHIs><8?X;F`kzaG(6$80Pt1<)i*pD6&kq`}pszPrZJlaMj7*xu=5f zFBXan^KbX-HwvCQ`TIYDWgl!am9lzeD%QMyXNq{H}o9FP`!UgL5+@b1ihw z7qoB#J!SY^5%&6xOkwi8gb{CortZz-bFQnx81bgCbYAp`7cb7`7ISD{DUAPXp?Y5I z-5*O^xLw>8cg&skq3u!Q2af;Fg{>&WQ`yNUfYx4j9R{1yv0h{s zob!xWFGSAQmVYFnG_eCrXJBjvKb%5U<4#jFhh6G;RdZq$hRfkwburjq^lh_-744(rTxTb=^p51L^zs=9V4-41kYokjcr?2BXcOf?g1eQvkxTuZ3H+jr7U++pwVeiu4gF=7-dQAwB z9-$3`s@c4<*Aeh`OTw~yvqEo5U2d}RewT!O_fA=u1s-;!lp0odkK42|*Ks@uAJvAn zL*5_ZEsQiByO5Z11_$GvXDW+{cs4WW>43y9&*V2MXE9txRg^fW3~_y`P_!YjRLH(B z88->D?n|Klkc3C>%bix)7&21^D@s>IWsnBP`}I{gQ|2O0pUqb*LDG5o3{ggX4$QHt zF>0nBq=h6WaW9um6^8B`^>AoEBesLW2#l8EFA^iZ4T2aW#(}FI5kMI6$EKiV4pHF7 zO|i$}3PX4q(yJOra&slUO6ws1c(RH7=P}?QB)23~4!>JM90%|g}v ziMC6UYU}gIQR?Y?6x=0=JzN7$m&{8ic?RS@Le`ISO2^j{sysn79(R2$v9tGcqbo5q zv#5WpgXoG;CK5BZAPu-m2V}J}U?pyXK+cF$`epUnsjAGY?f4J?B%+pu3lO^o!oMI~ zx<43f!NjVC!!JS>A@*|!%EgFX1)&MTE(oNs{sF{}hjJ8jln25X66q~WJrThfVM$kc z-;T5o!*Nf~XhjHjAUV$#sf8`YPtLXEJ9$dQQAR)hXJE4pDIC89eq6_g7T8F7QeXce`JBLOcJ$ja_>{pKc3_kmD^#LudkdRnAu8d&6y ztFa!XQkorr4@UeLrYs#~WCq+{7*2I2_#QFhr&2qp#1EU2+L?Nk0)~BhhYeh983E90 z#Bg#XG=YA(E}<&AvfySEO=%TJ(AW>8L=dIV4soEm#Q>68ItR;|5z{1WFpBq9GZTJr z=K@fBhsfBUtd0TQmQj4XIx`MBQ|&ULo0Zj|)v%$Pk5*p-_tAyiQPW7*mr!Fj3>&@b7**Fd_R|4MDAp)I> z?zuu-WuFTuYR|gKHuwy7ROQ=qDxUv1@o^$J`zvasd_c^wA2<@$SG=xBI4IUrThQdRCBPY z!~dU6oeef6KvQ)Jqxhno%|th!vy*0b{-@QZK{7BSZM#Ai+EJ+SB)Ax-1^!%yws(UC z?DU#ofjTJgh*RtA;1qrXjBzoP6ek*VV7E zCf386>4LZl)(j|JW@>mWa>D2bwfI3{#)B~<&h%s52#*45;2?TNSo)yWcC?9o~fH2;LUlnkcQXE;HN@!%+A26F`Xvh~wR(VbDVR&tpD=_}yU z2>Liq-*;-ASv1g;FyuWy_z39F(m+S|ywAX~fT&7<_R*&DzMm(^W_7}T{CPrqA{^NS zcmnt)0OWCq{{;LCVe~^?^2jyn&#kKvL#mYasa`oj>+Oi*{x;%MRX zhqNOe_y6p+fNQTBMtxi8eP~jGZrCMCU*6aG7*$Gv10sJKwLAx%R0~B*>cJE6=OyKM zp^#%WV9%6i_acjg@H-k2HK|jNA?vHDB}BtTv=XHG3fmvKpd7CPZqcpet##e4!Rg3T|UQn66KNHp!XASPBef&&Y<`2cgiF| znU4ZUn-48t9za^+Jbh_E4?MvzmH~zWEY4_oU)a4O8DA0{@c+*ft`#!M_HE#BRi=Ze zBoonLxXANa;C2HsAyqaL4I$FTgGaSYB0wdARS`)TQW}Ise}JU2Aay$c$VOO8_y;Wh z(NfvC74++53e=zk#p3n=VNv84K(Sd#o`nGLL*T)4c$J3J3itB!45~)+%4nDb%8B%X z3D_ENo7~2uEau|3571e(GadrY^SDDn7q8HOPWwmxE<9HlvGOVWg0N#{QR2^oM5K^A z3%G-@&ZfXg0VdKw(9NS-xV|zm66wRLjcZEzvo+t?X+B}4T2MSvfQ>@wBl;1wACt>a zc0S&|2RhfRz;K zbuT>M5C!Q>m;QwWh~+LQslqlLh+C79xJrs~kYNoC94$&}FM-LQH;@BLjevJN5a+Ml zzda8JS}V?3wko@Ul4Py%4LI+Y?ez_$yWtMLcONb4X^-dr3BGZo3nx~u5ffwpq9N0v z=j3HyYK<^AZ9~KNc!rlPxVXvWH{9bN1$DBx&XDn2&`D)k;7>p0z0!RKJarrV--4SZ z1ePC$L~xIr(<0c{Wl#e{!u#uzbk~PSPFmo1xKeoCWd^o}Y=woud0ZOW2I%_5E&Mwz zUa+oH*<^t~9lz|-gDN5fh;T`1`*Gs9Z68Ak=#B?DS)k;Kl2fXzB_}TZa+4%CSTplm zta>c`AU$U%>mkG0E-_XE54CsF#OZtcu+#T;;wr8^Dd}2YY&i6s()ZjzRKs4lj?;pSCsWsjcb+@+$c%<_51Qs5dhTTZm`a=* z)$oex&^G+jn^MYgob!d7@jM6nGS9zPx>u9Km2h~R1$*o$p>l(q8T4NF2~TcFoU^2*vbn&~y2|w2*5`)F7Ip@_^IIy5 z^I@+&u+n%lByT@BWpvx4elp%v1k-QZ9k)!tf_-Kup5XgUSx(2TYTE+m8c{8KN+@3& zGes49=wXz)8tel|{LMaJdT2(p^>B?~KfF;`dlRmM!aX$mUTJ{=tmMEI!i<4UFy9#P z{cQ4vvb-N z7T&0R)yl&jO&Sm$eKZR{CG3B67S-h!u0EPZed8CRR*#|fOTv`Zxk>Joh`q21v2Cjn zI|*o5499}aVkLk_u6GMNSC7LV3Qeo4ZNK*aEhxpU96I3!JDBXan^YsGh?3hQF|Bhp zzPxc}H_mcxbb`0S9*M5yy78FWs>mv1cgVPQscLqlXl0bX7lv%Ed7uG*p-(CzcEi)F|)}-DaSaQJhUeed`&#aNB?x=^i3{!GT_WASG#o3@M;kS1oG9Q zwJwyk#zpG=JP7$Jl1c`0`;ogky&_lxWiI*O8uNO7kl)_ik;<~vDMD;K`I#@bGQcP+Gj zz{?LZTz(T=W>d%=6Ri1n)IR2$GtF@pQ zTI#*;Lz+C3__eDvD(^Fylggfh6!9Ts^`A-BgDUMdX}O`iZ`8VN5`B>AVM8mPVQ%eQ zXM^o>oaZVkOt-r#E^lLQEnatcnac9nwTKBy%T9@@Ed+`(l?w`I;)4T(PaE=%2`GYh z>$123FEjYIdp0*8QWt#+?jW#a-vWo!2jM3OhQ{s3xAS3TD(y?s{RReV!>KpGgWBU= zAhuAa)F%T|sLxwGkOq(c9*}`al{8S<7|t@*@;PZ=sITN?z`6C)>u%=*0QIAU6Df&$^b*-O2nc)2L@>fN zKuCj-4FQ!@7SBF0>xp{2-~-StsG3%3ch`zp-^=<5;eY29u*iR$eRK06aL?bimCjf zly&av`gHS&)FenT?nTC-t_NjE+fcLLpR0ae5Aeoj4{l9`%31sa6+~fsT zdB8h*V3<`VxIy9rr-0cPJBO4OhFips=4!!+oWv15Ruc$PijD!VYyk00+AZgEX}wOP zDZdHpAGKyy(_Qg9z?zyHUrm%gHNdSCtS7by0s1ll=PR3^8;?ob}bYbdd zE%la9cxdw`><~IPPYONalkejl1KtKnNVJ*Y&dU;80)AY0%BF=oEC+1ql-MtPY2)w= zL21`gXZnR)yAh8N*4fA6XM}ot0>;AM?6dGMf~-0nj}gXK#{xH3T)i~mK~UiNy*zMn zmCXm?#6aSFSVAbp4{E%#)lcEqgc)1(faZ!V#hIrAymds$7uP5m_z-|9i^u`t8o&4V zA)1@*z_lnvW~M_i0|5~gDS@wF~ z24LSkbjf`|Qs?wI60NhjuOxK=Tpoup4A{Jv`r*nfO|CRQY^_+TU-qU{X#eb*TpzCA z296T1J5cI0D+qH$hJE%cX=K4A_skT=FW+mJ@C$4 zJmvjNQdB2>6z?aln|BQ`Ng@^#+q60iPe}!El156P=mVmbj zDuVP1BUlAGCDPEJ7iMRJ%JXOtFNb&Fyu(oQAO1AB_$K50a5aw9t%tgyP#09J(BT^` zkMIJN6rf~7uoWUid0v3d~w&`)I@YS{i z$~7ol**05oq?v4rRl@Y`Ga?HHLI0&87v1D=^|jwSS$KYXj%{uL>B0N<3AjRHS?^a zp3qy9pNQuwK(n1`oo7vYLUPaJ1OG-Xr|w)}qu`>=K0eDp?sSlT7;X*z5g`BNmH-t=pHbm?_ariXH(yN0I=hf@({>99uT`&3PL0$=3h1)?!ok%Jv8%14}*7GZ@6ToWF1ZOy>A^BBoHu-qM+O<1I={=XrnETIzE*{ zWAKzZtDcW`)PrRiU94;-5M3G2!D^4@=dWcDA&}BaN{TiPwbhcIHHO!-q-&*QZ#({9=}a>&$LJxhu}50Ml2$ zx28Ye2zEs;u08I+MhCkaV@GFG*Fc31tO6m)9cwb$n%>J1ffm!Z}}h06?e!5L(@GnB9KwVgD7_ z@S*ZQ;GdRX53ckXCM7aL=-&zF?ALWu3CSND)T$7lFSbmnVJ&Pae6>Wk$SQe1mgJVn z3Y}6D4_-8^(d(`HI51a%M#9HR;+_M|4#btPNh7$Tq!9UYkW#tdJN8Ueli&NLPu)e`@p3x~y5N)cH^A))2)FNkiGBaxqVRU+ z9NfVI!3VtWrD+iRy_>-~4cd6|eu+tx_k@ONMT|QEqif?k6c&CaanoS$lS1vC3Kl#B z=C`msD7tKg@0lJuZ!CJNCsa1;+!529bJ_6}hcc{A*EP!gsx{p44S(5M3wCTu&Rq!O z>*MDZhFNp1EN=u4w@PaX+;(ORM9ULz{stIVzt`-Odsyb8BMgj^op4pS&Kl+Dl)??? z;X5TqiZToHtP?IA>5<7i>RYq(c$)3cg&puj!5srXGlVOXlfn!l43g7y3YD1DA5EI!x{H9?u^?6sy__g zm}cuaH);8Lzcz@i^>E7+rOg=C_wcdF9O=mG{bO)4WEHqk%3`7Sc{A18B;>zPf?pD< zUr3l}HY1G%?(>nwQQ24ssxXR&J4BY>V%d_*eyT`Orcnci>7pJCtF*&su!1H=aJ{e) z-y>wcn4LOlPyue1DmYF2-sgenSREML^VlOulq9+?onw#qy{W>}FIp&fzwq^oiBx;P zaP`Hx)Q2Fl)y~G-h39KOz??93cTvcO-H0uMuuj;qJ3-bMOuf5%b>wRJqJ__!1C&nX z!2A8)0%7c)r}6W`TYJ(KRp4po_gaLuJ=%ojr;yHgGX|{rOHPT6&+^-k6F<07JQ_bw zh!n=-452`nvjB;C(k1uQl_=BYTnzu;JMmHD&G0$I{*2PjbvDCslV|^)9GvJIcf`pj z8WkVlcfpZt6?$pNdmo%#@=mfu@jl}CJj|N;y#ERazYF)J9|Sg*ZIr>MXF$CT7PB_r z@cwB#gIeZnM=Uu2!(p}xh1Gi}jlaW-Kd|Pgs9G`-EF2#q$-Nsjp#%>(G*I3>iTcQvDyI;DU?0a^I^^f|* z+>On0e}rehDdd7*E%yWrb}_DczsY!WR5f+?)WXH_Z#JCpOCsx66QEGW zY}Ypl0LDE4fP}}K@DB}W!z28Od2n^Cfc1y>?lLJZY*dE>Ak;ZxSGs23#(fokxWVBc z5+nSoNC3Ey^&{zEk>U;z)VYI2ap>j+Fmk-v!!pM1aAS*m7mNpGBhevPUQV{1vTuuD z+CyWk0X$_NaROj7-*N+fXpN7){fZI$D3Jhl!Dukk;m{Sqj}+k_MY;q0uz(-NNA=yo z(KNgGyq(}^r+pYl)qtZQc)?*HKYM2wfTL;a&h4_9)?T3UCl`Jb4;bRA++TP!;j~ZQ zr}KsPCYm+Aa4+`Bd&|2=-lO$}dy>sl2?+hkzHIJrBIv;eL=!u~I(t{NWU--aH<4ka=@frbBW6_x5NgM}S7H$<1=-+*a;+cQx1Kewf?fHgIL`_dQhjA0_+mx7!G?0@cbkZ348kjO|Z%cU}7_SQDNq^CR7Te9V&tH^B&G(l|{wF~ms_ljlTdLGYPv zS(LggDU4e$B-9m+#+KFv!A`Dvl5ra4q|z8CJZq^E366m3x?~(9yiu2|_WSK{#(vTu zhs(Ec(ZoA=S_UOVztCQ%u}y$$F32D?!X4au%)#%p;&s=Z}nhm3Hgwij7x!7 z?$?7kF~XG!HyU)7I#Y=22ACn`?d3~g(V($K=J!qcEm>R$EVEaj%7Ui*9e!`aAZhZ! z!6-`>tnWN%^!`DtjV|$frw>xvD2OKy4$GW>4EnwGgA$kwYbM~apSo*cI%gZv0{d0r z-}O4pAvh&YLZCq`SYW0t8qsDX^WF~YlJHo9=G9Rv#x;{i!fFxw4lcRvO@(Dno{Q2%OtCJaOXRxrPr z_@nsUKLKO}SPUjQ_(G2>cyAg6>)YM~0io;FjJP^}iz&1nJ`fqT#U#HVE8ERio1O!U zr%KQt(1UKb_&_Q?BCI};Jn0jV@0g&Z_cq*9al$7F^5H8{QH&2HLAWUhMu-LQnUoKq zlq^{4^FSKtwEixfJ+J|<5+=X47G$LNUfYOo38}At2ile1*WXHEN@bQ%p6csb77gE> zARh`Ga)$$c8RV0t=>l4x_p>uX>%lBsAlx{(t0cd1B;YrhlJN`q-KKcwg-3RRGXd76 zrL^{LL7`g4Pffsnih4Du#hNGSX3L$5G{&U?KK!MC#&N?;gjb{!THiP|_nI0UKEQ9B z#Ppq5juH9}o)z#+V)%+D`U>LEJNY5-Ov;Ddc@Do5j|j#mzCIL>ABoF=8_p1(hYy0R zh2Tg-EQXK(;a&(1c()Ydl@Q*#6Ru^!?dWX8?uPKeIK;j|VhGSIdI|Eb<$whS-aijv zDWoePUYU2|o;RZ~L!8Y{Sl?1%q2}$BoC^;j_96sQll*?ZlP+3{*js-=ta}M!e_J-3 z|HcZ$#t9eSjxB9oi`f23aEe(6@IhSu2x4bIxCW|pKZHRD2R0x!@2|r(Uk8g2X+7^w zJo?UiEKGlAMh?9ZFbaW`=&c%#Q`e18U55hK@m6T58nK=B;rEvz-SU4ndF}FO))R04 z*E3EQT%kJo!D5!lW-Ej^9stLnfJUeQ1w|*PuFz&onLKfYGGoK!tt;et4+2xRJy14) Mg@NJRirBtMpUP%5dB|1?j(bP^;T^rINEt1|IOsGiw zf0c|VL((Q6l9C3HG~0`$)dOvPl`ppSt$49g>gLbN_2YCBrcOb8R^D+dy<^;8Fi84* z5J{m>&pC+NZjVE0$cEuT0zzp!_93>WeB9QVqb9asqGT z{wsq^n_YfN&PbaDPebrokVf4=<4?)Pv`Wa!h6*UnBpsM_3SyG3$G#2{M?q|YA)&PG zh~$K4m?R~15uO3V%rNyEP0(F1UC;PBCIKXq@e-uY+T{MUO6hQ+NumI}Kg|i9m;i;J z1v`t+*bYGB%XQi)%UM|iLsh}pX@JzEjfO@vX_Qnz#b*sT&&qS)%Z;;4{Rjp(2L?Bn zysv`yRi_|*R-Q>PV>0#Ip?v0F?>ZY~j33T`3K9TF1b|csHW&>JME_TV0DG%3$p~;W z)2PEWC1k>O)6;H@KZJMVDVZ+RhK$tQ(vw;g&2i{)idK!IFs@_U5aQ4*O>^dS#9`ez zsAaZEm_7}O^omn5t354in6wHgNQ*I=B~7qITX9;>&L_ZxCJ5|l*}@>{Njc!@@t>1B z^UV^fHV5131h|V(ei7nx5TAp%8_Mmo&C;9DS~tA^2Km21d=27j`Pt`W2@(=y`~vYW z5cfmepRZ{h{t9GAcRl#0zXzcJ7B4C|+lY#h!~NfuajAf7OL@t~lU}R#U;8ZkOTH zni7IG#Gtf4`=T}?-md+#PqS&&$F~^)qykduGiU^9nTiDa*``fU9PqpY zI2T_~9w`26v5^IdbTCD*6k~H>8e!^UbN(u=DG6Mg)Eqh^T+my?T9SoK3$91f4LQ?_ z8<12d+EiL@cuD8OGA87k5AD=JJ2gOkbvdNI*seMn!8Q{xuB=iD7#4^&cBGBG$Ctr$ zj;fUGxj^@$VCg~NM$N`C<+R&krf)1Un`9i`%Bz^2fy2vt`LsFv` zTG5@6lc(~M&1{ys&7VVB;>ouz{+MmG|Ae|>%V5zjsG9+VT@68O3xt?vdnk|JUnVd@ zz*8xX3K>&2CBU_)voBpmxzwcu3w2o2nrIC*Ct3zvH6_D?KPzYFoRu@C0@gPH)^)>J z-*^k_A8K(ak|qw=#g{@xVy*aI2!F&8l0oUXP{bM_u+3Qd#D`(jjEp(98A(Vc&rLpY zPU)r$XF?6`Mp-^*O$kh}6mkr45NlZhOJTCIT16bPVW2D{y!-tgWYe+o>i~vcKWo0lvBx7mZ z;Giqdx&Sr7PN0F=IS8TQHNF6-?-kES@RU|9`XlZj z(H)T-Q|Ax7CN7SA6gP{`$W-hU-I1Bpw1Oi7@FLTbE2%r+Hg9aoN1gb zYY)@CwUH;>NIlN^KQb}~ntru>3oR0Oy!&R;>#~8HC(zvJH58m953B+5ntXXHFIC&< z7&GH8qAqU&%7vkBmXi-->3(m(^R<5@&>by(2(-mN9`HE)a|N1w$cuOaHhkoYvQ|nc zJffluMOhN9FmOcmo>}#2?_xF6MM;f;uc7-Lu9SaR@xLNjyz)WqI(VkKm@FE{094;yoaQ;kq%lFMG>J$$}#V5w!Ed#%i z;c(DWkq;ZzEms!3VH$A;=NE}TMU70$_0hbjCIE zb;OG8$?-In=7^J`&9To6VndzjPbcPN7lyf~r9Wlyh3I7UD>9*UO>?}K0V4WSY>6I~ z+3jb9dRSdYe2Nt20+59Cl|MtMX=U7L=%__0@m@|q>9ll83`9?hpy7>{+6d`LuZR^f zsjTsMH?#@ly(-2Ou?SW~z;iG_iWi8V#f-v5;*T+fI8W5ZX2wMhJ^V1C)BeF<%#4xV zk=7FM#EOez6R=r)B9_ND#Mfh|L~IQ(-JFnSb-O6(Me*0zOgvLm$K~SPVqx4!{EIj* zZq(G<12bC~_Z&qA^fNI~&;pzN_|sRTxPn$BeKZKCoAkk;XOME^V zSBiKfPRqU%z!@rGgHtqa8IjK0ZZ;|P(ay}ZjJp&;w*gC|-pUD=moB&R4@%(1uobwJ0^av)fLbinhbPyA!c2+=Zf1U@Q0K5_>2 zMZEas$ZUL0>>D{1wv62PxP)^7AAH(?t7N?e(cseXIt_ok=eYdHZ>-NuRUB_!eZ#V-=HF}5L`&rS%-?r|bc zL001?P8>)Wh4+dh6DLKa0qGkWF>vyf6eBK3OdaPxo@PMO(&LC%HB$nv$J%(yAvY>^{D z6N=KvmKrC_EKdbe1D^D7q|ha^dzkYpq&PIZV->bc7G}bHd?Yi%(v}e?5O>{$^!?5- zI5FLhfai}Pl<~Xsifghk7Z%nfaoVT}w(cQ?@N^5xb~rd8)UCnr89uV?b_Kq2A>AM)cW(zcf+%qXoh|T~0D&i^Wj2G<+E!$zjyZfEP z%?3Fb5h~RU*QtXPD|{waq)aKA;!Cq$hcy}jypgfd@97VuEsJgB*MDH5oqo>{>>&lM zY1SLAz_n-~-6X5IF$xC#wzs=QQ%Z=JlHNQnN>wAHOMhviqC)T!JbaHyL z5lVBeN+pUAz#$d|GDLoM|G=C*laRKxyZ>XzjhOOyO=9;x@Pt-{8XhD=sSi za~GZ7?&5n8{SP>q;)18CQT$9d#YVn`ZDyp^UPf98VTCuMBHkL`5)NOVWL@2YIFz6i28q?{O||h-BCev==5}}Li!{i zE>63R8WaS(kJ5e;;7MMLO9DgU4r2E zyeiHZJr3K%r$+PCvN1>YjSi>aR6CNfoWar;0a2G(6o#eG0^Lh9V7xzyD>D-&z7RmV z9kK;Q352Nqp5)^N&0j26mSqVqL$2Qw3mZ^;3rP=owgneOZ5EvO-I*!)h#1I>i(chN zoTfEKid6sUh~#4yUvr7=nVdK}i;KHH)ct6{v%tr#2zciDEGyW?fM<@lAZs$7A-XS)$eTZtlMAF)t-uTCV1=MC)`;Z300>gX?&f+qzCHHN%AV;XTj%MSk>@_3 zqr`dHxf7M;n~aD9Su8$`NMQxtttf=l%Nr#1%p0Do>r#HR7E3h79dH7-1w7BU5#ca< zPU$o8H`agCsLa%L!U65Y?o6Yz5%aGJ;a=J^*>qCSIMRC}6~8pySVMM`WNn36*J#O$ zFOpg_g{v<5#`e{~QRS)h;(a-S?X1kQ?R^nMdV+rG^;La^G`)sMQ$Wc?T;_%aH#;;% z#AUYBAu|Pqjl4wB?T{LllnJ~Ua&D0Chjxe@R@MSM8i%DB12FfE@o;JmdA{|-(bF2Z zR?`fvKLf3cC0o=*^!f|RsE)Ad=VZ2^OBLR6PG;sRxMEN~q)S+F8hXLffDG~6n@vG3 zgR5yJz0@>UY)}Z{!U9$JIq{|;jk5a1SC?E7Di2;!u>7g+A74e9*Xm~|=OqHS{YS}kR+<~Wf zoisP(dE^A?-xxt7qr@Raxw1l26}4>3e?i=L0@@I#jvY1P=K#MfsimMb;Q2l<06Pvj z<-Q*hYsO}esA)EDV1yr(w|CGR?kHP;7t9^SU zw1mvtk9=7-Cndk=sPAUKup!1wghX@CX)_)>@=mtR+*7o=_pag%%m#%-E0$oKvwt4z zjE0Y3=Zb5`WmQrarBr; zGw+Em72Q$2!7Lf+>c43>Bvh2+Gjn^Bw>LHQ?pKFi7*US-Gjcw=)kwo)&M)}NHA?7p zWh=ZNg8|EwDJNNM|48;dWD?XY#-?lVh5c+`EJ~Y$==Z+cy z`wuj@C6Hf^IC6rX0o0G5&cmAc98v+#7=O1lzLB$B@|3!AD4YY7ZiO<3AFW#Fs)fP24tVo1C z$kP#!U4Yp_^LhrPL5b${MrorR-Pr!v3Q54^YH3J2qkgT({Vh;MTDQF&y|Q8~e;IVvY{YVWiD z9rB2FwrNDur|xj|=uY)@mYpkSOQ>zaM8y6Hp%_BRq~Z8ih%*a@LoURX5Wb%<9A*F< zw_Z>&9aI+OOi`kakw^ITL~qNl;n#PmMs)0u*BUZ}ZLqt{pSy_Yo#)RaqbIo99Gvuw zz+V*t9&B9e zR_ed#Jk@)OR*U+Hyp4SGsi8*KgO9)a_)QlX+`Anp>uo1#kJ68HqH(tV>O)WuDKn20k2m9wZ4{f5jmTwMq}s!s0$AhF>GOMz60? z*>0>mgtBb?YYz>#9Svbq3ZRtq=qk<*3TW%mH+e< z$V8w$_E(#Ga12pHr&Q>ki!p{Yn)^4d<~Q10UC>6@q3^F~*H=QT%0oZEJALSW;4p3d zfsZhZfAFJ|S9I&|f>O^%q{n{SN5fr8AN@r{{sEL>>%aDq_PIclsyx(~+Gy&hR_QkW zd<9GmtGuqi_C22z2zVd>VOKtV_(%D0Q-Goe=#E#wOcFmA z3_}@l#`l}>c9dn5vTGp^AnVI_HxbC_T9h4qVQV?oZks`NuMFX@-D}7r4g6;18Y%0n zWuc9kLVbx=5!$h-?Cao;mb8qvH8y}U*H${@xj68%a$d)i6{8+fNa~Olw^BXpqM~1l zZVCzuuhcdLg@rv3+s73 zu0VLGZzKH-q}K(Hlyz(H&UfYeHE_%fCG)f|q>gN#D*%RUo--?wO-Nc+8}M8hyroTe zu~UURG}b7~0+t&;*M-IiGx}78VB@OnDM^?o(;Q4z0o6m>*mw!6Q$YbUrF18ry zSiar_OGu(E`WR=2oUfgK;$`S$F?9Ac#3UUfF<9XYcs}ti2R2R>vwTgwM5$>9#b=e1 z7UCsV9p+db{BBN9Ims4x?-0xDf~9|BRc@^M#Hn%JCD?e_u-}tOqg)yJ=Dn~gNjGqQ zc)xKC)4#)+%pqT>r07MV7hpi4H(q;ke9JCbVIYHg4&pW!Sq zqR=A{0nd$rgRV;|)G>^cU#_r(WwXKgK+XknMj(wHU4wJtNBQeoP>F{8D4*VY0CXLA zccB(S9A233A1>11 zs{@~lyQd`BUL81)6!1JVFnLQ|(YrEh|M&`5K5IQCNt6aQnZq9qv$(`&i}VMsB+Ov7 z3U?fk_qu_X2jUD!&vrG-Nd|r6^7U9pIHu)mUcRz?J*AUf`x)Dfvmb_)!&Wz$?+?HU zuc8Sr1l!$Yvb5m{Uj2C~B+goa0hn#>Z=ZeEa{Sl-`(F!!k%MB$8kO~lg z*^&V&lE=6~Pof`#RxIFoLEL(KCLSX;-<~t-pF==Bkaxe#3Rf*eoB__ijgUo6vtA6` z&e^m&Ak{+oF)m!lTs7!9JoFf+6?DQ7-H%|alAff*X&42Vl1E``_% zu@&Mvi0dFe0Pz8czlQkhu*!bB1-KmGePSWxLr8`Yp8+;fu#;?bzV~k~qXb$2ZZ6y;TavI~viNnMuc018x^N#Ao1Az5l7yv<&AnCu$GNdc z(l8I#oNL14H_7)Imq<27m9{gq>jJM3o;>9_f*_HUAOEE?0dtq6G|WSeC*r5JeKfndHbu8 z^uEkn$8%<>o#rij``}v zAk)(O7nkLMh?q;BZ15Q#d}@Nv*x)lBHZZkJ^m0HK0H>K70PA?{+_B}S<@~v);rPk{ zyLj^4cq^BOGLFJ&0GknKmbq}VthvuD$0v&>$(atu)c}`PmJCqh8`BbPBP(J{cU2Km zn{S!7EU{cG*$TD&>oJ5vtrWnaW~7~86<5Bis#dql;`jXI2WfubG0;TG#zD{GPl>!K6A%uPuf-ZvofzWt6#IFOhM<|NOn%zWPAOZHsZU~`+hhgIjH=~V*k*@f9RTbKf zc5gD_vqZkd+wtzLCi*R>i z)A)FNP4k@ic%ia?A5h{b;g>}E#=gG|dd3ZjmcsnoceVtsX(}dx5?&!pZ^ZAx^bOz! zlyR;NoDVpnSY#y8i!#E&I>$&&z_kE55OuKRmqkZmd}?n?O$pI}6*MaZ)*234<2c!r ztmvhp;T(zk;E2kUiVG$KBR9dJa*tG`OKQa-)3{Ee8p{bZ->|F4pCKEDax4v)6Jo~d%w1^h-=ou3N)m9eV6EIyQGq;n9X`peEThl>SG6>o5K0WZME1LV> zl`Q;^E2f#8^lt`;jsmpy+Ck4CaGt~H>@>@atP-A3%dnmr|ho=swN(c21S{o07c zs^SE^R9sg)3M?Bti!;HtaH@Dp)Ti>pFsMJ49W|+7lSa~6Q7t5;P6K;N#D$k-0r+kT z4r~EVzHj`Db%}|tM;YEOO)D)Gv;j`E zWa(fXYrwT;OTg0vrGJfRER3iIYJsUPpb##DvLza%AXaIBod5CDDXI$rPqMhTM0+1C zIRgB1SRV;n5}dIwTN!z=ONn4=p~2j61mb0+pDFBeGx*%9K@PZqGUXUlJPX89{`5|TF^9aZwxJB zL1&K*^`NOoI!;Ke3F+3zcsecP3IvKkVN3ex+WH(j)lDB!%PwJ6i;)FjrF zXqu@aMyN=sH?fWw8K)u{C!tJ_Gdgil<=F_LLNb-mpy^DjQ`38}{f+vZY=GfuHcXNcwZrad*0!b>KWo)LVlV^@-mJ z4JGM6i89`^E18s1+uaV}s@PCniBKd=%bwnO+^tvN;fR5lQ{V15?&j6g9PhggbXQY| zzOu7hac3LlV+)ETJ45+YlT_Wu-8pK#trUgWKF6UiIr7WLbUzG*_bP2EKj#S}>l)9EUb zSf&G>8s?1a=nZ6RIeXmwq&f=*wnjY$o)4+D&a{5}65Cr%Mg828cGq!tmRjxXR?Gve zQ5}5G<+Y$~(ZAb9Mw}`vG8IX6%!dFqR(%1WkbB`K=yuIpkn^xQ#JOKl+6Kd1LYgEk zqBXBVi4{sL|1LpmNQr&Pb5K&FrrOe=-?wZ*;5yg)?xpa(FPuN_u7)W%P#Y@!NY4f# z!ZO;_+7s8PFeK&qUYFCrkRL+fER$oO%6!fiD>3SDKq?BUl(>)>DO_!K zkgj6e7@p=&n8Gh;RqyuFs*rQXz&nWpwyL4zm>aXQ^Nu1khCnh7y|oNjQ9QAsgf!2< zbge9p0jXhSMR;4i&>+0i%Z7yXvdVa%^kpr#3n<$t9ou+E(RqQg?LK{_QpySW+*K** zL)u*7jojpKn)FuE&9AOgO_yYD4;C#IcvrG1$r&TC?=g8{MR;dIBT!3%Av4>N=w{So zyS5i+Um%o2zMksByLT05TnL3>;@$guS(XRMk`_O1%j)S_t>AGU88!j}KjyX}^+*Tn z##Btv3DeQGKq49wD}|_&ol^u*QtT{E`K$@Q^c9?fv^!AH1%pIvr|V~BX&cVF;v(2! z#QG8j9PP5KNPiP>k}CY)IN?Ff+#)dDA@0CrLlA#@D}f=4weL%*}2O!sg3=hQZle-<3(9vU!AGmVPLO! z;qmkvC*ezT*~>1p2eC5jLxT`ddmsQEXflM{%#=3L0S{h*&qGY=9fL2@Tc=*4CW5vv zWOz_t7wfIs3$guZ5t-1~wqos4Z9@r}CZ;PlIK=ZdWlqPpZWNlM9iDT8_P9Gloqlon zje&88x(#@r3-2NXR$g4!7UC|Th1iy0&OJCb^;HD_1w@?C``dU8H*o z$ni6mUVFxcbKiG|hJMrJbbSYF2D1@vE(BK8l;>s6VAHA89YCAR^x_DoP;}%9p7s}& zmlVI%t5V+V{L}Smg6tv#N&xx=4a2zK9C+FlSj9`!Og~pm!FIAtz1Df;2DhTxNfsU~ zx{&XL^D?7Z0MY~O3G+~9rlbi`UND-<;H|2+5U0Yx6JROZln#PA+Bvfa)8Lb9XAg$* zIyk8&3@}N*G!YQI14+m1nGy~yDo%xc(0=`>z394zf*r6gq=y1Ajdo^AQ6bQzHxcF> zEb4X!u=G$-w49J_03FL4_N@N)@+?UcO6n)V(gX{sJrR@z(ESOM{rYLUFOlwLSYOlr zUS$YDYD4#T!hQvyDXg-md*$or7Atml@QSPuOh_Fgq;UZCES6uKf7RmtNPKQ zQ_N|zH?=q2aHUBjm{2~|yE%w1MG#vQ!4{S6U=KdzqIM^(y+?6Vi`W`fRcY@`EOiB zg2}}T-wOA_^KMsSzr7MWfg|pw^17N9xeBi304+OKY@4W6{QGke%&KXg$~go zrJGXft+8!$wQGZG{1?(Ko!CRGe{>{*ibm$E5LY z*S+KabcuUraSuj0wLL$rQWy+caz^_+-GeCoL;}(og!wCPUpdt>>=APG4`Z174~>`l z7dgLwcOCwtechYCo0lK`Ls%EgzeG;=pImSLZiKuqgRl!bjAbmZPRHDvzuzwA&Ym1) zsGxhlq{ZLSI>R5Tus46t64%X6vh4wfzCDNUx~2)ErN{j%z}T=wK=oZo#GTy?K4;r6 z%@P&}sG$r#vC@y+hVXgBJ7xP$AykKWR>t4alG(pe*eYCc#oX%grQbE{xIa|uU@XD$ zFg zEFPW{Ke;~;!qXPu3i9K-XD^%5LPWM2D<#btVp4v)aNVVWHPJjk{G#pzvrEJU0!ieY zZ$*4}F5WNZ-K~vjfs+0U-vjyICTN4Tqr?aAP96P(w{KZRQD4;`LH^#*;s<;Dt=$uiaJ9}@A_$JwI4}7 zFD*R<>0&S{)6&QABw_F;cCg~b!zf)PfF6D0s2cj^P8m$((g^>L^3i?j zM(_Zwfs*Zj{)ykp?946Tk_j>}h%jRs!QT`#YDju;BLXbU2r%^wum{&c7N(^i{LF6c zlvMq1op|3Y85ACE#d8t60K&9+Ahq24?_guAZe;`@{$xI4e}#~~0I}~vD1q=egsA%v zoBIE(_}`8E|E5nt#}o`Q3Z@FYtvAxUiR?^^Ro%AA{wHe!oylVm}egN3>-0!_*k|o3x$4g{7Ivo&avTvBzlYMFeeYdnnZksucSRvQN% zzD8+Ptv&&|)ND1O>krq0Uc!d1TWf!mUpqWcc;6K3{2FRJ6#SlrwP`KdpcOU6nrKM} zV|IGcK~tQQ;EAQDy9kcK^9&Z&?S7yV(519rH`hYE6WexSST=b4KV4li(vVTzGen;A zhTu5Y*PDzI1;guf5#;3uI~!Ar(#HwLZnBgNdr^@355o#L3gL7tgcy|eHN>AnIm(&r zT$wz{p?u}}vU2O^E!za(%7Hv_T0@6<_(*AMvm!sG7|{?KQR5h6Q=fn^3{L``N;=r=yO+y>#jVgtUm=_R*C}(G2r}1>yNF(W#UC{tqgTcQDfSm;@eA`Y- zWByH3r-w+#M!Mk&X?|}Ieg{CD{&(X?f)IB4*&sxH5Mq;E`Ccr1{3nA7fzc}J6+oSD z4rK~T8zgp<3ZUX%5v;HlDlB(!x~XL&)0GGO9$3y=_^y`&o@Yq~fZr5^N2~9>Lbkwi zfS=v-7%uX_-x$s`$sO)#t(9$D=n?Tcc22$3+tcu;m)0~+V4W`?jKgw?%CJ@Cv zwy-epESF{v4p+E)aBlIm{`!xAkYflT50i1l(8*ti*J{>~)VMl1!bu2Sd4SRmmrog5 z!UcJQN*H7-Szk$Xl0L+lDw5-@;jmddcr8IbP7pfCBR(kXydE_r4gs zM{K@No7N0)G&!;iM9CIX!CB(1eovAY>muAL%)v4DgDiUQ<1i&AElf}R5_Tm} zNo&M^Sw`Vh@rFf@CyUxDt@aLYDL7W9dw+hOf1y-}Zc1v}WlCvVZH1*nk1|t$kLs#C z94o$BH9=n=#*xjSx7qzrLka0$mc^p#vF!1IDc1eHA+-2pb$QiM znK&mi?rdV)~L)+$t8s^TQ)cmnbOP`+@yy^yidP?)J=VM|22f8qLW^E90XqTg)+P|*nM+}7X+7;o zgn)D1u29HVK@cB)a3Y>9?tgF{eo;)d7N`6?L^up)iq>uocy^qWMVyqN`ts3jphW#doVILXbWP9`cy8lejjWYz z9P*s@i4#}osN4MF{1rwj!7skH;x?+%Cw8u=AAe=A(26o$4&vB&Z(xUfw*gPt49_3H zEk&-}Y>g1?f_7+Akmx6V0xt#XP&kFNjSPQ*U?+rr7!Sj%kHB&DCUJ0e@&m^lh-)ZmhN9$K)#IIvL^GYT z)letTHG;0ufw|wIJp5KU3$Ycr!QBpu`w7s^p$Fl4KUxAuTv)AfMVa+f-FJ2{iY|+X zD-JLTC5%9>P}q=reMqU`^K6xO$P1x?*^V9Z0*EV}jC)7uIeEv-oEFd>$aP?SB%8!T zR{a)@b>x=#qN4-AvLs%99_O_+?QRlH2ikxHblMkQX$ooDYKnL2UWkTVr4!&Z7?j_5 zGO;&|Xe6Znu=f*FQs+!z$mZGW9d=jTANbn!iRqW~SDx3%R68DDwR~a|mX+-ZO*rqT zr*}7zX0`@9`QD}9l2SCb76u0cJ?!8Gs{CthDJbu`|nwas^|km40jiMfx&-4UIz?*Wv)0&e~x z$z?wWo=P#6qw->dXx||(F^DTAxDtw_3-C4WPBeoOQ{lAz(>yhl7Iyd}>EcF^q?(;gj5;X!c@_?l~)+n0lH{s_^&T%%dw|I2gC zE-%!8mBIT^7WIHn9KAec^gTgeCB6R-xPE%gNom1v^)Z2e8sL%ksH|&$p=n>#Hnn%#V06=t zV#LM`b^#08__e&S!-UiOy>wr}6hP!Y^0pA9D8HaTr$V$t1vZiLM%#izc zT=cT~5|r_}<9ktT5C#(kJF2X({w7h@25C`v;*K{SSe8~10n+rZjd;{e0?tWy{xe-#qY1O z?|pwY^tnOL18`NWpam|SDU^-*;CwL5*qEHz()Lt8!`yfdQkMGaYSYc`>di7; ze|a-=W5MeEi=!$|UyaOXZWw28l4ou_B~J$@$~mSfLU=g__D(BU;Xp1A4BuZ%MQMYc zQ2$4+`-(Vl1{m-ugahCZS`S>z0SI<+-A zLpwm$G=~dJh8{LOBqe9iX`@lxj12IO_+kKoaxy{q<360{tf9s?m`2pd7g0uKkCEzbNY#f(cX#f&Z<9_PvFfo{Oiu0m%Ez#w%I z;-4U(QZPa9JCgOcT{!&Rpe>Aro$R*bqT})8ac>T&1Z(5lYwh4P@XcU}oQ`T*@YMZl zUpFZ(6u|fo4X%(zpwRAnp=8i=KulUYYVsQ=WjN8EUW=!y&RDF2o|gs*HONMtY3@K$ig$!t16p~KGw69rT)8$*b!Mm*aP_YE{MsD+j(B42Y&b^MPb`m{ zJERn(MwFAFxqPz|sC117RLtTL716K~oHJg6hJcM>&M7OvVkzwv0Z9(S$PKN+iG3 z!q@h?HiJ}0tkfs`p{4W|oU9KAb1Ds9Qh_|P1xdd^1H_cdf|J27;&)GKsk`86-jfqC zBc`vr7Y~R}t=ojJig^923c{#oh_A0t#U*0v`h{>!B`N^#Q%V}-@Xn+ zhSXXf#%r!E(SPi>S|UonyhMJKnpV)aXm^?SPobl;KL7y&9z$F z79kc)RtvkLTgatixC=El{t|wV=*im2Em5#7HCTG#&am3O)i~A5popft81U@)%I0&=)wM>4v}$u7An#x%81_%S`aM zjxU5c9pG&6VLy7|0xC@|06$=aKky^IqPFmqPyt#@y-Gm^!Pz0 zC8UceKrU?2N#fr(M%udJWKsa0h_?k;^#L42G#LGIxTyyU7bq=&G6wJ$@EizYW&akO zw;y~KPx**nmO}8sRZiHE!Xdm-H+wr;vhb?_uv2oH*Jo2NyW`7sZ=LAa`> zgbSquoPD#x%GY}Uuof@5GrN{8rq!!*%ZIN1| ztxb)htZ9#0zpYq4f0q>;-r7%HMcTIT0 z@$3Zrl34rfy~baGN`G(K(@5FE;eOnBjnDJGKX``&M8ENXk|zd!+6ufH+zBGbpzO&x zNlI5p6sl<@H~+*v&nAocb@{fdzSJ_D|EML>`h^^BPie^jGL7H}0qJ&HXT{@= z1Z!@~K2z+)1Z!r?TZu7c*Ie;Jm>{|8tW?o(DzZEiNTt-P=_Z?eboWl{8>W4|n0l+1 zV)phjc&Fuer=pCIlfiq?GJJbJc)f0FZ2{a8giDd2$~8CcvZ8c++b#=ljcMEsav8cr z_BWsB>JZEvl-629i*{Me)?!OLm>+vxV#b!+sW~wFTQVr`fLOmJ9{(u5wk` zi}DHC(>X+#Wsq-!s|`fwCB%xE=ePj;4y@IXlsnIl1l?`>8wts!qsj?)Q|Lzcnh#YG zb$hRu2UUE0c_}P|OK?6YwF5SfbFdT!aKXDnzE6Yr)Xe=$qB;xU`#v4AH$t8T<$U3| z{D|JdKf2t~?oz^B4uF4+3l?>#Qi3O~{5?q3(@biFzTGv&2=RMc$X!DOw=NMVGr;Al znFSSMcN)^E%Bri>+`cN=^REFFujXug6%m|0o;%wDvsCDd=Lm<*2*vT-TDI|^2{{W| zalY5{ynNF|RS-i$JP2vjvBRLqAyTFtHpxgq+d?kx$(26OgioVee4c;$;=3vLNSc?_ zVe^a8^(OmXH>>b@{^q+!W?%cRIJ}cNGapo@MgiHRcjSCX_&nQSAAm+)yhmohpDQF( zD`8B~x-9X6s?<8Y4UM^54yie%Qh~N&P8(|lrBl&@;+1EQnLdCV_Dq9m)|vgiD2x{J zS{4ZT0^j|n$#4f0CN||<8!W+M}{%mP5z1>SIjORnGXA&!lLM=AECEQBfP9C;E zX9!MY6mR|(Qe;RKK82fQ76@k>Lwi-|!c{8zB})|O=EJ#fEm_t#O^HQW7X5i&;(PHQ z%*?WuTS}}d39F`<%@$HS+ee;S-%-4TXiT6O*K`_3B^wKk_<=_E{ z=`71~G62v~WBAVp7=Yn3mpP~sN;I1+7hI&NL9aH5sm*YY9A!-Fw;swBNW&iR1VZdbIJlfQx&v@uGnNjJb43K&8>29pR4zIvOrnx z^Gt=dHH~El}5{#WTyMlRf>lz zneW~pQ0qJKrpEKN}tNT(-e9>xtFGu?tsBArPl5=8LubTQg>7rEl7N;>4;B;e|pj6 z74^_X$fxqW8-xaLMt303E`?^-z6;>0+9gF)fw4zv{3QvE9@Tixi1;tAB6BV*4(Zvg zrjYX}2Yj={KVM3<4cIp)RzY`|dqY4u-41}e^OB2d3H(5YkFt!?cKhDma0~-3fuZ{G zXfC|b=jl`VVxo*axG>U3OLZm|hKw=sYoX56fj#0oyIBZ<;R2+j@@b-qdT>#s5Bc9I zCXm75=2BtdK8<3a(@R=8iA39GJR23O}SmPcawPSB@B;ITKT6jme=j?39!p0-LEL8=0 z*sJpBU?6T|su{4g5{(|lD@-!oX(Usu_0oMW8L{~~{%559lCv!0LCp9Kt#mHKnR( zyvrbjxCoKhOfIsPh*AOUDml~B!P}uIs|`(0gl1a%W%P*m^{hh@gd~DJb(cHNq7#IF9ZKwHC)~y zf4GKi6kG*>|0F|cv*0Qy`CBVZ@J$E*#ir}mz&r5N|Ne(IUB5k;14D*^kbmwXfAoYb z2>xCIgl)@k2kddu^>z@%Ny#4r|0($m`0#zl;S}S+6+fb;Br?Ocqph+Z?4}WQBUd}Z*DnhQaCXeZb(=7P~KeYs3!}r)ATMA z=P+Hz5T`&)-jf}L!FRT8e){5+Fri4C^l~w1FV zZMrZ9;S4NLPLjv`S039O>QqABO}`zEDT1%hnh4DGR^o(B>N&2W@tgYCI!%cm4w-Hp zK~D|bB&eGT$Mpf$OH7^zHX#|z)3zc3UnF zdJ<&WWxRPTACLaRg~YdCNll&!+5z%U5p&Ii1~|!PoLfckbq>f??0zNoL63(yMqV`C zsGHa^aOq8tuMPf$1m2MjYZ>rbzv;OSE2JBgnY*e8(nuL~3-;H4!&1Szmu|f?8AOB$ z7h*awchj>*T<~gQ*3z4vrJz7AXeEXypKC3Q4H?l~47Mit9~qcW_y+;_8jt5=@y%ED z36!wYT5AgF#5Yh>tx0iSQCe$#3I5eFUcCG&52^%JLpt7YB&R`7!yVaft)jvyhv!i6 zpNTQ>=K$eT$^XOoUGUcr$g9ZE1+*TI?U=ZJcQ&pP-`l;lG`75;nSbQ<>2^bQm4rf6^(n5lHAG8iXO7rq?e8hI5BTFAafoq==IPx2h(2=A!BPiR^;h<(;JT>c`Y zmy1*Pl_+BW2-vXr(mt)YXCEsz?Tco&f!YR|NQ2Bc@uz)bz~~sVpT`CiI9IBNr%KDs)phwuCCAO|S?i?U~V*gsOzf?WVLdNDLc9;$$BZ z7Y=sySHIZRzv9K1s#snxVmj73Hx$pc{*i-3eh7&JP~*uVv&1BybI*~O2uMYobKe<{ z(h-J$Q2O)x5lhldzoVY{mQ6>Jc-?^ArZWxL3zDq&RpDK@1!bfDSM9hJT2|&k~WJhbRGfEJvC<0NJspU9L)}CLNlQ&t7nUUPCh_1LTaq=2--UgxDlfRJgS$l){jLmLMnJqSGZ=4Ny-fDkzgkQ=~2>7E|hMpDU*# zw~B^A80VS?&|KO^ARjQUhKJR$*0GjEUOUiJQZitlooEfEwUEwFv_|t<5#EdT+0j-E zWsK1!11K7k_XEcKXy`yE8s{WgsUvmeN&HTF`prd$aSNVuj~kUz^C~{lA~nP*5Hcae zXf)_4idIaZY#2APT`01Gnx}@qKp21mxeS_zG-!?r()U1^2VoWjwq0YvTBIS!!!WKf zRnZVs5EA)t$cWf_G@AhT$nSw(gn~F1(&r%j z0HFuMRR}_^T(cnFGP)|6k8Y#~>`$z9;QVNNOyd)d;|`=J>-Xoj&Hd4hha8N?@F5bb zj#WDFG)%UN_2fJN58P!ShdU!-sX{07QlGwmd~IuOutdzBIHS;NNbUVM|G7#p8qJ?b@8pxV>Hv47 zjUs46h-2Tkjj>dVLBp6zReLf|!zNmgLVJq!iwj#(3GC19Cci7el2EChk!Y#d@m z41LK5Dwras2ld#0MAiSRn($0&niD$cfxxz7@fkk`Xc-A>*mfi$iTqFV1ENIs7}7wjWjQRWk2B)a zowx#v%Y^t*X*OC64AXkGZc?TGDFZjjGO7C0YqCPQ{&E8?8Uqt6HQZfRS{(EjTJT#u zS9o`dmD1v9>kCDV7Ka5{vxF5G%wT{-n_JrXUvI9>ijkUnauV z(1%sz)RB5JfB-1BBoD=hB`i)G8gdu%3sIXJb*TXP??5;RI4p?-+(7z62%nO75RO53 z9m4!rn4Hasm1U-oSwiVS?}DJrQaw<-WT_VIW&p(Vl7^#>kg5LhCBzO0k4L4+YeylL z*(>ad8jD+njwn4<5+(dQ>MjzcDm9EVpxi5%lz+mf1cx#W_X#d#mhy8clan8*>(p?+ z@JL)IgsGOz{mUSeI;9)li?kex7vL$f`#HxPZZek%({#$mq{<){i5nm%_QL%Rl0G=7 z?J3}9hf4Iq``<1cT8?r&&iv4udxeixW5({6nAGl2P1_)WzVoX19O^2GL2TYNZ#Bb3 zao=4-dLgxDwC$3FUV~77hPxo4Sx9qELMlA57`9xqX;in0KMAv0Bo$T3IF!k`f^E;i z%3mQypea2#FP1;ng){Kf9OGk2rLdIa*FV=6MMNv4}c@O@6779z8WRdO^IIzzl830yJtx{ zgbN~g+7rC%6d%<~(`Aw#U4cbH7J?8LGuqb3HFF9MrN?t6oLX0BpvCKcBln!tXr#qU zelBI^iCm5c6M-d|9#!X{sb9@;HB*zt1`{1mg{yc&`KuLtLiQNsEX4*sy-Ny!0=o(Wi0I z452e7A-&me=kOj4$9gbJi;w$DOP%f&;sSIQ{v*(7_qe@?6;e~wG#0HwY^*u%+aYXd zH2vFF^dwm)XWzgckh3?qtqn?2$8rCi;_nt5= zE{)xMya)P%y>NG&Y1DGqK0)t0L6W^%*c&$nn}ic_B{*Lgj?0RV9DeLEvZ&GU&t}F* z?@sRsdSisC@rihmaBsXG_Y3Rdr;d6f$n`+5Hz{dzLj@IInf@5@E{98e*BZt>;mzOQ)^$#Qcfu(RN2>qjH zhg}S4I_{~U#Ph<;gdBW8SeKwLbOfG-b&oR7x>OoU92i2G2b@?>ul~**^q%r(t=$JC z;EZ1mdn(sykfF{480M;HQr8lM{pwu&oA3|y zv5?3BadPO_M;U=tA15JI^4}7*>uEiR;xW|w5 zxJ9m|AT0=6lGmp^;$!r{TyQm;kvP*g0(WtzLW@NCkdTs+g1-|cr{rOs@JPzz*e0A! z$+vMn8CT&z9;+hviA+vCF&_qU+JD&Oby;DSC;1p|9?6wa;}Y&3_k@O17m*Sl``>^P zMkq1%b_t^ljZ@t{ZncI}g-RUxPl@>dl%U43|5M^sQbO1=X5!*ae!|C*<46^b(gD5I z@!Wk?X_;G&oR-iL1(5b`iQUJXUm?b$5K3Px>6pyTf=TU=7;ag|=o3hD!;NwVToG_y zdz?Y-hkV=n39n?=U6LA);9U`QJo6p4+eRqx0 zQ=;2Pwa~4*O#`lx^$e97C;_)Zt;SU!kS-e`H4o5#!$-9;+(@Y|L76tSw9=o>-+(PY z3ivUjBjCLfOs|b|=r_zQQ}{GWI}*szyN*{{+3oqJ?Imz#~bjQ!Wd0uVwDeRtkyr4mzqoFuem|? z5Q_wxCSNY zBes^Sz7<*bu7nIbB+7_iqQ%Mp24Y=lQa~Brcf~D-cqwe=pWvV~!b)j`jdcjZKOw{m z&uA0y^TJEo96U?-SQ}q_#{Q^ft~Aby#v}1NI~p+Rk*H*k-b53S*k(U^(+Keqi0u=M z;(PX!{YVRka}a9<`}ol^D$6MD6|!`TB33w=0b?N)oBo)vQ#V&p>TJJhTwxaabXhjT zxi@6v&(da`wb~lzyex}3%ZQOob#EgL9FylrDJ@3Q-%D&jA*rL;I zWKkgv;bAE4JU6Yq&z;4Aw5NH-jr1?OvHm4DmGQBg&ggRMdlCJ2I2+@U+db<}L&AH2=)evr3XB4VJ=p=rppc(lj_ZYW>GSdH!kP3!&02rwRn~~bBOem!|M!pH z{Wk~%sJK0RMh3K@mxQqyQz%(LSduZG0g^l@?9M30FALvgOrq*-f_&^gcsprOczf&} zFgZVt9T)b!E|Jq%174R9J#GT-5K6}BsW-+ReRy0XB@1K1A_s)kS<9hPnk4*`RT@Ew z$x_d@>%yzq@zI9@ghz-Kqm;ipqx7*$t_#0pYvacTdj1sj&i89p1ikn9 ztt(hZ&^t#+&Y6rY!o4|jv0r#ACwcN0!~6e4^cAB(S|jEE6)OKdlvg`CuS#&j{QZOk z%N$i8Bavfm?Gcqc@F%B*;he-+%}^mQQEaZq#Q@)22XnVU$jW^xy69*uw-m=!|1y6( z6aW2tbd2E0&6~m1fXb*b2y&s}rVH+QWDZf&9>Ptc6#Y-;{w|0p7=b+OPlyA|0k(c0INRPp%*E@@u|?+PRg3$`4)_wfi~E7qo_f0i@Zt=nwG5qJ)Yuo z(VAiJ{X)Q?O2@X#Q!GSWPvpP)pJJtFN~f z)>WNZWMIk&!c;KPYQ$Q_cG*Tv_2am2J}n|M$}V(%-gr-HQR(~sTLaw2SThl~gh0ML zRed+xW$rCq-8Z{zBePK^(z2x(=N*`@aK+5bxdF`1HKKlwECYeFv26h4?D0SMl48G>qpf_ZaS1cj4A-E+4qg z#L}Sm5h1@&Kl;6MH5(Vm4}E_Opdb*aAr!H~*Au1)M<%4m>)K@iicmZuoyr;(9-NSb zBZYMn42sYuP(=uj7B1k10|u@i7||Dly+A9K2$6R*A1%DtSWlrd`$J3W7WJJs%@V~7T@++nvHf0 zEaWh7v>P!9Xq$}sUJ8_%E5yfv0|S2}@2}ao0-kH0T&TGDy_TawEC!I4kG>p*(u<%^;PJ|1`NA0^I_aR7 z9`51Q4w~0;-F$O-K%ZBAN&3`|#)4!MUM;4CU0$PqBFrzh-7Mxn0^Uc^4e@?_N6;HJ zEc2|TWj9}WLgD!o=}SpoMk(vjunX3vOwx%ns0DRFuYYLyI>mUsID=lk@&c&Mh{%Mr zaTQ6RI>RvwtP%QHP!EE_?9Mq-+@1P?K#d7vqfWnVM1#%H`c0JHre78G{?l)Sz0X#F z90O;gSRVA|1I7rp$mlYoP`Vn@aS*OUnoL>Vwf=H+bJr6Lw?gDFIm_N3Vmwwvo^Vsp z`|i+gX2KPR0`- zT6RW%Y0rU;yQP$#-BQBIaT^zJ{AuHiUd6bQURt|b8r@{-jnXN7&q)z&O5dhHhbK~* zc}{tQ311*(iF+m@w)PIh9)|ei+i}e##J+JmybJL+5VVkQBY%H`uv=1{Oc5ES477N( zYqV%rB4^rB{RW~P*00fT=vItAyIWdo$mDjx=2|e%G=O3j%pxNqYmAI2=zTfxNBN+4 z=Md7rE8NKGn&C-~Y@jbL? zqvbiL&YkKzMTZNWcj#fitr+_6K7ez4=q>jnPrdn+=+l`!(#rH(RfkDC%_u@XqswZ539HipiBg7y1YKZ@8;!RO6d%S=XX0U+Thheu|y z?(~6Ghf%hza$v>bk;Y@7@w;3jO-~5{7$vXnZ9xCqbY{Tie)t5QK)Z~h3Tf7S?WQKA zyQ0OQQtJ|$C+R>$J~2sa!wTEYafknX<%Zlgpg%mfH;T3mq#d?Rn0_neaLopy7^ZTj z4~#ynhf|ZRTyt+^Y^+sd(QS)0ehA7d4C?SrtM!{Uy8EF8>Tt&u?S^V-bND?Go_+7l z1O1V0;MRLM+cwbu-rHAn8)if9Z|{-*`reys3w7vz?~ldSGl(*61DD^^ZBqlJtc3;& z7}sSUpuh}bhi=YZ8KL69mKyzHFzAIqRCL=bpSMKv$^7;zx|cyIMyeNq)diG)_6$1e z>~ogqs>bj!e7rF)(kQ-V2hm)+xhgpl<=Bj3tG$L+p517%-7fNO8_F|^VfCcYhN{*! zusDf7*-@_Q!n!J~T{kn9&*Vl(%dq$K;8kAZp!hkp;f^e>saz`yKfAK>%MiIquB9E# zpg?}SV%Yo9;7{@g&Mvo%;bkBu9P`MP_x>Oo5Mz(pLK4H8`VooY8Hnu@DqNrShsUG5 zQs;w~l(BL@d&eH`pHk6E1hPa`{hy^fUpo$nH;Tske@eM4*TW=(Po09FpBZR82Uqc$vfYzWG zD!ezGqNn|Ab2Ahoq_z>_yDTXtB$m|&z2k-v2vcus-Os`zN@LRM3-z>UUUl1|z$ zN$2(fc|G#GV$#{_UM_LI#MXhL)R1PB6v=0?ezX`wl@e=cm7)zfF4_j&T62`HaX|5Y z9BPG*VnqfkTtLr#q{w0bZac&s3hFGSCl#kCBF>VWKL92&_-z;W(4VB>7S{uslDj!1;8lGBfze1xq2L2@;ak5qO< z$Sone)uJ_`T14z`iq&Tyud42?NP64?FTA;)S+-hnwEnRj8zG)>ro z00vc8(AzB3Ov}PMg&ouK#*7XiEg38?AjQDRV^ALO_DVkX-(FE&i?Qx zYp5qE?xd89qx_gjDY$>BY8m5ME8A_8))`Ah74ul#w{19olk|Xbsc2&qS(~H^<6~=A z^kc}`FIAnq>_WPfamEZ++bJo1@hQoGQwkd-O>~148LjYB7#Hl6rj;nNNsW3)9gw1C zUxhl4R6d~@@-_!iCVgQ<8or~;uB(|@V_90AWXw$e~AY-lQva&R}k z)9b=uZ+pN}z@G+^g{Kl>4y6xyCI37awY?xNWWD@Ey0@x;aIE4$@-%>YsQ46e<1*fDQ z4f+2$^nW$-+7zo;XqK+eFiYP;xSCs3WtM)Pq2@J( zDD(ZUY7wZB#w=+f&5{c8)hU8Wbmf8xHmJ#|6#isPwWU{PRD=WL87xQ#$&}*t7M*A_ z=>}lC3~Vsz#2^)GuGi7lR7+$9F-=E7DNyMJg5Dd0Pk_=$G7fq7eu%n=-9O?T7DYk` ze=iJO2Xz8jT~3I{6eAXlghm#^AHp!aGJ-XCxe-N;EWaLDhGb{;Kp<3>kXr@ych|nWs?b?p};=@3%F&Qi9U~7Z~@wN!wr541$fthJDkHDT|tbqb0i83 zrNq|HzAD^ZG9IrKo+)`s9bH;Iuz!`Bt84!@32Dc0^v(TGf_H&mh%^=5+1e4juCh!5 zeZ7pE;lOVp@tr}imS=w7g)}3ILI%vMC^Hf)fQ%ReDOfZ_=_{f^VS`DXW;tG0PPAOb zAS|+cBJx71MC^s3{FknF37N9ZrQOL6#vZWrt0Mb42}>7i_<2R~DWo zgyT;^IaJwP%N*752l%&5*=K&@1?vG`2rnI5T@rUambH}#hok8zkf<#*YN_$YkbD+Bm@29oP4}lX!GTuoGG#EX!+!%aLn9gP4Z-iQIYTild zvDzWWZ?*566fRRQwzhU@5`iq|(N|1kU3VlGa9WNBAA)^?i;Io;GQjXlO{DB` z;dgGj?HjOXA#tsg#o-qEAQ;I8WuO5;;tOEj4Fer5+dk}l1W-<22zqw}5N|ZGV2{E& zut;fhfs@BUSj!WUp79vavYJn?l@%hWL zaJ?Cb?7M*xV#6BYF#L$^tbu?Xs_PgrJO{vimo=Qo0 zI?5S@XEM}Xj_}e5PR-#$0krm@F0Z4xu%1{6M}qT11j_Wd<|W}`Rc8bT?{Y{xx7;+B z1m&aGqAZ_Fl~h+wmEy@Xr)n2W3MceXO-tBFxEkc$Nj!sDP@c(n4a#j009mt0#{ zp4JXK>@8Y61tybsx~OJiwOS-Geh|@1!e{7sQ%CsB@Vg^GAkVe816)|Iw*qHbf3L($ zJz=_e#$48ay1CrrKBh$Jo54wp1O!xOvk+D_#s*6y3uCJB$wLdaiVeIy1Tez+%eB|rRCglPmXe$GY(>na;o#V zN3Xog`L@SEcejP*RG(9WD_Tq!l5S!MX3-@TkD+bWKhkV<7q#3qLKJK_@nR2krC~mXk{E7j4#aC@ex4oxA zq}U3PVK2BVM3(&*{HxgS-N$Ys+wn8UJx?q1pszK`Z1{gvneNIQu=8m?TccDlpy5Au zANOP{RW8!OLckm4)c0O~>H{!Yz1c+|PURjnRfvu3yHIYt@?5B#QC!^sov%Fr?;cY| zz&m79cLAvUNYkWcw01Y-@}XS&ia&DE+B6@@wewqSkX@&wx-tQXk(X%gCimN(Wia-} z^T$0kFd^^Ohl`i!xgedKt3S`ZYMC!FhX{_?t`?2}Jd2C#nhabUU zcqE*W2-G^7@K`ZYSqcb4%D65@PwS7GA}^>#R{7UHTF$yAae7_@EM9Xto<8WBSc=Ay zl8p0@RnuI)S4uaqFnO!1W1-e+i@Ga~d!tVg9^R*rB}h2A*48nJBQn`nn?_`xrEbotnvCwLwSF&1Ltgwu_SH2o@GwaErQ^RwlV(Irc54FrpOi zNp!&aNi<|-Ig>q%GN)T8%ers^S|B)}x^Zi3S^9+t4_4sTOUX)KV?WBF1=|N*IlXgOxFw(oS>v{bk_Rb^&(FLolf}Si5D~W!mO)GE+=< z0l<`Q=$4N^`;7-h!VdP2AM|cbvK$_TG{^J$gLV%uAwyi7bZG(1B zX}AZ6H+IEHu_=UNG?#x7nk4MP6F+kk04S(+(w(DqxpDp>k1agnt2U?mJcq}P0zv~@ zYw8Y3V<7Vs?>fTCdRR}e7`hEXUS8%s^O5PVeG0m$3p@``x{RtY?v1R2G~ ztUl`|vzVbJ%VmU~HJ2ayh1GxMKE{>0&D;fUKK$SBP8zUR!{RDLJyc)6MQbC<{S0~e zC)PIFwE|Q&<}sxr#e^jpG+(R#Yzq4UWt>PvIs><0<((_1Sx0nez%)ht?tcF_V}$27 zm5=&YsmLt8?rOV&{jawgjf3Z|#n18!p{k3HM`@ek=D!b^csgl(zGqC2> zU+-GJ^HDhqjk%ev<<N2RLvZKhZbyVOal&Xlzv@a5ieNp6@Zvz=4IB$+w_-X_BR7lr9*tA?Pzp-n0^ zv?}D^2fPi!i}xgG%Z8cMs~2v#Rj@ZI2Z@8$-O$UZ3#1m2p&k^zxF;V!C=A}Cjje>7 zfeYWcOSvf^vDERDNC|oOrj0G~_19WT`xpNfk_imZYjTkE2yGZto#xtpN6_0V39IhS z4Zk7vxXCvBO%e{?JH^llE{LR*8rFKB+f-ZNI1+-7I*YXd??2%!j5G_oz?=94aT*g; z_o?v&A?v<0yj7^Yuh2$YlGjo>q`+7xfVw(?&sDX@%+LelpX!VT^^I(5iz)HE($Wh4 zn5c%ni3(dx(Whzgod7L99YEqaA1!W%^o#%zW=_CA5iV%a+7&XjAqqTsDfS(>WD!|~ z^s4qaZjPi^X&vMrYbTpXRLFpLlN>-P>^Q*dJ17k;P6!t04_H;5g7N+oaCucV>^Ool zj^C}|E=lZxM(`75UV0xyzN7#l+DAC0<7)}k9VI%9JHD3KS$nuKbs$-bw*uoFMEi?! zkeIUxX@cHGL0OXw7=;@kVbkId0a>edsw(H|IlLbr5>Z#iJj70gZ~(%g`$NGNN=%wR z^5QJSI~O3f8^WZ8h}{C=eh8%S?-2W;A_W~y2T2Qw^d_d2$kdGRP*3&1)1U<&6O^T% zyy2}UW%5F0JoS7klZkHpT7T&()QE_Rjzf&L9yHP!K~mdB(U;tec74Sy_XP4#Z8(0zP1V zV9vf7CJv_;hZ#{7;)8*6pyWPaNs|PiO4c&OG{t~#l&gb4X#kszO8hb(hRUmP3eR_vUcx`^H zjUa@jXS)e9!LtkuvMT~Gqo7SWd852u)=clAS}@QwT<}jf9Du-C!8#o#|IZAAbdu9# zGKz8l=v)X(k3jRVGU`#r1a5o}%A4$3nKH?#_;Y&IZ2sep-CP96!YaX03)zo=?kb!O z!u<>4Z22?b_;vuiZWoMRs{&yc=dU+1S>0{0hzt$A3F8J_%tV67L#A)f!SozdybPAq z00CY__gx`qA3v;UI^`xC<3reVnXe)C2&CVK@M#=`SP1Z*Y{)O+S#b!&iik1XQVk`5 z9q>1hXHVYv(he+n1l4*1Saw3kMVF$Lf&xMB0OTX_n4M}>Ls#_hd`{6s6c6IC(*3_p z1-)N|S~~E5ZRsDOmIP?2MPU?Qw6i(LcH?(aM|TuzdFqXK`d1|AmwWt@*qwOQE%OPbK(_s~Z za*B|7qFxKLXsl{J;JrAAb)!5Atbt>M85FV?X>g`sS(K5q0yaLwrCnHR3V2KW3^_%L z)IGGAI4o>iq#5<3|3|k4{Cm|r7H)-D6!mO64Or3$OkCHbLJ|T5U4{i~HOA>LpkXTcYWkGpq{2ng% zf)Vl`AIyXkNPO3%izfXo+tsY^>&$5D6>F9+G1$;@(|Jz59v!odT`($ z!6HCVg2m}w^Mresrr}G%6Y&3!qc1I$QMPY`2iE2|h+ZxQ9e_JIp9XKW5#vc+CsC6j zZ4$Um%b;nJPr;2K3@HtQD*)iVNdSdu3o@Qmgtg?L#p3T>b?ptHSbm_E@u)!;h{Y{I z{aTzOKM&fyI`S+8fe!%Rl>^H)oK{GDWUfKgZmx|5V+eGN;J|()Eie+@~0ZVvD18Vty=hoFQI<+3sJSYh^CK#*U;Mepm)14wN{H)35#kM z$%)$x!-ej+AkPNY$oai4-)?CU9Nx>EyQPJ*P~Kt}^RmHb~ z|FpXF{lNmw+kJHSX>B9jjdbvL z_uFNC=aRU8fb-Xw(uwse#AF$OXvlHsIeFEWS|d!s*}%v}oRPH&K3uY2-QGtLTim{x zXKTSvaLfPt2?}DeTyU<6W4D3_UeLQFC|qBa#C{(T!3S)1mr%MYn;HrTb*oZ!*MZ*( zdNYH+!9~F9E;F3;WX;cq!}wBQGob7zxA0qLl90YiWs?Q}@NTk8i&TWq72#shmLtRw z+dh^O&~1-!vKEO)xKpZYB4-Z$=MG73u;vtZS@l@>UV7e6ras$wPGYPE9%^r+i4*sh z5hv~~#PwVIzN9<(V%z@bmA>bPV%m1YZJNcl=l4G!1{1N<#JKh^N3b_{J=#>B5JG;` z5K%X5gN`qCAkAJlHiT}(aa-+X@mqtn|?FEZV;|M~X^$JXJ3n6{Tq`#0ks zUYF93;QY_sjOTf9iv5>=w{)*2pR3^Tl+BRBIN-mtCzqR^Z+L!$SYc<-drwzgc`@v?2WpKs z!V33*GeWOD<_F^qMJWAOyW^$_?#+E_C*IzBOu0_S&3fBB=L%6RTi>%{V3rk^(plbf zbk+R0;bZMj4NT${dNm*zb`ZoE~dE&?wjsXx9lV!S(~MFW7fW^9*1v24)Io z6^vuWMqsl#g@^0zqdy(~o6uFK#eWrktV>jF2LFGg*Kn^(3t;j;92UY?j;EFl3sY7) zW5`&^O^4YImS-Kq-VRClwpK?y?ia*bBQ?V>6g)bGDwTvkJ=#QF9Ne{BofN!I#MRCG zD9+AlmsxnD_7y7++ckAaFf7l->xD(jXHq?W;hp7~)Hii+h>TN#{{w*ZQ)CP{a!5Abv;wIII@TKH- zNzBRF>;AlMMla5Ft#g9SewRcyalLqK)7t2@#@?{;=cKi>qD3pC^t}+Ux#ogS_=N%a zR9OzX@tvJ$L+EeJQ@KDOJ&JGW)%!PjpE-N3|b9p5GWe^DqA1|?e0B4PxSaKV( z;O*o=uN#49{0sJnd@p#6u&<1;uk7$;LmhRCcflToaH_qDNf+qvcS?f9{?K8Ym zMgg&WrEH}O<*sm%dOr?BzKW#Mfb@RguFt9o)j&B9{cjCr*}YI@t}BO6sRMpFSIGTS zQuZrlX4gFF!3hdY4qQS$CNY{8d$T0hw5)7&YqKW06ypm?8=Bo^LfxNIY#mOdX)gZ& zvQln0t#(C;bksSCH#AD~dQi?mC)WH5`H{EtS%`U{sjoOG&5wY34dUVdL9{G%t%y*C z7muXth$=w_yzQ{}`XIRo#OSL*G9ijc^No3$?<7@|T=?!9YdikkweZ#xPwRS%fVsa4NIia5=&`cEb6K9zQ}wA4^NFnaZ7iQdQbvEen(GB>xaw!yYI!gDn> zrdvHVmp3yv7p^|AL}mH(T2ztJvQ1)|N`aV6cn_mWo zK%e*WP$oQX8kT`Uku*@(9?3D8Ik45iRI8=Oq@nnknSh11L8RZGlE^ifC=W%&bsG__ zrwlc9C)+f2@*Y~xXe@PMdbVzR-IsNBonbS7c8AUU2||ziw+BEKC*c%Iq8__Mb_@cV z-!=M2=xi<+rM`#wJOorxS3daK(U>P&aOAsi#ZT4A!a4f)4&m5SDWl#TRB*iGjkR`g zPIyH4@u^tb%%K(HXcXRazm$Q7yc}Gt!xP(0?lX^A|5}GM65KRQfSZPdM;h|p^^pV{ zddpfoO>x@F4|ylR;Y7^!KJV6!!>Dd-4S#OFp;UDj5;eZj9u+9%$(tc>^3X3tsZxDW z%G}oo8p<&o+;~waer08JK5ZO9uFBt}d3FqxX7!Jk2q0@wC}a2prc z;34nFLnCZ3K?f2aI93M+>h6Hj!f*@tFLvdlq`_>TRnarEc=QI1A zMpJPI)<0&=si%9Awt_XWAgP|X-E0OyjTpNB76{i=&|7g%Bp5a6df>JT%~mA#KvTrd z%7Qn;CgJeYTIyGyaQf*xaGVgf{(k(Duy}m~_6WbMe_2L&evMGSAq|^_*ETG|Swe7w z7FP<|XP&_h;nim*g&p+Cn|a5O_dem$Gv+ZxgKn6A8AEQC#xp;`QO0o39vKA+EBMTX zFnyyI?s6>Nn1y!>+c$!7NjL*<9ujVDEWx9MNw#q~TX@KpjNcH}+h*ctg|BQ`iDQS~ z;cNIq)>uc&R$R~mK6WJ_F@uR*h_EkCUIc0_*x_JCuj||g2M7}HfrUlfS192*`+EEr zfv(rXOpL29&-p08TSrxVevOiWp&e?_N5sxZjo-T~NOQ9sxCy1ptOxmKK+x;Lo_Z}@ z4FOJ0{s?Vnzg>m&7>CC>1w17+N4gcD-?1mCDQbxkAEFG8Gt=;knxE}MGFtZ^U3qoy!9%l$UApL~!R>N$?jE~5sSuWts(_=0Ug9=GQ zZo0|g*6X16?65Fr^LU%zdn<_a;FbCm+#=1m=_Z%4#P--qaKE2Hjitxw_y|6^Bf@Hd zJ3cXdn?nEx>-Y`tlu76B<3$vu}3 z{u^~2xqZotf(t0ke6E3LD@i|$C0Ph=&Z9bf!uTy4sm}t!ds~XA>jB~CElVOcgXgt| z(=Q$LRtmG9%^JNg@LxhOa`8g)0vprxY&LblFMRmySltJ3?UVu8pqASKO2!=$CinF; zSQzwz@`#hXANU34xdM=>COtP1(De9o_fLBq*6put`y7-l60YPGsQlg;0dl97@VEtl zBs}<<4TKH2htzqs&M0}?J4x;ekwSHy?+dtbuI(9rS|u*}lQoL}Op3Ipc4WeuJvyA* zV}SZdzms36#%H7X{Eh>rxF4eVtd5_PVk@tM$~l}9-Hkk5I+BX2%7RsMk5AP@PKTJD zo&29o2l_DmdLPZa*2mzT)?Zz+O0u%<^u1#pkw-$e^h)ZB;l5#AdlaaBEshpGgF|ES zloqR=k9D+yITl^4>m(p;8`i@;x)#2k4=-)8nt9H85{#66a105mt#?ub!@}KLGm{w~ zk*{&{WbQy8OEsCcb)8H?8e=IEuL(Q1=G$KAB%0_c7BE_v<=}6!lS?5|MC1PoKqC@} z0*pw5-gIBF5iE3G+;qf&4@%zVVGQD#K_ zb^(rexpvUIWXK30EC(_40Tt4xWgS==171~r@513m2fVYQyw9EYNDlxAH2}g%w;bkt z&|5xq1;|3U{CD`L<<~>|VY*3)j1X)eZ-rC(>z1kH@K^+QP1%sg6kDa#uokuwzG9+V zV3oWJ2I1b6PN_)(cNEs>^~QAt=O|Dde7oewZE)clVnX(#xU$rE2`g2O)yY4A6HHyF z&zmUSbW;}Mu%-s4mO6F>G>GK*tp`%8^SDHYg0%vyVPKfWs0>_C{a0Z06~MrrD?Sk|+*kTb-_J zl=&5Fq~ja@vb70J#FU&nAHlaK%_)tr7Fb!{2>xPq)(W^M&4A(>(@ExUfGzfW-9EX8 zWiC1*z~0vlmyBDiF^+C2(r^a8V{))8r?k*obpBwUOy*JFoK?tMV8udh8)%%$pfSJq zOVCRBy`8=fP0e6WWvR)qti0aNz)ttUveBpCfW=$J9d>7fkIy^snUe56npzF6nV2rH zuD1RGN-P1zaKe2jcfxG~O&kX2Mzi&_o3z~I(}u96hHKR*bNax;hbMDydz38Y^==PL zhO81dN?$1a?Rhg^D)^tToIUvje2dAdhMRH0>!6NY)#Sg?Px)g}gq5GvF1^6zMFVQVo9DC63{Yof#AqO849)H0ccIXAfu7}Vdbi9z9c8#RK z(+k}Gn*82Tpw1Ml&Be-!#(Sf`Z@BYtEt%iu#WLGL7A(EIAp$nu@~5$Z}5 zcD$&^-GbxA*yI(`MTzOT2$KdkMPX3HRF86!yOFp=xb&hH&lYe~GVnuVnzB-xI^OlL zk&jxg^nG-)2hS%Fnm?Hr+5eJ^`&+I(#Q=r}1T@u@^_~ zHdgm0ROll=^h>wWe9r|~|LBj+z1S@GM|t*`!p{5Ea!=4;7ZdCEn2a|@*Hd>*EnS%O zdfQRIB(i>0VQDX2iu_T5zm|oazcUem_17-S>i=41yg}LOsp30JjlFW?>wQrS8au}E zy%Fg@yN1m9uutF?bVu;t1Spg}%k@n%fN?hfAmOn`{edBEWRyRp5biRSu>Q#Y?Iy+f zb?Qg}ggQ;kBG>Gjxv!EAv^o3%G0Lxs27pUhKa%#9DQ*Kno!(alc9Zjd*Fvs{P+rVw~-Dwwh*a`Z!*+`4$o>?w#uw?uK6!t2 zZ`|ElU!*6^Je7bjnC9CIAS4nHO2YiCZ(Es-^2u)?D9WB+tPTU@Rh-^d#+`r5LxpKe zU+W9UUH?H~c`q&pFr;IEKsTAi{PCxcmE{5$<6r{AjNm(<*ypFVR+oLwRdPvZ5}b=1 zNBg3vNBXcr;fox)VVnV;AYLP2Y8)Cng4OXh(ECQX<=nL^YHs+7x$KwI$NH$KS~zoY z@g+CQopxKf9qxLr!~HP#gxkPXx!>_nk&{bf-DKUQ!vRXT83hg zI*lHVf;R(5PgUu`Z(r4EhdbBgTVil0UW3GKa7Yllg{_;PXGY>v@SVFi;X@$c_AKt` zKwZSPL{6DE;Qfw41Qk}n|49B~a7m6N*GGY5k?W&#;2vlgd~c6@9gVHj!RP061FF!6 z!2bKaGy){~z!~|t*&iP^W7`2x8}Re250nF;!wL?an@~=C`b2|5 z=KAk*+lfa=WfGuaJ_Mx-J)pOwSBda32!=~&Jk=k8?&Fgqpm3-xi;lZG?F zl~qesNZx(G)u1k21cPuU<|r3=_vin4$F_&NxZ$%>m3V{ z)fkaw zyjPR9ZkIj$pRyFGOL^ZE@?VZGGX?3qFz^pRD6%UZtVu{aSIRIXnq`(m7)~MR>54mv zjm___1Au24(L4-hH29JZOfX#fg<*QV(}e9W=Oni9n@r*7;A@RBn@sZavZ|eYz3KTb zHK!8(@vBo;n!Kt8b-a7O}W803>>>VjII_py(J z$69l7t+1zcdqr`39H1zTlJWETou(w``A4^z;$2vmnSQc=6AITdeyRxjDe9Gw_Gqr8 zn+@YpNI=3G;Q9|HI)lbF68%P~UV!LtIMNzB6YR}hEa z&JTlUQa(GYSVEQ9bdyjuzJItcBz z!(c94!_5QDFoe$Wh;@({0yK->fV{zcaJYc?dm*fZ^lFIL6(aWD$Co{h;FKrj$gcpQ zqY$ zYu1&RXJ#yg*05s*a0eSQvZ?Vp*RNlL19f^ z{Bk?vE8+ZWQ}e%h3a%7GAUP*)#~G_9WUPj+zN&|&>@Zf_Nd6&6KPQy!FUK>49s8%_ lSA_5Oo8bch(FcgOYvO^lQTM`PoDMC`Vh~y)EIv^9{{c~kc18dI diff --git a/boards/matek/h743-mini/extras/matek_h743-mini_bootloader.bin b/boards/matek/h743-mini/extras/matek_h743-mini_bootloader.bin index 121b7eae3591fff9d19d040c26b79a92c3a72318..f00008ad995960c90bf1063585a431df485344fa 100755 GIT binary patch delta 22144 zcmb5Wd3+Pq8Zdm$%p{pE&~$@zpCm1`O$+G)77+@?M&@YR3rRfpm3GYMd_@GrHMrs;=fLeh}DQRwZmA`jxp|jEgYA7~uebNDdc92S)}EDWCu&4Yodo}^wEb3i`^4L2ka%JUiJ?&M z$05{yS2RjSRt!JHA(Y(sA!4gaHa4D-P_DM$rZx53a!x>aWhoYLJ<_4R(>CH8`cB#& zE*5pCeMXmec(4QnHoUZCnZC28Kh-E1(a+Q_s%^DJ_*-iZwK+i!8gK?Q1UiJQbJRW zq8z#iO@(2m8v6}K=q?bhWxO4CKuIR`4G5jJO8v=YV&e>>NI~)bWCwI&1Q325=uDNm z4GLwKXw>26vyu{qs(`W6P*RyZ4jNG=Q(_*aN*{EbmFC0D4RekC2nIJF23JnvPeT03 zlMp^D%_fjB8vAXKKl^rEV}*q5kp!q9LIIH!AQb`)MnD4*|I;9pz15g#fO4~wsm7{8 zvS9V}^nvUHxE@bUbE0-+pvsGmsZj*Sp|upPm`Gtcfo z&`u|m`x)|o2LBxR=fLlVeA_&e_#U*@4e>u9{SWZ3fqyM`@;OO_0;DSu5`Tll-@xw& zzdu*mHZl`rLvtSa%h!XDA6FInujvm7%IGmxg4Sb7$Ckjd=Y`kM{kEspHQ}sqTSU!M zO(&X=mgN7|ytyyD=4cbc>AynatiyAf@RaLLl>V0;uzR(l1n@f#Yp*&{<`p~4Z#5N2 z>2~VBswyNvL<~y)t1o;b(%RI2^(i+!`9(Ffx2aEAqev=tKxIV!D-h$g(k8Dq*fdzw&8I=i(3JV#Pc{`U(>W-G+S)shn64Dyar^7Z%usA_WroZG1w$1hn>V`9gMZckL z24HwS2(fM8B3o=){ONL@;r;G1VNOt_a92)fSo5GWcvZN$WR(QCPMY^$JF)GcJt&pZaKVVxgJWB;Snt6w zRz|`c+k!+Sk>BUNLU-Y&>5iBx+>O$`j;cafXpudPIPldhk44!LM(l;lF>-s*>xfHnku%2Lpf4FU$;8SsR8Y6?6REW?KBjn^THEvG6(f#G5Itt_q7mo{Luz zrp5h(j5f!dW5K$Di+YO<(c+20^imb1FlMgkeJgbBZLlO3by*ghv3QR+4kqmK#KLbZ zq{}q1Pa;hcOqhmNk$7B^i|dBsOGBEFm~HjOK|mo2p4dQw&5y-*2C=x(BNG=(j5er< zREhP<0#&C-@_>Ip!eWef$eCkVgqi_*N`T%za38#f*yvFJHwb?P?i9Ga;0}ZP09;xW zV*55Cwj-V_B0$`owAe2zHQapGxKxd{Gce-w630`GWYad)AyyQsM!eg( z-dNSf@xNP;xK>CATV{P{kV(9=3(`eej>Jxgg?7EvG?$;kr^4dB2XPtXBJo)WMP9hS ziG)8IRCj0da{?v4m6*goFMPHF>0I`#KuXr&HD^eDF&|t4W#2+#B$W8ID|F`!$VK9A zh;;>8e0~t-H@30u5Ah|`9v+F<%&YD)h9Ax2Z9913-O4f6OVZG8aJCB)nvJ+l3F+~q zypnKBjd4_$(sCS8qSK#SBI8kNfy3YY66}>#VhEbjjWfe7hud)qo|0ymC#f6h-s;gu zT_|j#{{StL^0@wH^DarxE#PTx+!_k*qKDU1h( zV=XXnMD?C|@~hq@VN4e#KJWh?y5H`cEoGok7Y>cJd~LyZ1{(?_4RQhw5j=SZoRuI7 zL73c90vePS)xL$_!7F%_9L*Q=DovH17Uy`2_?M&_11;uz`S@8!Gk7XDkC*pu##me{ z$@#LL%`8gIx1(M*c(03P5Aw{k;}Y6k1jE;P8NM;Un8&%ZA%?v3^E(UT9EdBCn9w7Z zGY?trGmp&5a09FEm4K>AwcBY?>BaizR>lLWi| z4O$%bRP%TT#|OD^5G|hZ%*?ktSBVQz2mFShGfu5ADk1^jE$AXlk*^G4eU0%i2j(Ov z1~j3?qe68=LYU1@_KvberDgzi&I|h^64Lhh7`_%Z>_M+Ak+}dUBnrM%zN(FJC8I-T zx!3?Jg;Hqob)hd}`Y5t)w73<1DRGG~Ju-Q>Y>W=yE4(pAn^Wm~5%vg5?QkeLO58hyQXA}8ORxUP>34tQO?c44BIrVV-JU+5BNy zeb+6@;P|i}I*Ru0c9Q!=R;p}?hs8SWA>Bs|w*8?r_}yoY5G-O_s8Yd4YzoXbuM$>@Pi zA|vD7lp$P?Nx+W@A+dLi5I zEVnQxE)$;^)#~JIt_ly@SHt@nb?( zdq0E(10-A!7RQebS@NIwX`woPES@9mh@Ubg*Gq^za`7ku8_CfV&Cf1LN>%Vc88?pR zyCilubAFW=jYdv~8LdoKyI6*jg8boPW)rYBC#S9p^xH(;BM0(#5P z0Gfb$*4L$N=lVc{gG|26qNrxUioaJFW)$ zWm_2Wyq6LG1+K$8s#IlBwT70)S>i0KTM?%aR}2wiWSg3uu;{B1nv(1}cZ-}4pM~F; zXpxI;65av(1+bvRKZ?|Bl8fI-!elj%?-!m|FQEQDD0Hf`lZ@WBKUf16U;c_P)_)z_ z|8F3KQC>^%%oJ#4mXM~Iio1kmnu(0h{nC(7rzs>#ahtb~j`Ud4
    *7UU$pC`7dc`bhq5Cw&>1|;?Q z5n>J9Ewz&Bc+@>*Ju}C)EzmJz&wWOR3$1BcljS9w42T0ZM-@UCoV@Nf6h!Lf43T=K z4KLSp$xpAtB8_ne+%WBa_p9x|iE-)ki(XU>tUui(Pt$b51?0i5G=rlFYv18RJ+ym@ z@fcjTDLtcQzcml6A)6{*U24)anR8V6Vp|%2)kzO*TMd*&jzTAVmCjqwN-TT4Zxmrs zpkI1@Mc)jXUPD-xTf8YZ!kgNlDZ-nwMRtkFo6)2dDf&2sM%YqP-UKNFWd6_&VRjZD z0b+&2VkKM!swNd&1wMByth=(!f32zoT7MBZU*TWTVfpm>3-a)ekeTNsHm^$&+Hp=| z%4J*u@ck(wmYsrLusA4zUw*SWa0_!)ZKRi~meLI}ph*@fLeB~JO-QCJK4JZYSR5j} zJwdOAWl)l(NZr^dzlgMSF_RN)sWakjo}YT`|@G3g&GzaJ;sMq6r$V z5+8%yxBTSJhDB);>>$lZnAHI=H1(s^-+)iTaSCsTWnUP*b{VcZO0pGqM8 z%zD53pr6rHu3yrph^$;QLi`*%hBV;-{Xg5KmeI=p2Ze{$}NTM$wOMl1Y% z!b0mZzn<>{GV;K14;-pt2xwS9zb(MdAujW(2r@V(FMFmIw!;Ys`Q77v-4<07ZBg@G zmbyZpHshYmGL!;zaB!IzA9Q(*_NgGRtVqv)2doWQB=Gm(Nq%>NuTFYKFL#|nfu$2? z(%c>KlWVMy=y!)f=CmwDrWTTGAav0YT}nu6q>e5k0?slKgRn3@H3TG0QK_(FK;(&1 zHT}LNuwzmU8tu#4{;Eo?$k5u2lvews-#vNA0DE2m47eArEwRw={tPZ-f)(G70^)u& zkf8vBYojX&l^-#S;s3voG_;tYD2Vz@fWnakMVEL;S;U$8M-Y=N4-3mfXw=(iXWT&Z zXXN-CaHPVQ`f1kip%H-{96#<3zvKkS&M>WK;HD92PG=A|+R(tZr&ftPCfD4`VG?3o zX5@E2JiHwMva0VSy&3%N0IrenGkTabtV*0LZj`CtFi*R&^7%;79450fu4vdiaGQIl zbRUw&RvnUJtja@D92e$!$+uk^bDV7+)BKeyG;CaF*bSB~moh}u{$>th%W@I>A^0EP z@(U&*cFQgI2KWcSWkNo2`@wPRc?Hu!rBjYXIqDdDP`jQ;OSNmX>$?aUreOE3ulwj6Ig8yEPAT{b_Ks1%Qqc*?W=>6Sn4Ptz^z8hnt*_to?ZHO(z-L#~mpB zLkDS((v5YXiPrwg15gjiQ>Wj2=)m#b<7l+JtjC6Cwwv_;|0)hP%mgoKXaDf4PNcK; zmma`StLOmDFX>|%emdP`b5$-GPy|BcSbRQye2rPwD)>H~cr>8Rw#- zcp~lKMWuY)njf9iM6Kh;=8&Vp)43XaLfDb3wq`-wSqJ*AT##G)GY`z}k<-@xv;)?O z({GMDP`RGSJt^Jve(r##xu)W31HcB9qV1#N^J z`00vzeHpYWKk#pe(+3{vLC~iEa}47j`ux}x&H6cz>;9bd*l+!Oq)YMh+eie2Y^t^Y z+UM$*{mqJ!U_(-qv7dTUv+>s}AmD$}>Ofd(1v+k=_gDFX zj%P~~9+inG`lX1or-Kp0{AnQ<^;f(Y}rJix7S;aHTxA2JiS-dPoV^%y7Jx_6F6E z<8u|1A&2Me(s&~hmsk7U7lv+e$FFxPaEHf} z8@dMf#3kwbY7im@U6M|{zt?4!;rdR+V;w6>%6f|9&Pd8UxPL8Jvq%cAqC7!2vW?U> zRXbc4bdq5#U^p%0*{S-)o-H@x)#G|-`Gcj{OU(g2hXrfRS*21iz!#<86M*n+opn?I zI19aR!U=gBtfT$|*7Wsn0I52&XjNZ9#AoY)6jlL5Mz89lX)IRZ89k%Jfhbm`ula1v zoeHXh)sp7Dz}XOiuirhLe>?} zE@H9pqGQ385zwCv3@^m{4<~8x?ZFd*H!sHe_Tb()zx&0(DO+mtKbBbA7gxBFx$7xW zq?B;TG=4rp-4abH((SzxGmBNrT+x8u&kepg7_CP-wyQ;o)9ad6tj8KcF|Anh=9Lxe zDUIZ8V5|dY_lK0gQ8z`~?}r;+K@(aCj=L#jYr_@1`a}@~&RT!~m}lxgKJTpg$nXE> zHJ{fKGPB#P=4s%H>k4JS5FqVkb1E=_PjN%;m3|!1e!M31PD#V#h3Gpo6H@(vJutc@OE#O?$ zOoDc@Q(Cd!x)fG@#Tr8P-X0m5_3I^4%NZ#&Pb;F;fP|}0K$yfAfF5~EkzqU%7Y^1G zA@Tme@BG1+?(w^~_+Kh5>+gROflO@Jogi&4rg)kMYA)0$nd2~TH2X9s)=*C&O{kZO ziqCmyY0NUl>RKm*>)enpDw&m4=bCZ$Cg}mgQqjsN(l<#(hL!79^j9JCHVh zydmX6^KmJ;;<%&_kJsBIPHmGy)e0{ifpfM=(`G1iq{c=F?UqK*`NM%UmBmj1xAPlN zc=QFrL;Kyi?TcsHw2Nmon5~yB1Q9NqX;{JdVeN9H!(Diq+o4?^AVMncE4_E7X89R7 z_eR(zlrrRIhZ|Nz5xOm>p%RIoN?J=cXA+OoTJvRK+0i^g%@u{Dua8m4V-=z^@7purP^8rT{OX zoU+^xI_aqL2_>hb-11X!ePx0+I=)A+^8dbEjf}q+$^Md8EC2G++L*2g~gPWli{W#c!)C()3OLkUNYj&D_ z?q7Vs$PYfn5nv9v5490RaL7Iug@OzIJP4fv(F4Kpz2FZ6u}3h9u$kS2T_6t5$Zl}K zLyd6oh3e48Mx-gYQBi@mq54fme3r1bcpI+YYNXGjdYprV8%|K&=YTx7XIi?c8`>p2 zg)9hUf_?PZXpxl}#51->OXo@B&1eD=|7Jt|1}zf9*n@$Kw#jxdaM2zB-v-y|e&PPR zQ}8>&^LIZO^0=J=(gM<_uMmE}d!E8%Zy7MGG78hDr&%Xv$Sr*>G zh@nhbPYoT$F|NjZS`4Lu;g6~_yk}7NARK0b#anZxd1HWc1uFC6x)4EttnVT}1S= zb0rGYqb%VO_6QRU6TnR7LBm>ARm*&piZAQm1KTfw|1Fjt*z@#|d-8Fo zZyB(KWuGCZ;NyOIFH&w^KGdYKG*~`0rk(xOBAA71#&NSI`713f7&>4&Ut;be6_Y{w zDz&8mgQ({-AU@Ool{13-$r;c8-5J?J$eZ{4L?#2Gcl8kPX`mVb-6{dm4xz%-5ppNd zFe`T#4!PTe8TlW|kmY*=60YaR;21$skN~pwl!7$;olsUVHT)}SB@F7%<%f(4xS5c6 zR;VwCOX~BY)KM4Slz3n^D4}3CQ6|UJ=_nVXgDPZ{KQJ2nEV91Uk+UcNhSmR z)8dCdlf50DOkA zp0;1M;GD~5A~*VVn6@xF(JncKeTAt&p&=HO`E1ub#2ORBB|Mdq@N}db1d9WjSGH_x z3eIOiERXfIAdE*Ej*qPh>Q+j4CN1Go1VT(s>;>oircIq2qBNezcw9lrG&9|oI?pZOF;cT z`A5F4Fy$9P!n=3IlU!<>%MN5C8>}hh^ZDr+GdqvCbYXYfBf;mw?y?_oX~U-5KXvKp zuI30x1x zZrK8W8r7lgxx5a;;Mut*jpVe zUZUp#7j?S&M}Al7B8jPQ1-P*7J9q+xB0j2p1`sj+EZB=fHooqcBd&+Tto<7f1oO~& zewaGQr3ea3WA~msSLwI}Bz{9MFw*g@;|3l^l2Hqw%C9W7k=Vf!4;8 z>k3Kp3@q0ZC6T}uJy9CkUdz|qgg}$@yFV0!ICe=X`bj#j zQx2hIV5*dWBV}S1izn+WgaN86oZ%$CY+GF+sV>{8a2$*$Ey%W!hJj(&iL>c z>PL&o5=ONbsF$hh3du4tU0H!4o|k8K{NO^tnd*^6)~k=Wg2GaM9*Hq9>|mE3?{VUt z1fxm{YTAQbc@$yTwzuomkLFu}+Z?QEkB}nc>k7Yfc7qraPyW_Px~BjEzjo@>XPh|e zQ&({C>1K!XN7yBp9p&PJU=K}wRpRs-MOX(QBQvvLl!MPdcm+?tjn;()AM`5ZH#`4w zeib7*$$(-2VL@gx@eezmeg(Ge(lEx_&s9=zfGiJN=QudPt*Ug8tp?jH=tus%#3&a5 zLj^#0=|>7p{2G!P4$5y(qhEXY6P_M=AIjZ-#nEZxhn-sXm0c@TkVUH6ZC zgAAY)Qr6S`#IAEoWc3|d*}d(CzT;Wo!cnuKd7JZ~73Q4qf19%?4?5y14 zMaBKci_7|%)g6IVOi>fe7`e&-ZGUIAr=9t{(W&Ks;O~dud!4cUwleGhioTo5>1tl= zoN+@=#r9BP)B6`5=z})Mu}6-#pk6s#XmF`oyKWyI1pFE}0Y~;ZX-Mh7lfUNQFG%}& zZ!d#(7aRt9R-QleD6Y@RPvqD9zMG#09iqi@7bVwOqT0*V>jE44H_|N~+e3$4vd4mm zN$$dde4Uz8L%WMr?V0Kx7!2vjN{)-V!oN8y6GwlV%Fp#|y74odni0TD)fJw;J>t9S z3h(}1&xZv}UNWyrrpSKuOgt~=!}$1iEnHG$<3@w+)^F?dV2P*UO+aXGl7i9?@lyk( zf_~O#e^4Nkux@oPOJ4(W8JMe0< zJ?wR>hEdAV7^Knj3!k{_iD~8$Gmb-l8bVxuDm~P{$Q^y%+4$%2=ia++T5;%4{<%Q< zMRJ4x;(YJA0n)w=lzp(nP|Rw>QZV=4^}B@Dxl^qAQo8qBTDXp$)BmXmdGC7qbBF%? zE>M=~YW|aX4o|W{y22%6FG;(>x^H*moNLMuMpQ_vK##J8N3~sX#6I2x=4IP1&gB>J zsIC}j%Zq;G(uXb}h9+Ph7_32BR>D8hqQk$D-^yQcMvjaljeFy|@;UBL1$6suVAxC- z^3X$#e-?%;%g0mMDF@-Oz2<0e3cKg2f;!wW?J6Y1p3H9A@|;l;0Fe~ zokW{ZJ}5kT@12W^!Ca4&QUSX6I*rS-n;HY-qdKq}?AijRx>Oo=AhF^o4)|Xmttup( z(WZdu1rq&7{nzqZ!a!Z6TNfz~1Mzf1q3A%ORT#cE3I8P|+!wnI)Re2zC~9oESlL|NSS zM-?zHhmR5&QyWmn%9ik%T3`(l>`N?RVE7PoKCHCfLc35UJ%Dm{8pF>p;#i3mFZ=yg z_fvjaybi7jI6_7o2OJmSJ{Zw?SP2?*iuL<3yAR%HC|i&=WafNH%W0a(FTOLM{N^ya zeuum?Ze31mgGJj)ag4Z6%GNfRp?3TCQDDvs1ENYh%@-^veF)eOl1B6o`$}JLL@8DU z4{C^w303r)oe~%qh%fptNr(1?HG#=#736G#rI`GK#LnIVHlP?9e_R^h1O~1kkVN7m z8xcTlhM%crfEKv{Tr~rz!qls$Ch7j@#CzsSATMf9C`W7#xUmZm`^f$ObyG;(3JL#$ z!0QXaLLA&MIO`(BCV?vhcNLr)D*tcA|3Be+s7t{hWw5kh48D=BCtNr!RCJg1KU?K@ zTQB=$iN|k9)ud1#Fn>tAQEf?NQqhe+t1tb5L^@=2cobsPOF)q6_mS!peaXqF7Z=?O z{Pw}`Lq(!9J_V!;lW5W6XVmgq`Ch;K4_`)RzvFi&P9bf76KMNXHC<1Gbc_a){8%;C zmRUsG2B%W zxh}GGI;?+W)r=bvG^LjBMdSBND&W5N`o=pE2w}?kG(N3pUy4`Daok5^^xDxKA;_RwMK(T!T36z1bC@|&c;`xl!?5dn{2VX4^UuNG{Vj} z1nv}I^{Ggdd>i9Y<`l;h@psteZ@pSvVmZ#K%mV`h^P% z!mQadfu;i;mDTA0=xGScjkBLKFzH>*b0n>PQ_tA({SIalS%uGxf9r$=-Yb9G@9rNa z(^S&ut`HMoi%(vA5(Hqfy)preIDyFquFFP7e+t4#JZY2F(c)s?ZS?3Ej=xpf>USRv z6mJd`-ybNx4~lP87{t9c7I5)H8!f*5pQ?ug9UJJnE2Q~11Le0viQNB`_&89)M!ys& zu{ls;lTH3f6o6p7PsTH9S*;9kR2WX<PN~o~H&S|C4+S@@Vz_SIEJ6HIwBc5#4RgdBPBdD%Aze7H?Y!)BsXwp|4S-8VR@m^0Jj z;la>S)TAPJT6V}RlUij-H&fzDxDjPtsbbPBwA%^(n!tI^ z%;YRsoZu5SKEP>BP>m*6teyz^f=W5F%Hjk48`g|+DKG~Y>q_C92h`Tu!=!RzX;sU} zaB3Q9u^&)uagS2J+T~AWQ6qt9;ZAI<#p`T*mlZWc@3ZY6R1g!aW>ZV(1X~Z1 z6q&GV$uD@jV6BY7GlU(L*{NkH^IsCG&A4EI>_JB9{iuYTHwt`AO=I2fyF7u)(9O-lkj}`zweadA^Cp;@4Xt)uiuQo1P zj>HC=@@K;h1;ie*Hw_rA8|+|btgJSsLaf?aYF{O)(5P<1O=@sMok>;yH-^zlRT>m#tmcIr$58J~n=go60 zF%@Sl3oDKYa~}I9s@z!>Fvu=%n$yHu*rs83qen=8Ttgim7Vdf6K)pRI)IOfa47*bX zg}*&sOP%ow53N$EfPydEY#GJdc=fVUi$VR4*#eWB=M!pIW#IKf+p1Yqv`+}FN~Mrb zm|QiE%7J=S*@+d)5qt0nc-*xbv3I~CNAoO*k(cub)JL1Z%D8F*J|JAIs(wH}^kskw zf7Ex7=xbz+PEw7?hQs*qb#_o#hl}RW`8A!=n%T8A|Ezh=F>jrGs!WG&{LM!Aa{7lE zQz}c&0(G2hr*%3z1`4O$mSI8Sphx)m38OU}^bJmstc%rYmfCdyG|x>ZN;8PB*?ws@ zzNSB3uPsXO#8BI`XA*bMUK)@W9 z9^!V|>LfF_^NE+7>a6Di0You}m zNP6vP9l0J0o<1b!bvOX2blsYa`cEhlS!w1Lijxe8u{5WOG6 z3wMtlV@0lYK}EdB{h5Eev;Z2&2famY@Hwe=c4jLGaHJYg!ja?VQ43P*wkR!Qx2WHy;Frd@&e@>EerIsR(zV%t*7>FJ zuk%-41`{|)kUzk&v_2PWpDtn zM9`0m6_^#uD4YMb0iR7;pp?L1a&5a%`>5U;3+f2Jdy)V41A*<*eR@0@s}BB4Vj6*j zL{M)Flz-vLFG%?ppgd9^k~GI(Yu;mhCCu~6P(<_g0?Ll+4;o`TD_+_2N)W*14X{ez zvjV|^J@?Vt!Vw6~9VBwBEzroft-B;fPhPc-$Q(X;WzVCNo3}k^oWJLlLxbbYI6I>G zE#sce)XyN_r5iTmtZ$u+s|HT!6Vi6+UU;Wx;PIWCrQCZttoclmn}3v)Ra+&7JPza{ zme&@d)Lr(UoHLq^uQ0x{>6M7)xaOTkYzH!{9nL;(RZ% z8OuE&LqgSR4(}J_HLEKtjW@e1FK=cB7Orks5?*@h z>gZf%z%Xxld6zbW0XXP`P3^+OgAGJFQddZ3PL9rCyx!>JI{`^Y0T zQm?8dlxI?PAOl2Vd@7wh4n@yO1tbm!MWKd|;s1O9=PYzoQQ39IF;&vfD7CD|KzFuN z+PZjJd%U@_imQ@$(^`frtqRhzRa>jRuc~U3&AR9$q>XIWd2;BX0T`?sI$I8^t!v=B zz@Z|ziatCT@zhQn@^L_`#`0cwmGI@$3D)-p6}+YC!*w<=uZSKllu}StE1uS{ZkJJZ zArFS{9a<%hLBZYkL(Y)9A0EBoNi9a_*+LLLIs-afpq0g+fz7A{eJkV8ZUMz(jR#t&peu_&W5xccndGD4r~g%_Sn!iBOwV zeI9w8rD@15_XxkOHzxcx=!E5$G33Q(H1jLm&7m3(KBQql{jm z_IVy?zkfZirbc-M&+`TxCQRKhKC$x_WlKQNG%y2R;-9q091AQ;Kmz%&VB0VgJB6P% zq{XBT@3T}|J~Kx)?c9R1cY^uh40wr&#BD;DwIZ$p2=5{HS0DqbYTFIO0TRmr5qAD*E;+B}3wuP=jt1+d=^kjS|hzZo;)FS!UjAsWXEX zP}pTtTet90phA1FE25RWh=%7^6I2)RCq$lioIFhh%~zep(7Fm06;lDqqaAg3s3?D2RlqJ&eyw&Ue&Hr!bza&)_ zeK6iU8w}i4GXNI`IV(&I9`L%7Y4S$-VRL1LcF6})e(kBNa&4$~GngNcZlmld1-dl= z$3le7FMTIP&G^|lGnw(q*XVOE!TPYW1MnLn+vh9*BYqK169v4%PJma~e)m}~lNixO ze~NeH!JxB;n8ctiA~LzKMI&0tcS_*nC|8+f7Xa$rV8AQ`h!L9)uq}X!z_Y>qy-lP&XLr`rQkm!}r@CwFppBfRdjF zS|OzM_f7sW?iYXn@^&2>4AqymUf$9r4}nKRyM*G6arkv%*+wl^3tKkEQEI>N(Z<;d z=@{8dj|jsXr-z^RVJ!$E;h~%y-l-0{zZPa~%Chd3kQR(~*MdQP%7BwRR})(zXCW?f zCN(bILXX#4;##%lO0(D&VQFp>B<1n&^{*62=jT|!((w4nt4KYi6?5~MR+0AgKds48*m<@FpE@64EwX;Yr#jn?ufBu zweB%S{TyRSYyBWLviO=)#fR{sv&KT@kAy~-qybVCd6eDcdWh)WVR_fMrx#Nn^is_G zy$s%AzV46}6U5OAU%wQY2ahd5@@s0^X+bIY&YfnhC9PH;F0bdHCa&) z2MB>F@W#HcPyqtzZG5~XKrqVTG0UJk!mBqB@(|bVZo+#d_ckA)uO#LeuZ_Cw#R`=AQA{f9z?{?_{CDJCPH7pJ9%!5g@K3fx{nNj99 z_REjy%-Y9Sn2$Ty8Jf3b0L+FQ{Qw`wnsv(azk*EeEZ5G7v z$`%&HjoryeqbRPd2;=rtNbdVR3T+r?)m9L$)b0LfyML|%wQfNy*}w%VZXMgS&xjm( zZ8&!juC1F+s+3rqsem`34mX0hhuoevI37py>Q?eJQY!PhtG|k9^}01fs&2|Pmez`4 zAqxx8jb_{XE>`AspYYx%vG4p?5ZcL{SqS1)1COlYM^Y{XyzWle_t41e_el&`kp%^- zMT`kpm&aaE6j^4rqw)7jK~*Oe3J?a&Z)YtauE}3i@Wk1}#?K&yJyU0#d#0fmh0uIX z>mojv*LJ^W^q%R8JIXt*QpWA((54?OznbfeANJBR!}(y#nb^|&V6#2cV#QRG$xLdm^OE1kyoZe2?4P(;Dhn{m?S96;m6$bz>;pAnP%k~3S^>tU zm`*pZAOiq-Hii#UzyS1LJ53-|!gQ?3XujYiO%-|70Z7^5y(vna-fuaO#gm5J?lONC zd7o@$@#Ird#NlHuP9ZN z99P}ORJe3J9F)!zK6zyUUMSG7W{xuX6kw#FguBA)zA8+6bu7*j?tQhCo8i?2R8z>X zzBRfVrCf7*fFyyh%K*vYb!U5pWHom?x{8{*HgxCEl+%U=}yu<6hNASP?JRJVd z*QP0+J^0!y7hP>|+2q*%My^eC+By2r+7`ur{K>r% zvjV;8b3X((m%IyJ!ST2bB*3@mIj?)-pm5@i`_jsR2xePk@O2qrsELyz8WDC>zYQimS%N;i`{uee$7n9GoEl6w`d9me4E@x3%Hclq@; zF{yfo(QqTan!39(e^KlQ%?G^_e0xWklix$ zdoDVuR{y`r@KL%!+-7^fHx$Ew3t^}}JdO)(^1AyJ-pFu651ujFON%u|7KV&5F&U!H z)PVNoN1KTcg5g3*QQ=jF=l9_J(O%^HsDP9V3^$89^HBk^-Z*Mw`44(WGlm}8@Q(9a z7pFLA(0CL>GkfSz&ZFqZ9(iB9X^=py7(uwnI|!E3WGF#iRbU9LcQg!v^2l$51ct%7 z{CC>K8e0v3;sx7Y7sXcOj|^r|3>q2C4CEc{dkqF-CF2I*<*q#QTEU~|sl1AOLl0}% z?WMNA-#Z$=Z~UJBh`;abJo|%92jN<)fHdq;xHT{kmm$dn(0T%m8-XhZM_9xz=^yuXSN!n&Qo_+FaFGL;@np9J6Ic7|F zR%d@NZ_6>G3_i#cnj-U}oN`OTvomhc^iCsZH{QVDCxTDn@%9;kINQE3Wl3TPpD+CD z?E(#8&TKUBy3#Izpn-InO4+GY#tt2;sUnYi;!)wwxaj&c{NtAAyKJvdHU>^ik>v@WX(pL&-qP_`L2HeG;h5YI5R=kbfSxa} zjcC!l&h0QVGFS}yC-|C<1F8M)^I&A*cIyX)+MVe!6u-k#Z4Bzf11P-OC_67JsNRc$m?!>qB_0-L00DI;7A{3ci^c z316rPokqS0=mQut$RkVD_|-SvgU5uG?`GgTgdOj0Es841YvJIX?i`EEvcni_cRack zbnRH1ntU8S&K9g@ymT`5()4yC?V@O~zL+hyD^eK;k*~h#=bEmY293!*~;tGfppN04i@PlvV2SJ>a54jZ&z2%Pz_`=h>Z(1u-5qllnz<9)- z2R8-WtK;CgG`L^DT?aP+E)&v;OVB|+xNpEs%K&-`{9nL9i|D6x#HuGCRtxC~;C|AB zF-Rsnzs@H4a9}auSa6}>l;99L*!zAAKFBsGv1)dCu5sqmSrf7*P0&A*Jt=F_q^u=5 z%W{#R`XD)L|3ipv0!O+be=WDdUNd5MJ%ZSyixInH$w>aa%Mkky;js_K7W}jl<__-k zQf*bCqDV}KRFV9PB{HRPS(dy14zJ;oVRcJ zDXS-@tVaH8@7n+r@W}GH4I}xRAiP+}{BV(M?{&Ww3vYawBADN2gfBjfVAp}H3z|q4 s=DZ&*{Qlv1D*i)Z^hX-}|IA{t;WByN3Sbtn2TBJ3`va|$W0x5N0OUmc3jhEB delta 22011 zcma&O33yY*`Zzpu&Pj5*(4-qp_be@Rg>*s6qNGWCx&$nn%BBR1dJvT&crA(~Wzixo zg~Qd_x`S5)g|^UpDOg)Yy)IXO3DA3i!ljB5XhBbCA*V^3eD9=q@9+QppYM6TJkMn2 zoY~%aXXc%Eo73_G)$jw=a*o24LNAqVi>pN1IE!G?o*Hk7tBkAIVM;xP#E@Ym&hjF0 z#c1h^U~V}vrof6{{0Y$>VCn9=m0xiX>J zT-j7j-9-5bD@~Q>9!%g(;=cK|1Zx7n3y<_9@GAH(gi*eMMtWvIY!>Cv*fa|i95R}M z<(QG4J1Ro?28gFXY!WFd)LIx!VMswskdtT8=@P64sHYPZlu4v1QkN2oD0PnC!6p6|EA!A-7bf6QB^AoI8OHEkLM7Cq^3SwL4RI2L3%!RU*`M!$4wLkWZ+=2i%&?XNPUl9GDy+m4@3;QGHI_jI+9y%wS z%jUy6lDJGOZb0Iol*!{pB;FzXOQF?}+V9`|=aYKTX#PU_IFGbd1BfDR6ha$(5=V=HO5 z)lA=9X*R)z7NArl032Bnrb)0Oag`V8lohlFi7UN&*lRYkS?n|Gt)iZc_rbraV1AfB z)Mx(*W%aQz64?E05{Z97eGG%r-U~tO;}D|T?Rva_6~}M^&phG1kZ9qhkQjU?q>>dO zmP8(cP^XK_{6tHa!>EUIpp6U&_ID8b-4i&AZD$=+R;VMPx#i*eoyR}rSg zzYjC|0&4+}vr8`+csruS^TSydHN0W0n)3H-NDTGu;Zw?c`Q=tDF7qYA=mxzB@SgwFCqA1a{!C`hq3sKS0=Vfj6S5C zR7vv5f>ozU@?d;O!s0~Vh^v5KirQSLO9hkgF@#1y() zVttztJDf-+3#A1-sn&qZQZ-cc;7Tpp%>cw_B@IWlkST9%MC>oZiilMC{o@cj^p5a+ z#031I@JWQ8ni3(LjJQiaC4x+da8Nrw^bRd94|x9R54DJFpsMyB&GKH?xMXxx$(&xX?-{`x+9Xp~TO<;Z4Pm zi^TWgsW;f7Z5YOv*wT4Ld;xV$i9&4dRZkVeMQ}e{Mf%?dBVQ0S^)WW|-bD%3o#M_( zXfD#6k&p^cDT4jkXd2h6;=5r5AgQoY#-R+(8EAU}w#gbX3{CIDxzYU5E}V{MWE!vW9N{y12$v?vTSI^EL&&yW6cjwa)I6;Hv2Ph8P_ zM8#4RZAH2;9so!5z^Qd@1Jz2Vml9tKd;{I@cFmP^21aNox7_POXn8Ss0;pq|I!jiLsElQmbe~$#* zM25pbi%#x(ApfCk9k$M8>yvxJ>7$=DSX;As4R`6G)x7>;q~Eg= ziAx06_<128`86F2%PH{#p*SuZuMr-P(-%DFe;yVy%II;bG?dsqf-?3vu%2G`gDc=U z;mfRj7qE{8A4cN8g%fdRwa%}DRSYeU)t?aXyyb)4S1+`Tj}h|KF?hdF zrk+Dxh!b8@=ip<)3H6=0S-|nJ@yAAGO{BeRj-PhOb^+J4_NOhyFt%5O$?*%So*0!i z_uf9IyGISsgVy)1tEMb)O=eNGC-DK#-^rwkQNx{ARK|eEaf~brwwQw^DPcMN zPNb2M{kTOVe4CJr>jhWB)Nw2h6i_G@L3}V&i{G{3P6;9EVp6PbE)Vakr1~ zT;%jng`%|Ft726wcW-5C#cbT(m#8?zW(yPTC)3~`XAsrIKJ=8J& zIMUp3q3j`N7@W3lN5FG^6lGj@UUp667Qyy9FN{l>V!JphlG(+UZk;F|5z_-E|I_L0@*-BUSYk)pv7LVYcKE) zG7Du>wJ(tJRSduu?nQe2(_}LD3SViKj++g97u{m$R6<2g$koQ>{>_hpa8{TU@TSmv z*(HbA0Q>7_I7y7K0BV6cH$(Uuf=pPejZ5DMy|C?!m^{LWi4fvP##z+7x+5Ie!$f{v z2hu3SZ-q~^sklS(w93WYVZp2AaJ5jZTTB&tg*SEisU^P7 zE36TV8$Tr?>F=L?@^4^LQBiy7>~vl(9u}_aW?+|)sh`YH;$E+?On(O>7bi->Yx+B= zI-BsL{$0q3_XAEiwUIjxK5G*-Xox^OmaGVT#V()HBiX@@7Jk6>8{6B0fo zWKX=GiX0YRoOs8*vBP~2WdM*j{r`4tmF`vj4#!h0`qZUr|8n(i$%_1*5eex?Dv~49 z=J!lLUex~8YI#K#_vc`KKCDM|$5`46JXlfZ;)%le42^oTbVQnONRZ2Wj!1J2iE^q( z!!cs9B;1`b2@Z_DC$O01)2so8P}rU^4c7`MGUioe`p3AEfz?e1=&c15^9Gd}v8(E>QP*&Mf% z0Y1+79%5$;+cTezEIb^|t;8`^zb>A{#GXD#M+uQxxii=b+O49nKAabfdUKdn?9_64 z?w_zEP#9}O(qJHoWsQC94U)P$`tGX!*>RnVvzfTl2WXY>Tvpy4vdS$+q>1Fi%m860 z3L$k0Mo1mYhR_Y))|&chop}@CmwM&6C*b+AE8uyhOZX*gVfhPc|Hf}y<(axOa0Yp? zJJ0BB#pxe&;a=Hbyyif$uGLzgE)hHPxT`Mu=B{0NRKdFiW_`_+fdXWOmo(LX6q^ud9 zZ^76ZXoGDxiW(%h$Sc*L4A>6P&w@kU*P%NQg{|7a}G_>4+2*e+*b24HlDu z(5qY3aQ?5&Es9D|P`It8lhT#x)U7Kzv&g`l5sax|rqzhGitVyZnySa~z+&K- z%_ytD@pb*el){oDzFR}wrf4(p|HA!~6)Ebw*)DT`$-04grJI;dGLe?8#5i})Vudqm zPA)HOot!lp57-&%yx57;esrbr*pOr$0<@~g@_;~qlG-CyDY$U%fsU|ElZDaA)9!2S ztlsoV!kWS7qfu`4pF%HOsy|>-oFDHj*wCw>d#X1P{ZjRxw42nHN_=wBK+>+Zwt+oL z_FQZw)~om(MjD3mtt*+k?kd=x#pMB46kihXJR00n_S4WW<~ zvT~;js@x=bO}h+05gK#SsLWB}vz!DRE}YFVD1w_n6()RVSi+6^4cs6wO0Nd`fnF#P zFmGK5Z4WS@8Zix_CyAaZN-@$yFiJ39)NbAchlPB4551|dVkus_D4EIcA(JS~o}?5Kx$wF!e%u-T~Zr$FDfMtmF&yMSllHcx|q zhYYTWfak*iwJEwHR5KqhSfn39pb%&-HXBIY3tXw5yJvv$nGV(pCuGPrvm0QlCv5DogCYn1b$EO3H zbHbMVJ8gd+8B+zpn)mbsBp}MvDu&Z_m^VE*xS2MSy4rx}tgm|08hEb$(^AFF(^`%S zp07Y!KKo`IN-Kmuft@Lf<_l(zsZ9eOdbE#Mx6-_p>*X8E{QBIgi_({NGyypB&?+%0 zR=hVx$7y0TO)Fq9BxNO7`GLXC)^P5d@{0Ix-;+L=hh6KpmF1P(W=}E&%31!2J&Vr z!~h16kt$n1y`ZW;8uX*a1^Uf02jh+nE<2;Iq;Jor-BMEDZYi#N;-(dwe%>^@Uoo+` zpVsb{#y6PyBXmmd3sP8{(!1H;;SN`3oKfCjLYGLH;&47;6B=2Ru7RkbbZ9fPo5X6Xas598bz~P?N?v(442Iv-iapLhN=#YwKD5g*3>gGVL^qDx_Keor{{B=8O~rO083n3U#LJDuDL%vI@+qS=w6IAehL~B3|iXF z>-3v9xdx#H>QKjJ?Zzr-bM&AH&)$QJKxttcx^)m|*@gxW?!T3(`6o_KvQprZh9_{QE}i-jXp6D@IWA%p&b=3 zS;B!c-BC&RGbqVO^&>D0fHKOSPDk{-V0oc3nUCUQjk)1Q@gqA(klL-4iQy>QW)z$4 z)wHr_lf`zs$R}+m*C>Y6kwP0Qo7=!BBK~YgIjVCTDzSFMoM=9S8zU{Fo@Cz@UeikP z^H+toW^xT>T3Kk%+KO+2QlX2d`MUf^q|Funy(}TJm2_UgPl+5 z9tG<8Jfxo8_@QKbpoLKNXV;TPG})B12r3*LP14gowy_Zk5mH+Z@m-cA6B0}70-lM$ z+>9x*&M0t?ijTA|Wi|OrTxh~YsoQ>0I`b}&*OuQEQ+ulVx%kBrTLaoTL#k0yB=%ta zcrkz~B-YR@MH;f5v<k4v0GxR1c*m6{jo0 zdPvS6026WZ-cdG~_c$weWBKRKIM>+1z2qbVK`msv1w5@Iy{?N2)H4Qfj4KA%I2&+3 z#?X-#iI7!t`jL~5kkvm(t_Jdv%8m%RC1kfsw1!oQi2Y5muIKT}s{ZnX$1O1Kor(N- z9_yA!AvKhjy^(K1yVPB99MY-AI3QbCnCU>x%f0m@N!khhw0yZG#ftTnQi#p)fCc-) z^VHmujn+J}p{kseC{lB?A^-=gy!TlIX@e#Ta3Y6inRkI@2{5>ds3q&;H`dFedM-+{ zKVLIg8rih*Jm?T9Q5msjkOp034KnsesQv-(;@3B=pAOh#Np}XHT+w4HM+0HNX-xO3 z^fvOc2>43eZ0SJFGs+2cMHW&Z#TxKrdhNk#kF!Lv7v@e1+v41K8M>jUtkVEcyw~X> zN6uSb*X5$^{`wjG9SQ1^gQk65lekpx^HMS7t@G|n40vAhPTO8z@}b1qdoSxOOK&e) zn{BA)U@DLnKou}2KVD9p!)j&jSQPLq^8R@^)_}4@d$Viopv;;7yZvvi1;l%Vzyi>S7JvaHW0Me4d@)FWqu@cFI zu-T-6n)VD~>I{u74QW%$Z?y$H71C3hoF_*-r2#Fc=SRGo;PG>P^glR6Jftqov2s2zS4{+|l|KRNtL6`YZQSHQe5^dti9)?J|HvG{jX zP#nzxe-u$A8pBPJH4$k|R=>{v@E7Z;rzoyl%E1vn%p~RCw^H>GHNe~ z5Qw??gbfnL8yGB%)XiPg5^F{N38_y*{(lMnUkUzS3;v72{~?XvGcVxxR0pO7xyFDt z$to6@rE9az(mxxK(V>G^n<@Y-Ej__Xl(U9m-{?2lR&NE5AS5)yx~qamXn!GU@>c#5{!$4=1}i0yDz z9<+B45{cn!*vmp+_IMeUX%ycQGH2Z%w#LB>84IA;tjC0%vlb{y9PKxaYs|vHtW2BX z%m=bbJ+v8TuCvBCF3F;L7%`lw>aVAj8phpHLW|+_X^D+#G%CFGptc|3F!PrZTX?dK z=q(YTP<(;XE^^V@dqLO-M*z)pE~J0mh4p`SQR$z%==3g^z8}#)26ay^*J(g#H_(j4 zuD~@)UL^>|TryZ=95wWwaLzahuN6XypH@efR1LlVq?)T~|3?DSCUf-7_y2^%XM93q zap6799f4~q%T!RD%edLC_#-5KJPa1=jMH66Go}n=#P_@?BOGjNjMxoK7HkWm!4=Uk z4Vz@}yvL>C`d!3IOo4_Wtb+mdx7HM=Kq}b)6}9E?EK@3;J{|bZI~)pkoGe{b$_|+f zXNblxH_(35t}Hl7XyX$B`2bRFUBw*M@q76FrmRyx^MZ8`FT7@+P*oVH=Gj8R#+QIB zM5^k+3?p@>gJ@>pa^Tq#IPQwl{KJ*R{osmj$2$X_w*y2W0?KyKopYeFBsR~$HDXG3 z2_YptVfDoJt9rL=#B)`+TJnJwd^|v*ghdPjP%Nq`QyxiemmgRF=5)N17HF|X_@p!$ zpAo(<&BWgeH%n(kc1w?~8fpD))e)1zNlZWg5{kLR)Vsk%GVa`;B@ToNirxk>Fi?Jm zUuhy`jtS3lvuxjk{tt+$l*!>HdLP)QhGn4KLE44A!ZWF4>O_wBr(w3ocoSQtZMgX;*YeuD~^+ygVa(TNzLo2w@AsX836MmZ~%HHMkFD z`J6Rnrj$qt&!8kc3uO<(Ga2fx*3gnLPR-#00d()63$LNMkiKXMhlB4y7|L)v7bV~# zRc9Cn@3K*r&|MyrMwQ@cG^c78ObQ1ySw&0Of^s}g!GxTEF?bqw3Af7cvW<}KxvHit zwH>z7N3^&W3>_bLQH{iUbic&-K-*9pI$Ot^Izs1!-W>+Ig&cc3z=8F8E0BV^dn9JY zansFH=F-8Fjb(1vQ6);N2bU}o5D-ifE85X6umgj#1&Opo|Iu#Mt1XNTESnc3Yl{Gy z3BvXxQL*)yJ6*{-Z~-Og`FSwYc*u`K5&LBj7gC6Qcem)n6RhU)I(j&eucvy_%I z$K2V31Kryel3jI14IW`pU6fBTwOq8bluv$#qVJeHSDERs z9djF${mya`vs5$S?*JtbFit!7yGubdtUVLz)`XT1p+(ERFM3HcY?plEG515t;WnfA zq8;az582DVZ9}>pedQv>mWvE~&Q&h5?7!e&#h!K@y@_ncP91YUqs#@c)+@8%|50U{ zGh@ikr+VvcQu&aE|J-%VouyPcNe4>-p_D`4f9dJJf(7csE&_21_kgKftY<%ga+8#2 zg5`|jx-HOo?H+jdm@*9BA)C4jK;>^Y4K1VE-H^)%bM0&X$VIi#G346$Z7vvpjgsoh z03gO*qT0=_{qBcg?Dc1lxvOD9KB)^8FVYJ@0y|T8mV3vtSYi$k9I;(Z907PP7t=Kj zIH^D$7z0NX+?zigb3d%K4gKj*CvE45*6MTjz!-IpmULNdCP+Ky{f7!pf-Z%Ju3 z5OhK)oMm#TMM`OMszJ{X4txLt)s-eRS`1f~0K$+mri;1q%6-qPD9fuYO4yaz-++3P=F3gP;xcOqD z(px`>vT5P3wyx~{fps!HE+DWYSoI&aK9dw(a@cgF>sA7qpcX@viOvEprVqbSp7MDc z-uayiH!n~5w+l@??^25@rMe3jxLgDejL=ZVG~*dMIPq=)K2o^B=0*%Kx*P>A>zQ&lIR&S;lMyBjhi-@1k=o}@7#!%HIeE$ zT?YNBWsfGkSjz0u@oDGiHv(q55l=g6I@6`(2xtn&h9sGD5_E$JXm8=>u_w4f21=y2ufuewIw z2Tvdf5(Ly82tbo64VRah(nV%mFRJL5Neng6WIcc91!@XtDnm&-jb-o)2>yFn~0rvFxYI zxQPHgzx2hfi2Vlb{E|>N4z2HslA@Cc#b_-1dvKDl6HocdMF60nR<|o#>vZ9~1MW~; z*tcyC*I5ov90!C3w$_Z7C5?g1Q>?Rvll8IgKoN8sguJZObLunGUj`I(VHf!MaVKCZ zin@?Kwj`wlRy6xXDR$mj(s-GGnE3GY(3Eo%EbuE9k{oDdxG9|O)1;1#Q}aYdQfa4GONF8_y+m>A}?*c6mq= zcOk9_e8qHJHpl{YDJ1I{cLF@f>ba2fhWrDia$u6!uJ=o?oiu*63*WPIz(-HzN752O9 z$Zy6l_irjM^{*0XqqO^Un3VR`0y7dRFtB0&>58)-Aj>KRYttLJxdR3)j)JhTjxn?_AFo&dyKF-3$81 zy)E;uslsT{9{?!n?Hp?8O$6Dp*$hr=uU?qXE#**S1@N~26toNC?)omUncKl#cE#TA z4SHIw`ArV6{e3lojp;>RdZgtyF6^NaJcFHf80hXb=N_<|9U4S-p=NTc*|+&NN< z2vk<#zJ+sdDO1SBqmaE|@u}$b)m^z`xJGjbHGPvTmprBxYUXuf) zM`**K>NKw!Yz=s>Ndk3GPUw)-2XbM+BT7QiJ<}H#f#)A7rG}M0;4-bsZ*2*}NA+N> z-*X1u!bmf*6Ny>JaWH=Icug4*)@BF&K9KkgxKk+SFkDt`lsKvkaekpt^dPZ9_~9Pn zNpk(3c!m~z0U`9>{FycFA+u%RiKMHgvPhGYefnCQEprk-(#|V2AP>EEoG9QrfuUBl zN6prQM3LekF6^=y!rS+be|Wq^i@$)0V0(ZTe}m8l!X_i8gV08V6h{2{XwVvoC~(82 z*pK0=M0h3AtJ-6@`I26xZ6*JBnu+`uFyQJWwcM@J`STHQ{oWcNB)^4Iwtgp}n!`lPbH{fQJNFGPxduZs z4@(nUiGCbqBQbk3(tt;HK-M4wHsc0J=#0oovS#fJRrZxL_n>h_8etKUF^JLDfzCcYKx*44`l5@`K3jeZ z{+}x!g#V4@qAMvKv<*{eu`a-96%C4g0S^_($sKb3>LN`KfxL*sFYB0QTBK0P#q7x2anz#182Ytu*Z~ghG|A=;LAX7w}I0xBLG^B z7|xNz4$!GLCDumQ6yJ!VDXn53n)r#71OoR7KL_e+3?QWiPQt>b#liqK7{z<)n8MSp zd;n^(TX8O1-=E8*3C22`{v*EOF1#n$X7`#>mA~Vi=*2rY`w#^roFNw7&_9jELgyQZS z-`IhD52Koo1A9-XzUWjmQ^EWzkdMTpcB)woJw0yoFXj{tL|yUAsM7U+Hq{wyYR~^? zQzwE=3D8uN!YICKXS30bm+Yk3*Z$LL$0!+?k+xkX3vEBtc*X&9?f+vL+CB;vu+wXT z1;AY=<57p=qZkb>X82_sqm?(vVYR+Cn#qw>yNi?tGs2?FE1|i^q4a{@ui8>_=bjFLhI?Fl1(rB9LyeRE%Atg%t!@?GGVD-8%I#%K0 z=%UhDL$4l$l^RV}>exD6GJ4_HvAsBFRBTB8os{2m6&#xwP?4O6 zHIW2s<_yH^Va7HS# zSLsD?{(O9w5dFZkcm)W#+||%0WHgfODnSRp9JNDTJ5vL>pJ73{sr(yU&NFqH!-bpUXUu$FKTSd8qd zY2N}WcQONNP?loxLqB0sm?yFx)duh4*&yOO^HFB0nb<&kRt)YfU-yRf=mg%cv+ zDH7cLL~Ix0S7qjcvo3MaZKe5UKInG<%gzo<8oDn-`mj2*rh-3F|Gk~&6IZE)<*SPE z!@_&3^tQJ@gM6)>2e0hU0@sM^6vKhv4@dw?*=ec4 zklm{1vMRsP8ezbVw>?_Nmco-f(iUu2@onHut}Zz;oUhqGK!;v>85a-%x4BKQfvFhj zb+5eK7S$%0qMWg|_MiRrWjNNl zao&TgbK59M)}7FX3x3|#+(tSPf~}qcZ@}b|DRpbaMA-osN@v^+A?IPoyBg_~A%yOKO7^{JY z+Aq??-+bGczxg)erLH|9>AGKSd;cY+_ob1jw%w(P&K0(o-hU|skhBwggx_C{V1vzn zw4p36h_1aOM3wR)bbJvUv)=;lh`6qg`R#*B$<%lD!|aYNd;Z$-uy-|4s~XBs z##@dbTs7eLPB19cJQlCOx7tQMyM4mUbxF46T{WG>t=+3lFKu~gjObtoOlTKT)oP!>hsm@m6SR<;@xIW`8YHpn=)M30u zLmUY)hFEkid6;Y)xV9|5ZC@ZQNsY9=QNPpPyg^W{1)~J+fiJzFJ3>jtF~K8>zGr;qvMtX2kPM zK+rwbP?+g0=2520(f35ab6)_EWWX~3L56>WJWK@bt^7F7&S@XA@J8*MRvxy~l@Z~W z$8zwqLgeFfsQn{?_3;eq&m+Q%k58bs4-0LN=ci0vh1i|27PXHdb}G=HSdQfqxK$hi zn`VJmpq`k74+?ot)Y(4u{w*klt@0lxHbYs9i&P^AfRfuKG2QbvytZL>KhAM(aDacs zE{Sg7`tgK@+Q?dCf5@aW()ziPqLop4U-8?V3qZI1%8-194A`b0>_m-2e{Y`t(CiL3 zrJUgCaMQ{h_{X4C`pllgBe8K93CcCawid7%x`@?%OD4Q681}djSW{oIFZaIUHp0#^ z27Ytd;mtOCHs2^M)Fgm(^FJ<}xzPzv2Ao~%JR`knc(arO;`V0gS|`d`<0SQd8ijln zNu>sm=C7{0%<5nbl)e0a*HD(;1639{v-zYN;M{YBzBLK9H%raVMbeVV3Qacf+(#uw z(`0Xyv zEc+|eNV?sl+8H6z5hS->TGWTK_c^fUI^>7n&SxPeHM8GzP@11$N;HUv{|C@R!5d73 zGQ8T7rXy0l4A}2cPZ3<-Sf{ZqhI?#99dIE|rf8jM{X;QV9e zz9({%xNL;5PytVfGw_mNy}673QpuvrQl2LH_`^ z%^<(i3y!kL>sd9L0Z*q#Wnlg!rEA*5IVK|;^o2-_)zZnSD0WT;43Yr@=KD$U+!hn% zrl^=+Bck<`p}MBKO;aQ9qxFo&QWK(QYj)IpQ&ZC!GUpdp$ef=c^tpap1{y*MCsBHd zdh8i>eyD!`QX4~U%*PSW>U3Kb6gDS7gT!wQaX z{h-zkP9hy6Wl}n->A-jHseQ{NJ68nYzcaE%9FIc#?t`2WZ~^lCDfym;&m`EQ+iLNh zij!7;#8U_71#y<}dX&cwp_&QR{F%ju64hNu)Og3cRbVb4Z$>VJc>X z(GB-eF0XL!Gn=tnIQz`&GQw}Ggr}ZO#b)8p&)yIBDhHp{!kxj`jnCm$LD)Dobe~t= z$hVGo_6-ZCH=2^4A9lek%NTN@G?w`p2sgt$-!cvqW=Q;#Q1F}&8ZUCdIjrPBX0oGfn{j&bl@CkSf}<8=ejpX zRjq5paM_@XngmWM4FwlwLoa(kVbXFq#GM2DJZVpsLZ8#X@_!+4(REf*=MA(bS?6-! zO6p>`NDgBddDPS6h1;|=xybymwR(mA!M#$6{mZLzeYk!r_&&VTiqZ+i8grrkR*EUU z=$f6z_~g3{g+If*urhKog~7>mCpX{{+qVVp5GHeY7r65Kn3SkqdOv=H_?F%wyi=EG z`vv@-Wq^_*xP1}ubU+D^DFM{gAmNc3OOH5rQg|sH4CicpVnJbpHASaLI0d>U0_XlT5>Jm1OG-{Ezstt!i6nnSkl_9 zHatamZ|fA0L;tn4Iy@A_cnzmtIqd213*5Gh@i+Yc-Q{CfS|rcIBjn<+(6lWETZKd0 zCTeGbBRr$i0E_W5=qF#6u;FEi(qLiO^Aq4*^2`)G+X}EKWIsQJIxr$U`24-bL0F5| z+um)ZY~kQ{m9O%7-u9DwwS)o92V}f3{GJU=CUD7%2-uQm#%CmVjYy%I&b@GlP_RFr zB*eT>Xro6`D{$cx)(HM9DcqjYkpat5=FjOfKr=|clV7UFJ&}A~#~xG6`A9yqGqfa$#hH1pm7gLhi5J7pDQCC&7H zY#qB>7xc&~t}B9jjy3HOpeDAoHu32knt-P_S@nE$YcrUG(S@2$0@C?WJ=|Sv;_LX( zk|wK}=d9geBprYQMquh^VooTo&!iZy@L0VXUlq31=h^)5DU!go=@#%pH_O4vWha+J zxcd74TYyr4iE7xh-&$Dd6|4B(|6W$61LnAZp&} z=P(ynNqDPsa7fFw!=95qBY@xr32vDR=~FZJtc(H|E+5=$t8ayOR+Rg-W1+MRK&S=~ zx?OUZ=3&p@e3xN&hsw!qNm_m_xY}o#l*kCd_E9|?w%;|)Am_ov5u)uN?pbW5Qo~x< ziUjz+!4j+F=^KV?XgVeMS&~!2yyz}HH?-45pg#DuIzaHT1+5>~2O*Cn0@ zN1U3@Vb48*n=Z-{3PVu?<4GND0R<#EQ0stVDmksKgWS}Vs(ha0Pop|~KrYpN)NKc~ z{h+ozVt)_(n0%fGeD_K0$M=+mpJ7hI6)})-;BtU86JnodJx~g0%i3& z)A`nQ);~arCZHIOyJm97T_(`dVQ>~TTTi-3%Rj?qUJ^eFH(*i5tf7YwP2={vl`Q4) z#0927RVjte~?Hw!gF(mk5_$${m;MSAZ9&3eFOrXN!>havV++ro3#? zT=43GMk{38*b&=@(yzI^z_3Uz!ixAjKYE3CU!G6F9pa&v=YkYg`pPHx31RS+(ya7X z5qtBMG54|)U^6-au+bLUN?W#Ak)AxEu7{vZ*h1mKS09V4h7VQvJQIOHs#@_IKF?I) z;;YYr-tPW}OhxTcw%z9`7G7@9Caye+bjBO8kw{#ARBV5N-_}B0-p2E2@&e)8hRHZf z7;c!i2t+68qHD$~lZ%A)UG5l5bGSA2p$ z0w1!~=+A!7y>Qscd&%;}jl^erjK}kNevpK}?7TO#2>4&NT?QYh0WCFnhxd5LHrwc@ zs0(i)N)K|^(dU^ir0<#LDh|CR+U>;;MGy8sImZW)&eDxuu=5=Sn{Y_Y#+isQ=8ws|+-FtvUGnzJ-7 z5_cM3HyZnK_-uDp>e{~g^^I%_tH*QDZ-vlU>HP`ulB7ku>03hKBhkgDLZFqz)sQ~V> z6|=tZ!5t>W*$wJ&0E9Y8j6PTGTe)u&_O!M7{9=Sp6$t>Bus$TcTdKGX1atKXy&r(IxO1@73+;O$8uict(+AAN@dBX>j z%o=aF2Ycm%RsAt{YrWy_RPzi1!f>j0D}WGBKqwCJvECO;ZIoAj13^*t>2JzkK9ySZ-Idf8n1 z>&c@7RKzOa2XN6v7t5V=S-F>8bzFz*VeToHfva?V?54t}l|;M9x=Dk>o$Pr9Xi8P> zCJj5=>$&a&id1dZ=&fFl%U7cDdVYbAe9)D8xV-_KVV525-jh$Bf!0-nL|Yr2Zp2>G z%P%q`@g4Xi-~YgOOThhIYzJ*WF{zQ$@dtR{K8&D36a0_mZwJTiaB__}_*u6Eem>j> z4uMYtk`KAD6*~A*o^D7L{AAgGKkY_M0njvV3A>r+y&rF&7Z&nxa!oIyFL48{S^TB_XZIeSc)-k3st zdrVl;n4)g?+2I8KyiE=_hglHdTaU@0%zmHH(5QK&5bo$8gVYWei0?KBzw4H7$%n7k z(Kl_;^vz8RnkfO+#Jk=}Q01-Qe-nIeyVAhUgtQB!bVIyZW{HRKehwDQqE6yz;&ZKs0n8QZnqsN1B%!e>E53=} zYzjRCAC!#RY?7aqRqo{LOfP}uQYG{@>EY%?peY^yQ%G-4o%%UQgiKI2{0rQ%ae&6A zsB?`N#dtw>gj8Lj=Om+E*Glb+<R3Y|J)SE#)*aAr>taxWU)(N%m9G!mw zZp}~#ArjNKV>w3Xb9h$3Gl^Mv?u0n>c76yvlk#D=pTlp*H!)oCWz1z;&KY&OvM>i6KCXNCxj0PX_Sd{V2S1 zPD1P{h|d}h|NFgs%n&2d8{o^qapl3W z{P>6dp8-3MlY5tlyH@5iaBR&3>MR7h2}sWe4x9G_u_X|D1F*l=?h0|y9$WEMkd)na|sVut^3fK@ezZ#@G?cO682GLW4=*>`C) z>w~xd>lr6+T&g;`U?I!oYfFVVa)3ivKqFKpCoUA7%(_gS>CckMddrj;B_;7v- diff --git a/boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin b/boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin index 2a5c57d308b2bfdb05ecdbc317bf51dc4bee40a1..276cc5c99a30da2de309b3c54cb516361718ed54 100755 GIT binary patch delta 22405 zcmagG3wTpS`Zzpu&Pj683r#OTdZ9f@T4w~p;m0jlz;#HEdcJoM z-`I1~@u=mDq)yfLRxi?uQItt!p;2|}87T?kIv1HlBYY?Q=eyUjXy_Zth}Dpvq?7!1 z?!O|q)LCUGrS#O9@NWqH=ciJADCeYPOs#;pEGU3dP2%2}C&4G-EjZ9d{Aln^&?S_* z6_J>TbdxBDCL+?Io9U)rqY0V|g|{$)w!0uFlm0q{&e)~i)C%!Xfk~twdvB@>8ZiL~ zzYH~|PTvZda>}%tXzLkC1zlA@-)YFHN*xWAs8T60pHgS~TxX=&FmmHeQ!j$f&4$iZ zlJDj4z5FDE&q&h=WK5=B2c%EG^R2Z*M9xqI6c8bUNHUNDp$cQ5f|&oR5c1xxOf*8i z>8aGA>S8isb@bG}oP)RyPtI_o7G$I$RgIbDh{M{m zP|9oHF=-Y^NR2g`MO7$8YdIxl<&n$;CrI8?l9fT?8Y$@Q8aykt z=b1%RWe(NT4*7n8^k2X~3;tQ~J0aaM%PhVNwROVx9}xcs_}9R{mN)UNBtiz#ln9ZR zA@VZ#z2NueshWpIf*feZU;Z5ILMVuu!|!rxUPyg`y1bJ0I(=x>5EO zCyZ|e6^iL}8@{M6CO~8vl=^2+^g5(-X#VU`tzZ6G4b->3M^&pxDRn_%Qs_(Yk%qCv zJI*w$hvcC5Lzn?!r+jbGoux;XC(^=%!NQEohDn8qjLW{0N(OaTW7xC^UT+I;O5!uD zcncEyqzoJ0jzovBNul9}7I+>kYJ$vpP){w?Qw_LSn@!3KKPisb*+!C$E3FWNhWR#H zjH2fy(Vl$W!rVGkATi;aOaT|kp)Q5#9#tVa#>2W81xphgH)NUJIh=Mt<){M3)M!%Armi68r+7VT*%X^Kv?o6TaU`6~#EV|8Tsi#}tU9lxSZ z*i%?^8FfYg46iE@+YBzY(V@eiEa4eG=&cZDC}V|tlyP`6ghoXSjW8?wjFdh_IH4J# zJfOiPNX+w{72Z~k#Nr{A`J%}e>W(UN2u**1}2np{JmCMJQv8d;E!#5?tMvCN~f>J zqSAliD#EmQ!N=%wt+_U=FS=l`IS?)0^krJq5W`rxlHGP_IM}!CAtbVaxEl!q>x6@Xx~U!!n}w zO6k1(P<1oM|87I#Gs38-N9=F;nB==VAYP>9NNk6%h>n-)XY!NybeOt#;adi&NPG@L zvF9JCC*co$n$8@4MkvQO5|e!6{Jy0~?{SU~#f-p5MM$q(XoilzUr-D_+dQWxfZ&g46J%4C5?GbBOM) z8Ft)*qQ<%YM?%J6!|&D~phl7(*WGG(TQYESd72x&l7fTi(UqsJ$|hafq!X*`bgY^2 z6jGPg1Bn2A-5@0$!eWUp=>2YRB;YA6ehj#%dnV|04p#Cs8OUpR0ycc=j&+uYNoEEM6v5ec?0ZTRjmW09mqZa^S{B=3W> z6D%Rvl4l{1K^bu^8~Gi)f=8*t`BGl3tv1kNO`wE-Nvbu{;>rM@H0^j6PvzzF^6m{7 zi_b`MzM^Xbi_#07sGAMj>tWf$JTs+LLc2#l7e%N-ub!b$^n^-+Z0+J@(>7+$t02@{>l^4Ea8gUxu6&871%S1W4>b6Ks#THaL5rPX{tuG2GYfI!hx7k8NUoN{1#Zn zhXb-?<~(4QcychEuWn{MspyDRE`IBWl4-QqBJ{*ejr<6{Xz@6~Kyj-uH8zDUIrazC z39ISRSd+dqNOqk3?eQcmf)SWD>aVf<1KPNf*)lIdJBa!u?09+7#^1~ZrH%% zj}sK{?Z0ehjP$nDrl2=&fa7I{49)ajBvwo2B+RRvcniIk7N-hN#OZLK@Os?j$d`gl zC&#DSJZ?(dB%F)Opvr?nQi>t|Z_sdl7)pf=I5odf#^Y2Cz=sk$g=xb_P00^VZ(=;N zWh5pinBN44RL-fZ(WJZLr~Pm$i~IUTcYY&4$)gJ8N(rVnsq@IN5`>S2Yw&x*_rtS? zZwgxL^)`;b^vF`1?op)Mvlxl@3E?AVC|d@(rr9NwcwBg7gdV>jygovgD-6B}O9!R5 zxl|k_w)dm-Jx;8nSN!Y_dcO{2tl9!W^4FsD)JnH4l{^ z4copjWn?yfM_4*?8r7s0j*ZO1PQg8L%DDOgTt{1}x~dI|(6XA&%eGRYb3nF}RC~?& z>n7ROf?o90uj>n7DDMli)Uzr!49My_Zc_`b0|sblcwm>CoH;U!sxb-X>U)9$VvMi( z50x?KJ$;NI5!*;vFqa6a(|tqV4jX5n#0a5JJr1uF(&DG$lfonM8Bx0jt~a~@1Lt^x z4J(DW;}h|RLQ}jZcJ%NqBD5d_SWD zqJ^*8fW!j-P*?Js6~NeB_Iri#S@AT?wlE_x8#97E@d^Bpa6NH+N~T}Nm((MVRgv{{ zI8@ZaM0v+Sz+!Hg(*oR!}kO}fNvvwhY1UkM(Vcy``hPZ_(~{klu={Y`^K!` zcvT*$p+?w|G-=Y}0HFlQ>7)kiBwN&QetKC-x`GGt`Oq-FLt=L^=az}X(apke*8T{6b zv_m=nXW+W~Y!gtB>w(w`M*`9U6}fKtXPcle>wt>n09!`{P#wb$A;a`~Qj-EU_iq0q z))lrr*2A_-)_2|0VZ8VG;z}95wVu=lwU{;zRkIPQL7wRp$H(RUd==>^@qheiXISYr z6RzuZ4OL5uAOQ;14wb2e5X*llOii9#cvm3Rb`zFeBoJlB`ay4RFm*{>y>87u6YU!G z4#2LG-<)dea|f@*0A?oI%=OXG>D~U$CRGW+O-iggCU8|FV@fVJP~v7k0W&OH=rAm# z~9Izv7mIKLgg&Z*X9h!1Vw09%BClm#_!1bA|mcS$&{ok)GTNeI*Jg6RH$@TqPh>_ETk#wa=KS#3N&=she9 zPaTKrgrZa(H9qa|W2q4o?AfbFKSBLd61qn7m1m^RN7A8t7YG00-XPtt>W1@eINI-4 zHJ)0!O|qgv?|unsNhq2plRN0mIiBD6^-_6hCjUk#Jrgzvb<jawvjYutSmUF9R2=jxe}XZO+3LVV`t@*xQo}q1r1Imv*8Aew<*1g3?_-XGX z(+N0>)4GPqE;sb8Bx@{5V=-&%t-0z#u{ndk>Zbd)t^k50SD_b@^t}Cy#ImhDk%X;* zcIh<>dkScJC1G=J^RwI#KkI<12tUh~I3*^(pk60ZbSs30SXq+a3^9FV{7?^JkQN*R zT86`7l^-ynUJXaZfVT^_2~~6OT6H7T{vvS8!as*c71C?Y%cI-E%g;(|eupBW?X1L9 z%D5ts6{Lw+b_!a-qE7<9@>WCWl;*0NNh{TjmbEe`Ju&I+H6O{Hvu!Y^YJU`cq# z8Zki2;ARS%GGFEYVB8m*X}(+3%vc0q<*HkoJv{G%|`Dl9kCVs)f-@HvU(RwO>FT z!hn9%h~I*`C5cV>%|Y+aL7zK=Cwu?T1A-wdYeaRUc`d{LOMXuqz4qSH`FMWiC?>B> z5Nk&Wm&d6}a?9wob1~Izj#b+nivG4umDd{xls8T1);e&|D+IZ<`ckX~Jj`Eblk=$#!T)AI#E z0zhV#AT)r9EC|*De`2F-ZA!%xxO*-wBJQM8s>D-&tiVvMu*%w=6MFbK9%$j{EKpnegXaq8dQGbGN44N2BMw~DlP zyG<34hgL(-dpO8wtJW;)QN&iQ9HNj;oIu)Wn1UNEQsb~C3P7KSo5I%`gx9kt&ENM$ z)!G9I%X(gnMcGw<4ZCoucArV{i`td@Y=?qwt6FOojdaytHEZK7W%zVuchc5|hVDI4 zVdqDbVclsdkKJUXVKL|Bf9oE_ce`^pX7b~K0F5sUdgln5vAPla+pE^jlYe~nv)d3- zhk7fF9XHSZNYKFd0Ihj&pbPfeC6*qX0X$y zuBUApzQeY?cu<#hUv>pb16nz(LQGO#TB&ikl#o%yo5+bD?|)Z#-#LcEr_Mk zVcCGJ6s2o>2N%JzNjGYBFY9`%t8^km>()^^-SVJ!V!sgs!7QI;5K?lsQRt*d%IRn5h;<2^1n2=O&Zb4HjHTa!V?iSx;^S9%T`KRB5LW&MeM;m zpl!e@CJgx>fPeM2^MD^U5wWj8KH?%FAGd~AFl|&Ooc8{KEjFg zXI&`cw5zoT#kTes(e7uAU1nr`W_TwS?X+C~b^FQglXR5OovX8xF`pc$cmL&?kDj^Z zCY}4J4P}1dBK1-FkuEgO-dlAL${~6B)LRc9Z0&AE!{ilR4piP^H30mpIan}bLp1V% zfmhr}Z|}7n#89f_Ak8o8VPbVFMfd16)e3vx>VqiL-n;7HP~9<5_moMlp{ggf|KBVA zY4Egr{&75xcJZQ0K6>SkZfcy)^RP?UukQ|e8<)N<{*->!gWV7cFYXWt8m!Jro$Aa=zIhb~Ho8akvn zV~3>XK)aC(2)aUNj5F%Qt5v$*PMxmz`4t3tf0W{YciZPkqodj&ug%^8+j+8aVuVrL z?|_K>pk{knVg%@P#J3%f(lKpsf>uKfRAN&4aN{Qpcq_^@idi)f2RXNt)iscuF*PVF z=KQ8Itl2z`>|W{oo!x7|8y5J(#?@1{nM=azGx#mV8d+G|`qJ-0J6hrr+FrjMq^$Om z0q-sUZ}Pcq&sj!2CKIESO&)pF%wJ@^VoXCH8i&L;Ya05D;O_$8F|Nq=NQS3Y!!(Mt3OYKk#+bd2S9nID zy)6}@F+9a@-{irs2chu~y2D}ZU-rKVYo5~P^N;ncqhEyZ>d=w0dL`cRk@T<%j+ucZ z9UV~ClI?RDcSqMej3vy9ZB7TKt9=hD!)IX&efTigQ!tWFzB{VS{R zV8!Pym3szn*TIJUu|z86O39da!>T0B!1>|--aUl>PFE6#0%4-88-<;R4u$o-^;}NV zPDy4Uoq8Gk7B^YVNRwWOw*_y{IdM_?t_B2<%8Sye-FrP&8Ln$rJkhqatfH$l@wBAMhx6BlwezL0YRa#? znPZ~1s$1Z=pi_(^0mEq_-$~Ui@Nc}Cq#4~s%OA4f05t;?BsQ$Gj<-l*0AG}OUkJj} z_4ddRaOMTxfF1GavaF{lX5Sj1ht&X)Vas}G8jIDqplet(P{!)a zmHSrSt)SXi9jQJ5>`noUI_Mo2P=#Xh<-^+OI!hB(N8(AR@{UhR9sH{5{qY)7M%XwcU$U4ylRVp_WL zjVnvnP+G~ohq3paIS^h3TiqmGZxBv+1x;un*zP8gr42{$imyr_aK;7%z$|lb>#Q@@ zW556JV?Mtzyu8z@;b~x%w-?KRD?qwS)^y+vpXU0#_XKfBZStyMxjO@o5uUy~dz3T? z*aJg+SYr9BR>IBz<=;ZkqPkHpwA{_vHCjN`0_kZkg3nmq?>#;EG^gRU{D619Z3el7U5;O_;0FZkbq|6O=Rufqyd4$wYv;PSvF zfm5f0N)yzY?b6aU_Qf#kOIH%I_fF5qs9!6S8c$0R`8pA;03=-T6@N3o_j+(cDaF$~P;(I`$(o3HlXX!0)k^AV zq>TtraY?xkFOGkNv3pj@;5auHiYn&u>az_vXT9{Gaj|G;6q)O#6652mmi1sr*&~%z zUveQ`(imgf`G!_0bz!Syh)yy%Bu?XyA~cEs9fNbXN>d6HdQxH?gmy{8X8hqo+N#p0 zf#o>@6drw^Fw#M9Udw`Vhi<{NJy!cA8$pCiRvKpTTEA`y(&G+1#p}{72@xR+@3+h; z*Dg5?``!@mgwp!G?frX}#u2(LcTW`(Kaq5{9L_AZ(mLxU;NQ_KfSCCbC=%ZWo)0|? zI^}#a5jwys_|7NaW|1aZ=X|66Ce~Fg0-l!Mv#2x|Sj6$4-xXQ6*r=+~fQ*eA`gBm-jQf=dMQTh=$4PZ0k%n}!2mQ)X#C3TWu z5?yJa>kM+KrAd%Wcz8;JeWWF>WamPHYV)jfmn4*FM0*O%#1Yi77j1l zxv)mN(>mz=br86D-_slcX1{ksGtnT2?`Kg2xUf%^NcBEq36A%I9O5A$_6SB1UbB<1 z3&g=5*$FPJ{}60^5qh-l5YiUiT(}TzMRn^<_zdB1@m5^7$wZ$+bvPFZH{GD~&&7gJ zc5kLR3+g94g-i)@!XA3$aFLZ6#nX<*EVHCBRx}ogKf#`B)FCm7Jsdh{>m7$f2kk-d z9dMi;5I(;*4ZkH^xc8y(C!GwC77#ymsZca^mcs08>@zMi3GYtLu#ap1K$hJ`n{mbp zYpnBq49>P@ykTnz?RT z^8oP8bKHnq>qffmZmfILO{IP1rqf#8I-sNe9+FNGEfX18YeUeR2(l7NULh14v*Srz z7>{|ngeZ1rN)+f-S=dF&g;$K@z`Ul}_>8)`akg5`SMR@qoEkic}I z#N0y)rh=qJYEA?G(7dXNSIa>k0XV@6pg}Xg%^r4@VCOjqRG);NRLCO zZY()sQozB4#4|#mC^5wiI+V!sZ%91w8Wa#IJe>C54>GpJCX(kfVFEwZ{tZY5k+@RI z;PFnPOnTHO1NjINUk0775&+9K4tQS#fRc@eg^g$P3AQ=E5o4 zNWlAf|0R%bGSEIP?g*lEe}}4>7CT!2CK|F`U@dFFHD+tj+c5Z_9*u<_RYNI8{F@}> zFM)t51~@-fZh%_;8l;mI=Y!rP;gw zx1_o_r4iP{$Dn})@a%7)wiBZFA&ChPCOd4J-eztJD-XLbyyBvilOh78ibBV;-Bk}dD5a- zC(fk=y)C4;pZFucy*TYxLBhLsCXrNXtH%jcBO9hI<_r0$S>^4=Jo>16ow49^QTI5H zd2~@zou7CNbVq|yU(wzvyRU@`u=$0egP{V7yA++rJlRot=P|p-5Y_D}6fr~90WkJa z0_ns*T%UM~fEQfe9_Hb~3VYG)1^$=)alH;Z3x|iCJ?42NYJtDjLnI4$d||Jn@cRa& zUEf(KQcR)9FzxO_k!9N8U&WkuAL&E(rZdMp&qZZI$5uv-f&a&%G_KTM$71{Y4TZhj z;#T)DPi9nBuCY<)As6yIv>uvW`98!v z9;I~ck(IPSHy4vCNsVab-yp>XDb|0dpp_)WvG`?3sg9yrQlZ`V?V-%I?oT|Az<6Ih zcg#}-Q?R!tOuR_X0w(JFnjiVME%PO&t_k46w(Q^u6iWEGmI9z*g5zN=_B;6PzaH~E z8fEWYdoYZL#tWk~N{>PrmBH@K5EbF+Em4}|*QjtLP6)g$rGg=VlERrL=X(nCS$mww zL`48lk+MSMl(Aw&l-Ws|ifdtXwC=bm;=D%jQ8%qno;?cYQ5=ws+l!BSFe|z4Ekt8T zPR6OXl>(`aCvGn$)iW?%PnE?2SM-!6qGb!eo&T_#RVuq#xf(EiNz*+%$});a*WFuq zj;FHfPF<-Gvz1@DD@47r#T`-4P5Qn;ZzIk8?mpRYLE?5{!D_)flT3-im*uhcEN6m; zi5lCnwJ7U6!4)!Issq>UEJ{Bg1|7q7d%9Ux2fQ*ZeAbfL)wM#V!?~oR2vGVc_#>UH z2UD?y$4y6Cf(d9$oT!XSa!uwz>awFG`O60U`nPbb)1F{{2lNWD?e5>?B`rAjiW`P+ z=NVy3F$0!8=)bUxjF3&!`1S=2(%mv51CMm~{R!Fgi`1;8Z*98XKyTe&>gx zaM#;Xnqh*TYnMYP6?iHY;7Elyp2ZXOHp2gGFD`HsU$%97F)1$Fsc;=mA~ndil8S*} z*okxKcTT`a$FrB*vp+y=Ik@TIP-`#<^{dkP@fpc2q<)>KveU0XfD|O4)Z3<9peBO+ zQaRMA?~3#`&H1=qw17-uTuYJW5zY2uGEGd!_)r(m$+O#j@Sw14&CnzpG{-#3sI*^( zz8L6sn8$$MbK{)^qsoeETa=!BituaOS`3=U3hlsb`f6KZq}ZhG#oxL+K?;c{e&Z(1 zQ-FY9y7ijVZan@IPgvOZ4KDYOuu3o+>EV>Hh9zxW3&-j`Mgzu|?26L-s$9wz)87&_rLr1{Ma8`{E) zPOWTqi=&~nq0gNvj$p!cDgF&1Xvsp*q6oC8EGN4kKPFt9KGIGoi%tEfe=h|f#{&eg z6Tn=m(*5GT1lpp~-qzBJUS>sGXcp5n1T%(?GC5;ULf+)o@jvhn!2cX~La(C& zyMUnYq;fkN7Pt#;%Bh4dDr#!)yn{VZ2if+>_NMHX!+{2es=edR=0U)(g&lBcos)`G zEy68**36tD|L+N@Ar-6DGs9Ul%UCUw`u#*fnE- zmD*nX{hc1)v%UD<-wk|J$SfxNs$`DsMb9Sjaz2VrYSF*l3LZt$x^@fXMm{;T`l>qdzCCY1M~He)HPi%P@XyVvg#;%7~=8!UA9H?(jatv1|H zgui<|bM=uM--hxs9St{_)p&vf;uRhldr{g2hJm{d&A6rtXT*TC4Adwad9@g_-<(9&Im$(SuR3#}F}>*q&_N!G~#)j+O9_jQF**j^D&zamNnzBZGVWx@t9d zLjlcx6Y4h8f&6s;p&P~Fj}+p`?4-l6*Qfd_bjm#_AI;+BH0bl>dQgWBGh3}HJg|8)PpwC zCv2OO751R7(@k^|l|JEzId{*W0%mz6mm09W+ihBsQ-3JbKdKFD!1C>AXq*|?g~Wx& zamfGjcy%#hjMj&&F_0KM9=w*{7zN5I{i;}T0BEPL6pA(^+J%SiPr-i*&)=U&VV|(` z{v7)Xpy=_ZC~Ywp^mYK{ujs%NPX`(CSBVin07i=u6M$$ZtOp}@G^s#^PO-rtW)H!o4pk%4g_qBkbey)H z{NuX|$$u`R?{iK}v(_Skey6vv3Wd^x&3Rw&)#j04LS=n!RTx1P75%zofKNF32U z?6KXqQ-M_BrXIbmYCLdN5V3hLo)^5fguq*y$U=b`(S9i+p41 z!7vttkx2Z@Is{NF2r^q3AVh8gOU;NTA5*89oTC4u9ltkI0$EYZ^Oay#0`8f)i2e3~ z|F|9G+YS+T%>x@AaHHmfFa_L2aCUG9!IeIU*a!Ys!T+x0|1TVXhAHTz45k(=$k)+z zgaxOCg`E|>&s7J#_Dh4ZkaEa(nN(0ft1V(&NVl?tC^1VUtAA?!hy{_NgIE~c(b*S!B zHFO;fk}(?S@e?&zS78@XIK=^Q4UG69U_qo*30ROU0pou>6pt7XzroZP_Lwy7K<}lR z$)*GL#Iyj@V!Wp;c2#WCRG9zR>VlgwG^LU6MPm*~YGA$h4vujn5WrOO8GN`0htr}I z{5vc(Mhug%!6?qCVe;%QcMkM!VF(I;tr-rc$VPE_jXoZlRBbY$n~&Fkc*Blv+G;LJ zZylP;e`1PreFr5T4vpubn$#vuNCBN}OR%Pa9Y9*)e$#LlffGxYy9toNlr1LcH4Fll zfJmnGrnv_E9e5{(Rfg?3|8RFmNJUusV;~Tr#pWOo4*D%7qewyj+T8?r>7mBP)S$F+ zys?ukv0B&%$*MR4?kKpQ0IPqBMX7f%9%WB*J(YBqQ~u^FrDe9Snl|&XJj>A{9yXsn z0f&ylxn6w2yuMesdtQ`1ryK}6&`;UjE`Xkv@Y^_NwUNo}XqX}C4C}i_j_GwV6UZ#= zGyT*K6TDacx1hIofDBVbpS?m%haU{ex10pwmu#<004q;0GX$2)L3)1*!bm*nkZq^M zS;0H#(Ke8DJGVXPJs!&55Xycalzl&BU#BpNdmSv`;s*{|-1P6FM?(!8>FrlY^>2jo zZ-X4^|IYDID2Ic7DU@SFD93t-{Np$PL1IwGGaA_z8Q`cekipCC5O|Fg03E@yP=Uvx zz)~ltol-h7O}=-~dvp*A?3KL%ng~(=@;?*Gk5)Wzg>0PnLjGADUpFLYPj4q(Du-{2 zv!d5oO^dF<^&qx84WXX~Gc9#RQ(YOB?WTKN7p3SXnf+ zcgv@M&aniYhmd*dz=_|7mTdBXSid4E(nZi+zL(MrrH>m}%!R0vilFzUX0pl>=|sKK zHJ(Q>=8a%XO^cfcUo>5Eo(AG5Cig!z$JhtJ_DFc`_aWluC%~?1z%D|IJoLQmYXm-= zC6=gil+L!Op`*L}k)@oK7WexjET~>hPPClxX=aVumT9F#E1br%j&v($BLb~KujW{O zb0vt0F9U{dhI%`}UlrQVnR3pCMQu>{?Lkg=7Zjt(0c#*qKBa}Ts%?Xyd&AmDj{*Aht;KItR}zVFfCq#jl@j&8L-Zx zlVdw#rY+(1(DfyLs!qe(cwO&N(0&+bN*MGu4?G4kyL7m0w7_rRS)lZ)q5B^;RrLOv zCz}TREBNhzvn^yaWF%{#Bd>xFBDv5=-V=U(NJDuffq6IwM+kR4JSjdMwq1r#IltI6 z=xy^e1XOwIPS^p3jSp)g=LLRsTWly*4PZDeeE#rVi3s$tAo;^y|8KA8UM=Bc8WJ0Jnvz>qz^E}j$_z%Tg0LtT z#|hsqnxM7AoZNEBKyEZ0%It@mCXb2^~yAy}_Y8$!NfPBZxHlP;+BH(ip(6 z@7DpZJ_JYTLje{?wVV>>Jd%Q&g{R^Fz~MI@kx}+ff_ql!LCFV|qdjol>Am2P0bg}9 z5ws#rf&q({plXti#eabUknwO3Iu{CMLFjCd@gyUxAyf+%e{QL6Tn|$C2bVA&HHcWj zxG<;#LP>rO1gX{J`>7z%Z_P-vXDP>Pgm~MmvF0VQ0DQ_BR`|LJNGqUX*MmHSxe&gJ z*3-@eaCp4O9R~3VaKc-*iFlT9#{=xpjRHG2&Ym5 z_Lzs3BnkgoV#Mo(l*e@8J5GS3y53NKe1srW(Rr|NuW!27ySV4vEOb8mlv4Q05U+%izl2e(Oc40!Se`2QDJ zD@hd_Y>~W!*F0je88vTNZP3&uDF0LzUL*LPnnryvD3mNur?w0V%a@O)-VF#lm**ra zA49BX1!8AC4df62emKv9sCNmEK*MvXU+7vs79SMiSJXV%(EoXeRDNvmFj1+<4!KD& zBEOB|qgOdWryMO>BWBmOORJ`Dsr^UoYS*k)^2stiy7`lX@XquP1(T}E&Hxdc>ZJ90 zCk8^K#gS!0;@o~gz0zcV3UmT)kba9b8MZB}kk}KrCLe|qsj~;a*ZhLVfBqiN0u68jZ&9qB4 zL#4?zX9oZF=N;8(a9&$h6$(zfZ@O(21hYC(xcHi*Y; z`i&~v$c^g4BR(L<5-z=hb6Xnf8U)kc7C-^5=G8YFlnt9qYM1ua7>Jd-AfF0@&Hzs$ zDwz@W1nD35e{M=_pUw~1y*}TN73-ehcka(km(N{!MI}+KIA`I~i49nix5hW%++Sa) zYarEZ3N`YxTfZ^6aBK~94mx_sspF}#?=&T_VAJ|Pc3%f1%ZG*i;1c6aW$q5Jnz`nP z`Neos5en~h)c2X-2IMymV#L406gk#e-&bRw=UgVLWzP!>pB#Q~O#FL~qO@gjQxl19 z$5}97i?tq+78wM`HfgazcuIt;yhuC`UzLz@6>xlmG#Avb`Np7k=@-JGC-0{Z1{wwB zG7WxT&@YQuas8lf&~g0x(mWt_J%hsRWn(GaFKk%m6pW)2ghP+3RPzV#*b+LVhg6`K z$$UJMdNd&1|9JA~`$N`i`oSA;WB8hjXsbg_LS3bS4buGSzk#J^(h0%2)L_>GXBPCL z!8^Adwn_Jg7X1B&KDahU(*76_Vd;}wgyen(To4Jv0@4kcWxot_Ow6*KQnll#BsW;~ z`7Kr*63$AStCt=Ar^Flr`WHdDjgbF^<)4xKFF<~zIU;FWUu}3VdUKS2bAL?3wj#=j z>JFO{+J$?c7-1ip^A!>ixNU?o-!#1~F$QvNcStz$;pX=qo7k}RA=B*lHXregw&I+a zhBr;`ZJ>SuK{UN*10Mg4oAGQ${oXTV3xm6eMjqb{+Zczn`y{#bM@dz^Nn*(TM=oZ` zmSU9tw)1CqL4E5|)8_S?V)a%lt8 zH-E*RMbVa1SBK>>ea2bqrRnQVO66c!JKHpwk0`_9tbRg64Z;->a`z98czAljyJ+B3 z_k)ET7>G;;a%?ZqOT9q8M1ZF3vatKFBkhKM8^}}k4c^WHicr7zKz};qzh{8l*t-n5 zs~aPDCS4CZ9ukw%>D19^__TC5@JIO&$amxU8xP`KS2dNh-87TQ$kd_MGE z(Z5U_fxKDqNO`3G8S%TB-g;jWp;D^3s80H{6^nxD;vD{tM;&VnO!>T^qnR}RQ|u^wfo zbgW<1*nKi8@jMbo3oXy-(lY_9Qu8v92Ht`(hB03FXPI8N*!aRBa%VFOZh9dR4+>$c z(=jFFuFkOgyqiFkjl`=1WL|Q7mqA_y=CMJzfDB}7zxUbxA+nV~1B`+|Jq?_I_{*S- zuL4yvdYFjV6>1mrQk!Samhs?pmOl ziLC1QU|0#g5s%VGfYA>PhI7GOvlVXDK?Own%!1v?Jzog@t3hEaj9POSt`z31d4QVX z7d~CH4qp|i-qgYKZNyyWvzyy1HzMQ*WgB>d+l9e`~C9mw)%c= zj8Dk2o3JP>vnS#wg-v!19uN-LGpPIE9+REN1wx8LL&f_Alf#Ikg!PUw__DCik%(i2 zZynQck1)I@1E&j9YewR&!UHu66BmM5FyQ?TsIBVeT|hG-u@Vplr3Snwgflg(@h+ia zoeu5kk}l-1-$nKX?}V=-hxtP*1fjvF#5g1@9Q-7 zjeH!a`X1_tX(D&N;p*5}^#%Mf5j?h%TehH~+io+$W`Jdc@|)sBI=IX(TTGPu$@_9NTG3+2#G1lUo0cUa-c0y-WZWbw(8>GK@)UL5?F`=63}JbgIHIvwor z)deuIKF$u;+h@Q!@wbWT5$ ztn47to%0*DqR_v7n7tELiVWaHEKJplFkR-2_w`ToNPfwB+5`Oj4JL z6sm3}HzWmTZIZBfW1hVzkWz~Cp0p0LeJw>elAF>2KbH(-bsG3wxQo8SHdBq;;%(!b z-ZRDh5^u|BdOsny^qO1Ehx4Ml)Te2rkLH` z4BlbA?vj-fJTmzATZbMmKtN`RQ)-N%tKN|yxHi}Cw4pS7_fD(M7F%BjycoJbcDI1H zU;ri!Qfq8sg*&ZgTamRDw71=Eq4MQ>@P6Tqmoq58PiTEvjV}u4ULGH3g2z{a*CxR` z0zJhF5T0-4lWZXZSq_(OeBK*AgOQNIc+0MOyjSu*IY7uM$*Ue1Rd2TGt?O+|t@39j zZ{7eQl!2=aEi_=67ZWvbuJb$)Jg`ia$@iTb2{P%{cjA*uMwJorroe;nwE$X3R2Sa@ zCyaS@SqZFw3vfQjH9#tig!c=4-iiKg(t|3bOUc-?IJ!L_Mi@8XsE0T!%KqAU=?T46 z_vBJ*t6L7U>GKZw-LRg+&XlG8(15vP%M|O}k=RqIO}<>ndg1W{s%-!SKW;>l=DGamP_0|X*vDA6o3XLH+k&)W` z1B6JI_V{HUmYL6=sSoQ`pz~L$nAfe*pmT`eez0cR-Zdo@W?J><0tp|h_f5~Vm062z z3K1(No6S~IdV`<*KkGkY+Uoq+!&2h`qrBcZgPVx`MfiTuXDYkt>C{p%ip6xMbt&lp zn6Y4ZbOSnI_|k0-iGmW$ChK`OscN=g6N1z)a7hxSPwllG9M6-AyW<0jQmD3*c8faY}vVyzXz!CYF=Scl(nkwU@DwC zehzZy3!Yc!;ztF`YuRZP0}8OFP{Cml@bIum5^$hT^%SY-7M%CG>68BtCi+X^l6BM}xlYsMz?D zjgV52{0JKwH%AyRjKf*NLSe>(p%(~@KtUay3?{~Zcg~0ZpPcv;i zaJb|;ej;Zh`rbY4$TN+K1Nh@P60;P&G3b354k~#E+{okcc92NlroaN;$&wJZ?f#7S zfj(s$W$;7}h@Zi@`=XyvNnY>$aF4U#1+s$3t{(8t7dCFY3;!y7xh*zvnRG#7Ixk$M zbZ~1J=7JbcAbny75*G=7ZqwiyLi8Jn*eqnfk&*mn(*X|~@x)c;e~_5||0owyOIN>9 zVtkw`m;u)`}!&}j}OTjH<^^@P&Sy} z34ebx#qM)#NLUEXVeTCsWp_Fu-+dR{R8#O@r28n-C~kG^?vB9F;bQ3OARf&{)Cash zia>0%u?rUr3(#V%iG?m>Ostrw)3u-z`q5$LmC#+tDJlZ0=)x{sI4pn$KP)0SL){%u zo&K;0*>4_qu>AYo!x&>1ZG6l9jfYblHfsHf{_-w5g7YhSv0vVkWcCq=l_Ch&2Yg`5 zO}e5Cs6$;~1H+&TlwW=`Jk$-=6TI6Y);ekd6fZdTdMI{b;ZSFMqH?G+1t>6V@KxxH zo%9=km-qPTSBoAyN98XpG)y_?(SiDx9L0nL;n6Vvz!mrAMR$Ug%F4R3a=JA z;xVR}0a{O?(L->BNv7M4WQsL@y61HxHs68S;UOqY4398($<5I8t#?d}pXvoz*a7s= zeEzu8@0hZo`KrRY#Eme^-dl>mh+M#l0(oFq&!*b|2As$rae9*}?i_XR!ou$p_%6if zyT=lfE4Q4#bVbceS1d&zpKj`=*u~uu!*Ko{H_vy0tYjPPR4%uZU+tzQFD%S)8+fIg zAc@`N261N#5u2(SO`Nja@0|n8HoWr2f%R>k-+N!6kn?*jK=zRDQ}6~HP<5e4=imti z4vAm*?k{2 zLL=||k(UgI-uaseH=4=wX)1UZ55YTmduM8URqzcgz`x%G)b=_;G0=4|yC-kOk=M|W z6^Z%qS{b$uHIQ?RoV8z&;XsP|zfxk3fqDEfIC*t;xKa{XT^yCZt)-$Dbk+a|bMi1f zp?H<;8W5V1Qy7V*P#_0vm~XjY^d6|L5Aurpj;~k9T>tsLbexnYE_e;YlM)27NQEBM zS;WQ!8^dcYU-g8`Vr5ytGBh;e4Txva<-Jh{5To?=_WE0*L@=G@Wu%>5LN^)=(vW@8n}h zgG>BwvywrD;BY$TNe&uvkaYbq{J+xS)fq?+cft#9kUlctfP?qT206U`!2(MjdrStg z5w~M0;o{DCJ3vuOKvxZyWooD7O*8ja!=0kqDLIy0c&^WpPxskl>AtnI>L|hL_YV5T zLJfh?zvRQ*El?^UF6)U~-ll;}%UdRs3#F3ShJn#=EN4A(%X?rTtpr}O49NIY@Y#S4 zbc4fOX=0Glg5iWxSXLJ?e{_*~zbU^Zi#GwT9t5F^wdrBldOjH-Rc#!Iv_zL>!6He3 z>edZlO>9ZPn=(LYV!%&?XOIX_dU+t=-8vwF=C3vnkNy%QAIOL*QK#^aI<5UfI9NUh z$G|%um1crBoM<;zE+iA&4k%6~%Pg{zh!$3Z;Vm78inlVFTiyqoNt&t?brK~EF1h8M z1xtr~BQ4f2aFyYfw`_pahO|2ulIsj4jk=w8%D?kcWud|oZbvZbL+4m*I~mU<{cMi}+!1(EA-+HOL1c zN(|!%782M*P#9OjdomwFF2aO@F$0+64|S(O7tbBVr19CUFpe&mg}nT^j@_wlxb!c4dJ^@7GWfKJ5$n%-ujJroVrCDY|jMLOdmBG@;A zT>W)3;e3%!II{cb%%*s-{6Gj1pT6zOF+y*{w*tP24{x@h9pH!EPFKP=$sd0EJL0w< z8S;e_@7;Q=9^ObP%0O%y_)2i4V-WlHXh0xv9&oQg+yMA8h@W!XJ^z2E&A{;%h*fof zYJu1kh#i3#Xexs)P`pu(fukA7uLWXVL*RlJAfMHEv)mFRMi$U4^yYx20*n#?5hhMP zWrli&rg{eHMy7_QriMwzsU{4Q6PBse^Tso92m&$4NDvT(vMUoAI5aaDIHVI8I3$xH z@>f$CIDC^JZ2gqfGX0X0N=Ij3)f9&RZ$fi`ebQ_Oj=($y4sRe`2%MNo1Y&L=mIY#Y zAf64Jq>?Oz=ywNB3;?YYW@v;k7;J%(AO|RCO%_|OW%#}VxV8s~K|=STv}&=wYBA8R zmrV>Dt&I#EhZ`XBr-AI{lM9ze1Bdv}F1KeqFqwCSJ7dP=&=tyzEt4x($nzcnCUSeA PNddqPWZhgJ&+GafcAdH3krQvbrws4KwI~Diz2U%h$YAQ*@0eFM zzZ5#{udL9EO4=f_(0Ld(e7HjA~eENxotLzc4m z3QJjS1$6`E#4j_Kbv_i&o5e%(?D4jEelH$ukLOkJp9iDdj|SVPL2MD_(AX3!6zn&d zgXNgP_B%>L`P~ptg4irlRH!X4n8J{PmLMnFs?){Wj8IP}Dk!r^Q=~2>=2PknpUY5^ zSw_PkO!F=MXg+NxkoTL`!o%8V+c;|+ukG(HDCl?0jk5*QT1aQd*&=zZ2=7J5+(;XS zGN#CaeiVtx`+ie)By^w?P4nVyRDES}JimvYdE@?LxE4=c;6{bi!jg}*NDXl!gfs|I z8V!1qq7@SEwn9Ah0*mcU0=)BTRe*EitoNJmul;|-@8ke;mN-x{~}MOJ^%z-Wvg zA+hXaX#<{e&5bhtbXxiyYvpCpHmvV)qb#>m56=`l|LQh=R9Otbln6)ViHY)3vN|1W z!)!>)SmPW&G;VVgiLr}9P z>|?FvV!$}IRMnKg)3A#cC(@pL{nFezQ~(=vr`hj{wZ@jJXT{mdMObG`wYL3B=i`_% z+GDfOHfsxPW)A@McJ~uq$LVo&l+` ziV$l84?(EX#ioC#rAuJc1DVi98iX(3MC{jp#Tjf9>!dP5o$<{->e$st94p|^gyWjf zG-`npn(v0dHeqq84+E@>gf(mv5|KpyC;I_SB6|{PAl9-R7Nbrv;_jBp;>zObv#@^p z>|Hv>QzAKF{Uem1v{%hDt2P`p#cL zm=?VQj6T5Kou&Ut=W7CwpX-8tH{~(`K(#1b$!{UAZ1Q=bPFCP9A z;k`^3{}|FGTjOmsw2H(wNiIeWCtAZAkeFxpCqP0W8V2KoFE$6Tcz6JdPx)lxFA}2< zDIrx7{jy-yDUv)GACs^+-aqKh<(HsFH)>VGB%FZI4Tzi+j#w3>KZEcsgn9^V5RO2Y z9gSGaHpC7jkjX+R0dKM`AhVYD=RdSei}o=9@i|GuQT1fX2Wkwj|TQuD7JQ6nuL(1j$*9VxSsa^11q~%ELgs1SX=Njg5Q@AvkxDVl32DwPw2&w4K zdmBjl(15l(hnpKL@uS2f{n7csN@Vajvx9GD4qSDI)s=FgWl;8IBt}DtU%SF<3m_MX zZ^2Vnutoa-jLu%)a#?&1wN8pcY}OTTIm1P8-(5laKl>t|Lwbkq&py?b$Nsh%*8Y}0 zRrLi4y$PY}2d+~>bC9M(LMl8dA2w@^c~qB*Z-eDvl=8}C97^L{fyU>c-fA%nP3^{6 z(fr9)oQkIzOmijuZrr;iqS=F#cBAWi37GoN2zmd%`^0JnHU%28iDg_@~6x!k*D%u~|4ax&UVjp3&(s;X{u; zN){v<`pv?a=zS^80dJHrF(wW#5=vwAxKCIWGi}tH0j68SrSKj%CB7px#iZkhg$ps+ z_?QqmCKmgI^f6;+%nQtEW;_dIY0%HCKz=iv3OS!$iPYq`Ao0{79CPB|2Ss;&6AaU% z3YMA@NNZN-5xDY%En~FoM**Cs;5NC01JlN&>g_ih<%TF%`g+Dwf}q=gt--)+xQokI z^7@C7{@^ksE*9Kl=7yXb)-*3Dp~QBfAl8825LU(Nb3Yt@7S=FIYj>$Mlqe3Ow1ZBp zr`LYx4tUS_)7Kw>o&SSh4jUxXY2r(cBk|wDnOMu{dBZwbz0mSV{c!>BYkpxuDA`B>p)btdi+&ZuYLZv-3{6W22&t0iq+b^fwbwino@HNR{rfMI(h$yL zCxvD9xR6Fh_TUy?_$q!ZJ}J24Cy&a9rEhG&I;5qYacVnpJaQ%J99qBy)8 zYt=vzXAA<{te0!CMlMbsM0#8+*HVzq9u%HRcq-v9K1L6`0#~sWiL-qppyanGv`7>M zW#U-;cOfe=3nvLn5?A3B!dHpe%gjC*SJHqyHbv&+X`FgeHlXTz|1q=IWrNAe^)cK+ zk}IRe$KEymaSf-=BPCk=??4F?l+fKOVUnTos=LOo)o`j{i6j3h5$O{i7&`{n36GDR zvUHQ5a9!m5P=}(FtSe%940lgia@w}~vl6OT0IBVg*aOVD)nW_^V(G<#<|*79n2~0Q z;g&a#IgK>e-N?}I3WM|3;|zGO4WYDau1oGI+(Ot|KMSLhCfP3x$+&IJDAVcGaG@R* zhD8ngGT_}G_=g+mMoNA+bj^LW8HoB$hmH{U|0U|q8ej`J67ue#>|DjphOxGx)^#f4jNEi|}&CEa|!$vH%JGfQCO?V)@J*B?yJB& z$gGrI)ihtqQ8578bRW{|pCog6Rrp-9WYk7ryy$vkixTQRA!KP|v)scNXlAKd0dJQ1 zF1h6p+hBkF3QS1}%zqnD=8F&_4kC88utpo3`Wf`XHZkIwK}K8+Vb$O$tD09ghXa3@ zz^`pa8ijaG_)wb+`|Uez?3iL7-VZwm=C&*_ij--Pi*tQ~Ps?FJD9|mU7W#!(bveoF z{4JMR6BdtrMC8*yKmPFFz@?)6rqEfbyj=X3a7{N2#|r8Ci3}zF=o9YK=Tp`J;br|D zRFz%$UVi{ym->XqQtrT?3Gb(j5BX6S$7yWC-fP0Sl!>@q2uambt5S|nNDZfCAxubk zzc6k5Dk^(GI6R(Pm^IM7JPklRKm3z>t8|a57Y?Qvbi}P{`fTMs$%cl#zez|(Qjr{) zvth69bbiz4E9Ipb+)Kgycvy_;=8^QTz=GwsygwcewHMMfLP=WE_yf`jX`V4&E^j{} z%`qm(sdf#=h!09gqiTs3Bb0wSBlOV^T@^k|OO7cGbpI8LIeyJ*EKc;>R zO~JE-g!H+1NLZB~H~H%DTYn`&_9&1rNcqNK`D0LC-OzGb0!+StT517S$3#RfdsA2` z54_oBp(Q;ox??C8j&L^9<6?lbtA@GVCtOK?GBWRYG`9?oF8_Ve1SaOkqjZ$8CL?Pa zTS|LW6xN6Hf=O=)vxzNQPS5=WD+GnHCM5L*5?R*N-LzX$w?*Go-ZLwwx3PhdtRQR|8Hx!iD=}eR1a3IhAu$?lFeOl(>M061^!`@B1`BtaCSA{);EfX7p*MxO>bPZ&zTzoz4-0XdmtuA`|0; zzfOqK5veHd6fi#;ERF@Lu5M7nafHR+hk&NH1g=^!59JH4?}9?>2Od#y_m+8%P3 zOq0hKf{dRcVkXyy#U?5579D}{0Bs=HAfu666=k5X@Yu{}rOQ*Po0oMKk%2iQ7*oMa zs}XAxn`E0b<*RV-B3eWil#%QFqIyA6Uf~J<&3t z6SGMs(z0b3XB}Lma7E3|;)UNPW=zDr4u<+!Y{4ntyHj{; zTsZeYbJ(Vd!u`f6_cpXtZ2B;Mb>FkmD68U$(DN6oKQJqP9^=a0(50Z;D>e~*Q^gb7 zO=@cyKD)3tac^T|??ENo8B>P!Dt@PlhT(kW9?M;G=Wfs7vVlR0D-3x5B6y7YF-JQp zHZ7Ka@Z(8CK-StNSP^A`jC*66_3M(DOpBEa1*G)gpBOP z+|aO*>jR$Y#Xt`b5G4XOt`(u}0R~hh=6>`T(K|&c2HOcn3C8oAESuoykWX!=H|3Qs z!Alm7WpdidBnn3+s0!1|=uL|-)oY1X^A4!Cb0JxLJLhONIWRCjL%@7(!XOxIHtBmP z(7&w~SHaO2@b=zfaS(8m!4(nkz89c2MVE$Z=HdAZ_5BDG1iLNs=L~s`e*LD1GD^Dy zhn4J~^VW@m$B5R#Q4wv^ZK8P!&Qh$~5p15eeQ^shEFgyLUb6dHLIHFtU{fPGn=#-` z7_QjJ=pO1*L|3dE;m^>=sxrt9cpnB3LN%eK1O$uduvq$0Gy&mHpS%odZg)%OkcBxU zhZgC8pvk<6=FZCTj{$F|a4~0w{iVSX)ex+CZ+k!jDow3mI9;=4(?flmX$z^V4S3J_ zD>ki$=ZYtmC~o|y<*49k3#8>^=O~nt2Ymu_Qyk6b&Kgmp2E6o8H?MA>c`et)*Ax%y zv&t_>pE=Mt;LStJ#l(<{>-3L@_~rH+`5Xvd2MD?$ehc3b@J0;DJnL!MjaMI6cs@h= zLXwwS$a*yF;`ND>b>b{)ab>{kA6&UXF+nfRqF1iz1Vs;F`jK{YNxZFG#8HcFVR}%z z*+9iJeV#OWy1sw7!VIxVr{6K6bY*D$W=e0@KL(<@-voP~1)=>lI5@@PfHxa3MzBRj zXN*88YDkZU&<|-cWm#AHiqVa|k2BnAk;CM)J2A+3Y=}JJ-2v~1gZrcz*$+Rny6+5) zYsQE+v6L<@%0+B? z9%5HRTy-nfPeSbSTVWN%J0bj%gIGKHdlCxnlT>YqBBPXn(usDB5gkh8Og^sPNEDj- zb^486iZSi`r1i!$ZZB-E#S38zMlGI0Mnu*a8BxId%JA*-0q-7Q*WZ>NFj7JNf?Q0N z;|bYLYQiWdn(%`QrMq0;_Mzx+6Z=fzZ$3Gz#}d9(8rv4rO^bF~ZaC9%ruPgTDm;^? zw+Fnd2miYd0^WND-*^Az$@iWV-I|Rm0Qhw$%6Qd9I-n+uaiNL!{_0M##&1wxIuQI&IkHe)u$=NV`m;3Tf7T?WQKCxFW@XQtJ{HPSSyN z^z>qPX52q$sxt5;r z=xCe9s@oB5`UsRJ7__#V*XlQKa`!J zJ$y;GaW3Tkag_Aedvv}%*rEIA?ZwtTfYR*!7mw<8r~y*eN&^KP-D>HlKy&YaZrU%6 zP;p>ZO@1*D@IoNEqMfC?tl_|@?kuBw7?fzDdJq^2Kt1J1r6by(vp!cgmXG3NOj+S3 z@qGsfl-jLj3E{|KH;HwQ3R>B|$!fn<i7*4#LqzNm{{Waye~8cWfeLfuqKX^``J78 zb3aLWYtTfKSXTA2H2uv}fOwN=s`^RFT=O(cl1Qrn$owi(mVr}v#-c;5CVjGRiysM# zfF9KQQQhVEfcH!P%dqn)-6KFfpM})Z8{d=c57ZN?{`5N1h{iy<@}a`fp+r6HXKQMp z5FxeI5Z`G{G$XO7D&QRt%*}`{t3!d?ReYpv39HFj>_+1*NNtV_QpW)xul0W_CbyUO zaB+(ywh|O{#$=PENNC6UF=7CfO02O?iZmKrv>m#&8I-Q^K=FPVtb>lCMFuNeK+k=o z$Wj1qC&bMPs-4o4ic=L~?IhmFIS7hPl^sGe-MfVW|= z%Y8wC+D8B$?H&zmoE^9yQ|Ms5M93;R{m98j$m(s9tATu^av(x(3E3?dZDHjiV*gOA zZC_PZ-cu64$_nG&lfaMRv2L*xQc3yP>p5n$SKSK7A)RcB1+s;O=}uJlps#u`Q9G`O zmOp4svSEFh6k<0%V8#CMY&Exdqb-|ksB#ymYN$CG5rBggzI&~Lv_TUEIFZA%%s1b< z7#Lhd)Z%q<8>{6}?H8n3pRDdHimcuEGpG?MQ5mtij|O#QB{KCysJ?}FaqDW=O$F?+ zq&uTuu4p%xpx!XxG^YAgdOLZU4}2xAvo@o;X(a@@d@CuCWD9uHeU4zYRV>l*g?SRg zwzxK4f^H}(<3|7}&gXKIBj+`r`%?b);p%Dp9r5bIqvk`c6S!pGvr+-%t@RyB2zYn- zrfjb+d{1H>U6*v$CASu>-QM4RG#N+>pbD6i?=L0HX0F17O2c(1c(7RO-(^D@l_H z-S`w@LcS{DaBG_%ZR`C#52jKDA&MNUL3sz}d}Q7Q-&9SABY;7h6Y$mu`f2HSk1%^$ z*4XI*q$PvpLA<+cBa#VWvq=M$O=-d_(=_%Jq)jfl*%1hkxvdmJQ( zdjp9d zqv@6Fh^Eh8*+QTp!ysdmn)U&MsuR&;X3-I3Qs;u{bvGCj)(^Z0|Bna%9~*d~9L~tV z3t(>Oe++@L>rPPmSci9(QXI_ze-u$Jn!?SJEdgoGwqc#);ZN65k5gQml!+t!m`TjJ zcbRHA<5@4;XO}jZ3Plz3Xyvz!ID4~npJ|zBXB6q1r4rMl>sR+-$azaDYrE(|y2SCO zR9E8}DP`#y$%qqkw@8}EEmC--!cSqGvqzdypvWLKsvvbxikN#D>ingYV6ss{X>=!% zg#+F@S{=HI*%j7hZ+qSs+<> z8WHAD%AhxCXd#T+kuy4IZ~IibyDW!rtYRA-Z8Lxnj=)apuo&PRIU$vklD0(K!5eKA z@%+K-Kd;sGx6L~v{XG5$2*mt+#tsS7bqp3q>c(Dbv8^=cjMS|m|Gx$QF9-jx2LHw2 zf4^qfJ2x=wtq4pBa*Y9PqD{=TNLOcBq;DZy&de*bNWaZe^O{_gcA~Xh1Zt$QNSbhq zq=I~PqF@$XnP4;wXbh#oggcY$DW$0;p}=?sa#BDtrFgwnC)&-re%LPk8_hZ~Kt)@s zbhItW8eT#ys9^5}b;_mTfcN^q;~Ik2LGKw@*ThsEc7#RY5JHcJAm(kvlGSw?)C%W; zWdn1TiG^@m7|thz60!45C}L#!b;B|wJF6Q4p|XVBG7t#0Rpp1H&GkrMbbaYkB%s>O zX8Z#&sbc}x?l9BmP%X|ud#}5}w4Q_a3ODb}z#2h2GbaBB$0OGH(s&!1fW+^BDx35O z4%FkpQ?$`Ba*EbN?0~cKsH3fqNDN=VUKUK5V`NmiNqkM%KJ)&t)lR10lncdXJ}P)- z&Q}yVn{Jp^TLh~q-EQo7M>e6Iw&3)&w$aXuvZ!`O3}?!Fs%fQ$@zfWBm685YVn^4Q z6h697+kL+eGwbiZf zLG<@QWt7{k0mQZe%}8hsT&3jYLZ2y%47MN^n}jI^6Y&~hMZuHm$injew;oe-l}+Eq zBkfp@zVX%*NPNmKNCkO!*EI*Os;rYijV|M6HQ@J=cw_(!*l9nuBF%_ukP%<ng3Qw#oRaDB3nT;Jp|CbeLy5Ugfo+YI5uK{^4Qf*zq9M|y&`NQUnAAaQp+d*Eq zX&G0Z7pUObJi^5nf+$3)>cJi(wWNY%X5=#A*%~pX;0q^Spq7MPp zJ8055P+$@hXy7WbEW3pjh3#S0#1yPLP(0{u7D|iW(Spkd=##LBLH>zBmBq>v$xZSP z=7V(|@1X@oTqca-#^Mgaz@>xP;%;tQWSjKpiou3IR-7;^T*LNrZ6>sb1F%acAwA3DN<=1YBt zuwHKiN>FvT#7sMFzVU;lsPAk|vB%w}1oJ<5Xpw+`UXobRg!Y0Z7<4U2q$T=xyX7y| zGj=d>o|kO(0w^X3*N;TS)>EETCF{hwl%VJ5!c5~y=eU~U%wGfvAE-?vxzt{d6O9km z-N~KgPI_i4tsSR42IUOrXoxk+Y0gs~z4A`yVULmSY78-ycc{TZEUK0AD<+qS4wmxE z?@)A~@?**$ybd?x3jxMq}URXVLRO=BFp{@{#ERc?vpo={nQVqJWnaJ z0IYS&4ETRUnc_<8cks!+YP(d@ui-y&pYmiVRW8!O5B)c0I`@^4^{dasp0oWwm~ zE)lEQ524%yWk;}_NnE=HI$wVf-aV=egLlZTZUs>JTTMgDX#GCO<%7A7)wgredgvH( z9sD*ojK5MzwWa|OBQMeV&F;gV@7LJck?IIt3W1KsJ~L2Nm3_zntW(NIANd(bM|l=I~Cn z$SU9MrRA(^GNegiLonA#~ zXs<#RE8&C{&GyM05j(%yJgM*-j;d?9R4!(Po^h9phR`6=XG~9bCU_X7p-U)A?>r4H5FAilxUQ}! zr8CTf6}av~g3?#rhYYmvH+!q0r+2MPk8=s^2v+@j4NoOT7aljCXuTPa#;L^+Wr8c0 z8{Lifmn41Ci1&Q$#&r)S{o9Sk|Lj(aDy6y==fWWicwmIx#Y`QZrh^mjCg3B9`#ey?F^*kv?D%``-;4*n{CjqIJqlJhMmJ~)$lL;U6hSIopgIO?7 zZ~fYXXjv_(p4n>D|8UrNMix?Yn~HIp*pJ7kbbv4iZVf~AzL*YRNZg1x@G_zpKo?Jhp$3CxtaK1d`DFhC1x zpowO8w*HE{2@YUdS(dT?lUYm^k7NGL{4@jrr-gk5;j=WYT31-07T z2Cd7Dvp?{J+QYtTbh^)Rc>E|JG_bX%JuhjDWS(MN^_;Am^#t;v+aTn{McyAiHox1e zpz~V6?T3I?#Y+O1589LBU>H zp?uPH{Dx-rQWx2lcCsf2E>jq#0ohox2AVX8sxWz{$!vw^rM(3>*|*c50Q;PACO6ON z!88)jH~?5SRBr})K4suQFUx}DFOf3eNsI%DO%4N~`(#lvV8C&`!BKc!Mfn@UdMHW- z3QvO=8A@{EVd9ZpJmQErY%YwF;xdgHz`i;%`rFDfMAfY#Ea-ubIO0VN+S21@$Mw%0 z-uS-8;=+TyvM?~B`)j(-0TDuWf;lz#09{;DOQ_@OSDf&6b$F|~abe>pvAf-5#PPuq z-yU$9C=Wa3u`g7T@o{iitfo5~Lo!M`LJY+n7cSG{oN*ldVmWRy=^)I*gmi(r0XvcQ z7dPp`cdH9WV_RdtJ53xD779wK5nR#ESb{5Rf|FosrJJftSbvWp)J4^iW6i?H^NPI~ zrYT_et{?p3cPpSg0nmY+fOM-$e|}`qz*8GYWz5=kH<{B^Em=Gx)UBrYgWp;GSMHNs zq1(cBa*N>qUUz)Iqa2o6F6yRoyBclog6ncBzK2rI>|b)MkF){n2tylTy)rl%kDG6F z*>4jXG8-vCItfvzDJBg?!J0kAIg1Qk@Ab0iWYL$vY|9D>O-y&;Iz!=DZu#%U+%)JE zJt*@~GCe=Kb)j~Bu>P;4YdRh%cR6Fc6mr5cRn^ByvB5#0r1$@# zMwEoWONIUEKJkYs%=3rJNByf%WSJg!{U2>lzj3W_<%vJIr-Sd$7m5t?Z}%J53Z6dk z$3KE)?{7DkvU+7I*1U1;&Xs$vsh-ySp@7^kp7sbs^9+$WR=W2KTDXRuHvXXqd*hlx zm@+?M)Z3tbe7k<`RaF=xUKf_mj~?~n`FY$D4%L*xc)u2^=EvUov9y`n$z5{C+-e`% zUa9#*4$%B#C4q+NLOy!1{tqr}c_E(0PB{*g_Nwb37|M?IA&20cuMSbai`Y3pUY&wx zelpezkqfltCqXkIc7k;f?8)FcRH$m&VUFgoOC7IjNn8&SZRSmvwB(;bL zWfT6sAR9j-Tv?!vwn9#S=XdTxZYrncDtStLR~UPD@;H;PZ-uq6Z|NUF(ZC43jt!6= zp$(&|#j>KWA>h3#2@l11&KXa4gQ+UODA{+q(MUB>p5k^*Al8cPLw)#d@Zqa_H$z^F*LJy zV0;5nha&?L4V#e$9I^wl-7;V+u7gC*h*Jk-b=qkv!{rYA762ro*0~E2`xglRgz&F> zgTWq5R4f{KffpmT1%hG;Vk;mtK-dC-6i&DgvE!i}1s&yrfClo#W~Ppa;EeEKcX|I) zpcan|$dcNwd#gwpZLo}|icezF(DiFo7cN7Mu!zXfh|yMoiasttYTGILf}7DkU2+rt zpDF2s|BWT0J24fs3zHb}af#6?b}J4Ayi_1FtKapzn>5`If)f%yt77VCk)~;2mp`t; zdX!3OwgWyG@ne{>bda1GaT++BsZIyqBS!pG>Hw|(L32_EQ-@N(b%EY)2QOVl0JNGg zoEr(vphB-rSRY+ka6O8qw2DJ${D)E^2-s(aInYjH07)&Kg=Ni%X%aS?#Jj7QydT{; z0Mx!=GWMscVnBUo5}&9t#6f4Oon~~svI?{sc69yGstb~)VG(!OJlgdo)Yt>V0LSvB zRVmHppvo=@u2-ajBSdQ95p#@-pogXBx(RB*;|#P<6~i#Upo?j{UR))sq4!g@7$_pn z`N<8(C2(c5*a2D)@Y)T4WMkNEHi>couOo=FB|)4Ss!-}gZbCQ8n&MiMIN7NPeL1CU zF8@jMJ}ykKFHT9!o&~3S1Ayyx!Qizj5Rq~A(od$NEP$@DJ*&Y9BwRwmP%tYHSk%e{`YCHuV%V~kz%h3LQuz-VJ z9V}1_1s-uK-XE=@#l(P&W3=+!a#*b|52bTt)$S#w!D_JZ(lTgn6_lRe^?74b)|?K~ z{L}Dkb(Z%#D`~NJcneqFe-=`ghR0d!ie|dTS!>MGT^FQ%^`t~mPgvL@4vbu`;gJeI z3@_#fv7-J zW@OF`^8R1)WV5?qKmL-}kq8Gk z0iFQ95de7@;@g0KA&h-MOT`WdrU!CxjfuIq3?mo3A#Z9&S6Mj-rw~YRZ4-&C4UOFZiG(O2t^Op;VR*m z2g|{uJlkf$&j^p(KEXc;lb6ngYZ==?Uj9yKU%J%r*8vP?0rj(H1tq@hJ7&J@qU*&L z!ZK{(Be)puz7>ooi8TRE3WTK(8SoO}`G>Sxo38}k6#IUCUjIS~7uA^1SZhvdT?^R2 z^jHfe&Jq6kP%gehperV&ya_XU(K>^nCQ!r=2=&V* zus;u+1G3(gAY58jQZeNHDL`DT8BZn}@;Yy&)sX%=fOPpB<4Kf9azoxT@MHuv*pT<* zTV;}<%t^4j@B|}R1{eykIJ5OtVbAhpd_ib{|9>8LEtgUDZvzL{ z8ybjuH4zs#b0#qUxPLYHmr9oKqgSmhJ3ey?@WFxF4 z`~w#MY^`kC0t$9A1!_=@VsTr5uqg6#pzN$9&q4tBA#hSUxKhJug}eFrMpct#MKnwT zL0hCUgGV`{+#C84m&HdfcI)j8|wtr~MOu2c9R4TJbb~LD;^cDDjse zB2dVk1>6BxXH$c>7-WH3-l= zmOJ-JOXi@gr7p&^FXTsQA6Q^!IUnPZHg~&WGD9L?cgI`rc6IF|^pb&UcT zf{|YL!t;$$kT$sVFC;)LcR@)Nw(CIHnu5fYQcMG3Ifn-i7bSI+z~tXOm<KaLRBOQG2K3vq>5zqY--2cWFPO4fhCddFp zqoG01$;-afnqY3)hexgejVxR6;*-g*xyL^WDrRx5F~c47!+9uh+Yfu6bdM2F1D9dr z4Y;U6VEJ)a1P{Qut%7511~oV=99f$*?&>hfNelb|w-v9tEWp-~t*{6E0TJ#vZL23f=#FuefNnX%lSN8yI60-t-Q?7zUv8G< zMw=nO)uzY7kJ2s&SrZw~4vDcDd8oaECjRT&M*P>e5wCac2}#%XV&hx8l)hbqQH}eG z5?o7#hIKLa*dVGS28r@z2lR6R9J^lw{)%|MkGTDV63X0t?!8@aJu5kL^Zx*erqfK`E4ns9%p~yW<0xKZ%*>>lkV1Jb0r*}x)oAb=XHD`sT?_LVEb#L zR_rcDX|FlIb60}b{8pZYyAN=!MW}pS&J20~@Ci>no;dfx*2D zco(!*7U#o$yKjZ*dPwem@IC2qMEz{Kt_Y^zbu`>C0~_|41MIEQ`^}loh8tD(h0fKY zTK2S1z9wd>D)z01QR*tN8^C=c#{%hrnbEd`)q>;T24M{tzTj=AW1qCp2+jb&8N#fA z-7eo0@cy$!cx%l)v~K9{f`5$`g8=ndoN6mvYe0Gp_qMbcCikNufqQHMwR}i;;xT6w z85y~&F}H!`*@hu+tR%22b<`@qkh#)C&GHL>U761edUp*Ahga^VrVR+wA63T(t`hNl zD?f^JaN6Zo-lToi#=|~M8WbLVG!s89?0spD}?^YppGSIOYj^*OH6#yRSntZ~JRTJ=0p?Ou6{kMU?2PL@`!^erCQC9CJ)yPSr zZRc8>95SFl=|t2aWg( z{qkutV7|U{5akd3jb-ZcSE|j_2Me6-B1o-!Rpz@4d}1Z=|Cw`L z^VVyo(iyWse?^I-sjL}qrWfC;U~w&!9+;@m7=WEWDKVN_M~x)c)UK&^YttvW6cchu zInBNz;mGPld$SX1YKs2`S&6r*t6dQy9nm52#%gI{H!>V@V$C(k55JYqLd*jlebq^6 zeu4SWARhi7K+A(ypa>;+u|7pduHndlgCFvi4U~&i2%|3t@r&qYE!P)nzLQkD<-&JY zSo^8(u7uVNdLJ2Lxcp|gYp0MmLSf6Usg5`BQ_ zWkV~TWp3DumaIMakjnbmm54m0b%(_4E(D4)jSC8B;{Ah! zR~z<@3n+ru_%gXcuYBlT_Z)5kq`n$Za0h@b`v|zC-ynPo!PvB|ej6WFrqaG7-D_l^ zHk^EeJg7e22Z9TAN(W?MB=vcV2GiiNdr$_(R?Cr3{Xnf;qPWcIHRy4`==2MS0DCsGpi=moNG z5D@oPJs9bphoFWq76K}%EY3PU`^h@I@I%lqs9IP!D#x5eqPbaW+OnQpT-|BbpZx{} z47!f($OK3CdoWPG;hpska7_8!Uo54f%4R&{;QH6hvd(-M#RvY?;usX#eJ|t;df)a7 zrVWXAzuF?f7T>lW&rqDT@q^yy;g}*G8a{9D$z!N;Tm|2;$XKYl6Nwt%7>^2!6y(jI zcZ2_TqGl>TFQpx*1{LjC4ld@2&Y>#!e@AH8kcHnCE^L^OpAvGPS{ZZCkem}6fV=D3 zvc9SJj547Ui7CSIr}Q{Y_}5d(YzCozVqi!Zeku(kVf@qS_CaqYn47@}KSZV_Z{RmL z=|J8Nzztzwmj}JcgCp!R!3`4cI|&Rw+}>1L8E!E@mfH>HivYJ7dQgjY_6@!Rp z(!jW!*5@>t^TD|MsLfDCcgJrBt7}et6;b?D1IJD@OMf2@)t1oPu^}9cy>u0D<+&Cc z61$-(Vt;1Af2I4haP?^owhE&*PKMhxMH}y>`UZs8H*UrrLHo=rG9m;l5L%u|#unlH zGxy_kVcI4w^&Z@p+q4lk2wj^dhaU3DYxssi?+Hmrw41>PzH_q0W(jY2ojV+4wg>R+Wy&2@|Vgfuk#~TAFY_ zDDnK>M}U*7Y&ifY27(L2;5Crq2UXsgs;BYm!pzNjKy$_BV#BEbZyQze#T7~h-UXn} zBCLvf-i=aZwnKakjQ(w*eY4hH&5h=gxkX)3&2YIIq$hAgK9AogYQm4n zC0a1D)$m3j7+8iTP6d{9nr(77anXBqNY$`f443t}sR`iPvOD+uEa>GJT)?eA9^%Oa zNrAK{OQJh90J|`J!F^6rXZJQF+U9UyN$LW)o(^Lew0nOUfZMq=xe@)atzxPEp|_<% z$7fgM`f&YLaG`jk0i{m2fj~#(*yp~IMi*Rg&q`tZ@_ojvfAj z1_(hM%i+CnA;8ZhMRn1K@qXf=ddDD>6w(FOxRlQAI`Bp`!&frST(L9DJHbKqH`paI zz*Ih5?Fe|Ap(04IFoKn!S0W9OTU^8=VGgK04+rsba68UD2sQuVPlG%e=Z9NBwWjal0=aB5?XljpaNp@oVf)qu zxD5BsRy|G?zS^2V{V*h4+B!#ZxP@$rmBNf|Gb3jXfeuVVF7wIZ%I$!6vhe)2Z2N)$ z(u0%nlW>(a^@f{Vd=;CbK{Ae>MUA7!>-aD}p*hTEwTUfJd}D(E{_-&!j}%Gg?&g1x zP}`X+D0N0N*37q!c~Wmnelnh`0A07iHs6-?q~xB@2mXy(PePldUE=Li!)F@F)fMv0 zz_VVM@vH$S2rHho<4EDkvy8kL0tP51L2+9Lc9Q{}vxzdKL8Pp`7Th=IO$b zR76=iERh91RW~8}QQdp^m(2%zG5vNg&Ai#m;61i$E?FsAM$>&qY$LKn(AP^)?vR1< zIsz2Z)`nU>l|$q3)LNUKk8Y>~Lo+&G*+L+?JgA2|lC^vlA6i&zv+$g)4a~2-aJUGw zc1#DEZ~Kn)1ja{%W?VCcJJ`!oyUjaV+v1VNREWeY!go8eBRfI49=JNy3LftkIe66U z5tKXQ>nfU{(VKDsE;btN?zcO};_$emqD% zZUEjrWFv0LfIf*eMZBhwrViq9jZc|^7*0&{;74%+QgY;MZ5g3WzgY=EL z*fPR>b;5Zpw`&KyM|~y$;k$u-(tRqVPfkC$EDC(X{NCol>IQgcLs?%q7fAO32o(TA zn_CXEJKz=IX6kA&RQ@OY)AFmqg+9})L?#HH9dOKkT|13X{P97>3UT{l%aj_{%9g_C zQFM!KlJ_G?Zk?jgDK+unY{Qzo-pwBe<|)u<_$o@|E>P}3TnT$Lf-6djk+4$Lur}dm z@bIZ@8SpM0z9E$Fim_J#%~W#QW^w~mD))QSPe(QTy-QLt2z}36 zs85@P{1-~_D?-%^36m@qq_M)KMY1?5n+ic2M)7b{%KCdOTXNA)6)DOzYQQjE)Qe%2 zcKVDqP{s(Z7Z%|;g5kxi)G0#>a3)p3VdD3`2t>!$fWdE%J%mI_qHEJR_K@E@UU=q3 zD|KZ+`1-{}s&hcN{Ng;S9wfHibAVbszxzWVgwysEg{<0x*clL33fuQ2$UY3F-rut- zay5J-!v}U2hEp}*{eG`S7{B)!{Jika-gL!!aKZC?XAA9nwF%2kBAw}aOe7K?JSjFk z$8W1A?r~#yG;zKVDNMu}LV*BgA2CoVICzc*;k^3V&`^_Qe{A#%;V04IaRr}4R>tm{@JEs*ciGRECxL*=kzbdz| zhb~0^h~amOLe5Q(LttQch_b48i%i!kdli*Gz0lMnH@)2(!Ju(t8-6q){pVMZB^!1* zxcD{){!M^F8FO6UBmfw90RR#ncicZbs11+sC+5NhxdPT7-nY}NIJZF^4uDW+iD~JI zV=MPn{K3Ws|F9V0S49HAg{&V*2Z|K8fS}GED2hYZ&w-ue?Ov8K^@N*R-8*4CC<}=V zg7xKO`$@;v_@%ux#u~s=)*&YVHtQWX;D^@u=$o&Yu#XZ6Q0GiW3mpz!5&TFI{xPIG zzz+-fVSH5oEgVgEh|fC+j&?Xka8w023W66L2J*AFh5nWf}otAlbJSK!_tC6omL$-;N^6 zC%=xMBztbDIs`COa&|`%ckX=;6{0PCvo{pC{s&9NJ-8UakWK=Y+;Mh*BYVQxlSP>T z#(0>f5EFP|C=U3k?d3&ZaHU-Q53$bs8;;ox*nb%ob^ke0EHkwy(9kA8guy1xr$d zfpEo&4zS?+G@xxH%5x;%c?!nvfo^U_vx)E zWg>h}jp1Ue&-8_%d-#O#n5Ryf4bE4#Pd;guxv(ZYRpv*!d-#~A3a*14$gFXiuVaXl zASTa=&Vt}G+qyXQp`GZ5})_?X1ID^;&WR< z7*q%Wr(uqiprHiGZ*Ru`M?QR`2J*w4Y)c5_f8uk%x%^3^9Ihp^AgH%A%i!(bZoQ?z zSdN5?wK4WQxC?}gQWIQMzRME)o?MPK2fms|->^s1H#W_$qXbw$M+PQ9?e~NK?+#$i zO>Z6CzRTlpdS4mJu)b<8aG@0PcK6VDIHvP#H@!QDQcK8p&tzN*#B#qL43ZJ9RJit` zv(}nJT-U&mDeowM5Y`+TUt~FA&Tq}+%&GL|Dk-K+5i7|3hDN#?f@j~2iCBtS-h z#bD%vIdlatmxEY-)B9#X=zcXLu9n|y4()(1Sw?L(%g@Qm_V88aU0^d+3HsOcxLzoJ zEfqHkt6oc<{0T^hOi)gI7cTQS2Z?OBT8v_RAV1g;KI$sm}vxpb`5> zIP==$c%?Aq^)3idy6sA;W4dto+?uVk`;~eCJhQsb~z%PS* zvNT;l>+^nbT4+0vi3@~l2X>a^H;o4TCQ~wg5x>VA?>zU&4sb`ny0nzGzRf69%lN50 z?5C(#gF3MJl5URNsYqj78erpJ3TPUxS%~P1bVA#kC+D44gUbkbr<0hz70WR~pTM&M zo=MEYa|^_wxAH^anUoK^^&EaH9u&it z3>?~d5S`O=Ahb4=7KMuc%$#huT+8rx1p@~NgBUZ0g@Iw^@?M&@YR3rRfpm3GYMd_@GrHMrs;=fLeh}DQRwZmA`jxp|jEgYA7~uebNDdc92S)}EDWCu&4Yodo}^wEb3i`^4L2ka%JUiJ?&M z$05{yS2RjSRt!JHA(Y(sA!4gaHa4D-P_DM$rZx53a!x>aWhoYLJ<_4R(>CH8`cB#& zE*5pCeMXmec(4QnHoUZCnZC28Kh-E1(a+Q_s%^DJ_*-iZwK+i!8gK?Q1UiJQbJRW zq8z#iO@(2m8v6}K=q?bhWxO4CKuIR`4G5jJO8v=YV&e>>NI~)bWCwI&1Q325=uDNm z4GLwKXw>26vyu{qs(`W6P*RyZ4jNG=Q(_*aN*{EbmFC0D4RekC2nIJF23JnvPeT03 zlMp^D%_fjB8vAXKKl^rEV}*q5kp!q9LIIH!AQb`)MnD4*|I;9pz15g#fO4~wsm7{8 zvS9V}^nvUHxE@bUbE0-+pvsGmsZj*Sp|upPm`Gtcfo z&`u|m`x)|o2LBxR=fLlVeA_&e_#U*@4e>u9{SWZ3fqyM`@;OO_0;DSu5`Tll-@xw& zzdu*mHZl`rLvtSa%h!XDA6FInujvm7%IGmxg4Sb7$Ckjd=Y`kM{kEspHQ}sqTSU!M zO(&X=mgN7|ytyyD=4cbc>AynatiyAf@RaLLl>V0;uzR(l1n@f#Yp*&{<`p~4Z#5N2 z>2~VBswyNvL<~y)t1o;b(%RI2^(i+!`9(Ffx2aEAqev=tKxIV!D-h$g(k8Dq*fdzw&8I=i(3JV#Pc{`U(>W-G+S)shn64Dyar^7Z%usA_WroZG1w$1hn>V`9gMZckL z24HwS2(fM8B3o=){ONL@;r;G1VNOt_a92)fSo5GWcvZN$WR(QCPMY^$JF)GcJt&pZaKVVxgJWB;Snt6w zRz|`c+k!+Sk>BUNLU-Y&>5iBx+>O$`j;cafXpudPIPldhk44!LM(l;lF>-s*>xfHnku%2Lpf4FU$;8SsR8Y6?6REW?KBjn^THEvG6(f#G5Itt_q7mo{Luz zrp5h(j5f!dW5K$Di+YO<(c+20^imb1FlMgkeJgbBZLlO3by*ghv3QR+4kqmK#KLbZ zq{}q1Pa;hcOqhmNk$7B^i|dBsOGBEFm~HjOK|mo2p4dQw&5y-*2C=x(BNG=(j5er< zREhP<0#&C-@_>Ip!eWef$eCkVgqi_*N`T%za38#f*yvFJHwb?P?i9Ga;0}ZP09;xW zV*55Cwj-V_B0$`owAe2zHQapGxKxd{Gce-w630`GWYad)AyyQsM!eg( z-dNSf@xNP;xK>CATV{P{kV(9=3(`eej>Jxgg?7EvG?$;kr^4dB2XPtXBJo)WMP9hS ziG)8IRCj0da{?v4m6*goFMPHF>0I`#KuXr&HD^eDF&|t4W#2+#B$W8ID|F`!$VK9A zh;;>8e0~t-H@30u5Ah|`9v+F<%&YD)h9Ax2Z9913-O4f6OVZG8aJCB)nvJ+l3F+~q zypnKBjd4_$(sCS8qSK#SBI8kNfy3YY66}>#VhEbjjWfe7hud)qo|0ymC#f6h-s;gu zT_|j#{{StL^0@wH^DarxE#PTx+!_k*qKDU1h( zV=XXnMD?C|@~hq@VN4e#KJWh?y5H`cEoGok7Y>cJd~LyZ1{(?_4RQhw5j=SZoRuI7 zL73c90vePS)xL$_!7F%_9L*Q=DovH17Uy`2_?M&_11;uz`S@8!Gk7XDkC*pu##me{ z$@#LL%`8gIx1(M*c(03P5Aw{k;}Y6k1jE;P8NM;Un8&%ZA%?v3^E(UT9EdBCn9w7Z zGY?trGmp&5a09FEm4K>AwcBY?>BaizR>lLWi| z4O$%bRP%TT#|OD^5G|hZ%*?ktSBVQz2mFShGfu5ADk1^jE$AXlk*^G4eU0%i2j(Ov z1~j3?qe68=LYU1@_KvberDgzi&I|h^64Lhh7`_%Z>_M+Ak+}dUBnrM%zN(FJC8I-T zx!3?Jg;Hqob)hd}`Y5t)w73<1DRGG~Ju-Q>Y>W=yE4(pAn^Wm~5%vg5?QkeLO58hyQXA}8ORxUP>34tQO?c44BIrVV-JU+5BNy zeb+6@;P|i}I*Ru0c9Q!=R;p}?hs8SWA>Bs|w*8?r_}yoY5G-O_s8Yd4YzoXbuM$>@Pi zA|vD7lp$P?Nx+W@A+dLi5I zEVnQxE)$;^)#~JIt_ly@SHt@nb?( zdq0E(10-A!7RQebS@NIwX`woPES@9mh@Ubg*Gq^za`7ku8_CfV&Cf1LN>%Vc88?pR zyCilubAFW=jYdv~8LdoKyI6*jg8boPW)rYBC#S9p^xH(;BM0(#5P z0Gfb$*4L$N=lVc{gG|26qNrxUioaJFW)$ zWm_2Wyq6LG1+K$8s#IlBwT70)S>i0KTM?%aR}2wiWSg3uu;{B1nv(1}cZ-}4pM~F; zXpxI;65av(1+bvRKZ?|Bl8fI-!elj%?-!m|FQEQDD0Hf`lZ@WBKUf16U;c_P)_)z_ z|8F3KQC>^%%oJ#4mXM~Iio1kmnu(0h{nC(7rzs>#ahtb~j`Ud4
      *7UU$pC`7dc`bhq5Cw&>1|;?Q z5n>J9Ewz&Bc+@>*Ju}C)EzmJz&wWOR3$1BcljS9w42T0ZM-@UCoV@Nf6h!Lf43T=K z4KLSp$xpAtB8_ne+%WBa_p9x|iE-)ki(XU>tUui(Pt$b51?0i5G=rlFYv18RJ+ym@ z@fcjTDLtcQzcml6A)6{*U24)anR8V6Vp|%2)kzO*TMd*&jzTAVmCjqwN-TT4Zxmrs zpkI1@Mc)jXUPD-xTf8YZ!kgNlDZ-nwMRtkFo6)2dDf&2sM%YqP-UKNFWd6_&VRjZD z0b+&2VkKM!swNd&1wMByth=(!f32zoT7MBZU*TWTVfpm>3-a)ekeTNsHm^$&+Hp=| z%4J*u@ck(wmYsrLusA4zUw*SWa0_!)ZKRi~meLI}ph*@fLeB~JO-QCJK4JZYSR5j} zJwdOAWl)l(NZr^dzlgMSF_RN)sWakjo}YT`|@G3g&GzaJ;sMq6r$V z5+8%yxBTSJhDB);>>$lZnAHI=H1(s^-+)iTaSCsTWnUP*b{VcZO0pGqM8 z%zD53pr6rHu3yrph^$;QLi`*%hBV;-{Xg5KmeI=p2Ze{$}NTM$wOMl1Y% z!b0mZzn<>{GV;K14;-pt2xwS9zb(MdAujW(2r@V(FMFmIw!;Ys`Q77v-4<07ZBg@G zmbyZpHshYmGL!;zaB!IzA9Q(*_NgGRtVqv)2doWQB=Gm(Nq%>NuTFYKFL#|nfu$2? z(%c>KlWVMy=y!)f=CmwDrWTTGAav0YT}nu6q>e5k0?slKgRn3@H3TG0QK_(FK;(&1 zHT}LNuwzmU8tu#4{;Eo?$k5u2lvews-#vNA0DE2m47eArEwRw={tPZ-f)(G70^)u& zkf8vBYojX&l^-#S;s3voG_;tYD2Vz@fWnakMVEL;S;U$8M-Y=N4-3mfXw=(iXWT&Z zXXN-CaHPVQ`f1kip%H-{96#<3zvKkS&M>WK;HD92PG=A|+R(tZr&ftPCfD4`VG?3o zX5@E2JiHwMva0VSy&3%N0IrenGkTabtV*0LZj`CtFi*R&^7%;79450fu4vdiaGQIl zbRUw&RvnUJtja@D92e$!$+uk^bDV7+)BKeyG;CaF*bSB~moh}u{$>th%W@I>A^0EP z@(U&*cFQgI2KWcSWkNo2`@wPRc?Hu!rBjYXIqDdDP`jQ;OSNmX>$?aUreOE3ulwj6Ig8yEPAT{b_Ks1%Qqc*?W=>6Sn4Ptz^z8hnt*_to?ZHO(z-L#~mpB zLkDS((v5YXiPrwg15gjiQ>Wj2=)m#b<7l+JtjC6Cwwv_;|0)hP%mgoKXaDf4PNcK; zmma`StLOmDFX>|%emdP`b5$-GPy|BcSbRQye2rPwD)>H~cr>8Rw#- zcp~lKMWuY)njf9iM6Kh;=8&Vp)43XaLfDb3wq`-wSqJ*AT##G)GY`z}k<-@xv;)?O z({GMDP`RGSJt^Jve(r##xu)W31HcB9qV1#N^J z`00vzeHpYWKk#pe(+3{vLC~iEa}47j`ux}x&H6cz>;9bd*l+!Oq)YMh+eie2Y^t^Y z+UM$*{mqJ!U_(-qv7dTUv+>s}AmD$}>Ofd(1v+k=_gDFX zj%P~~9+inG`lX1or-Kp0{AnQ<^;f(Y}rJix7S;aHTxA2JiS-dPoV^%y7Jx_6F6E z<8u|1A&2Me(s&~hmsk7U7lv+e$FFxPaEHf} z8@dMf#3kwbY7im@U6M|{zt?4!;rdR+V;w6>%6f|9&Pd8UxPL8Jvq%cAqC7!2vW?U> zRXbc4bdq5#U^p%0*{S-)o-H@x)#G|-`Gcj{OU(g2hXrfRS*21iz!#<86M*n+opn?I zI19aR!U=gBtfT$|*7Wsn0I52&XjNZ9#AoY)6jlL5Mz89lX)IRZ89k%Jfhbm`ula1v zoeHXh)sp7Dz}XOiuirhLe>?} zE@H9pqGQ385zwCv3@^m{4<~8x?ZFd*H!sHe_Tb()zx&0(DO+mtKbBbA7gxBFx$7xW zq?B;TG=4rp-4abH((SzxGmBNrT+x8u&kepg7_CP-wyQ;o)9ad6tj8KcF|Anh=9Lxe zDUIZ8V5|dY_lK0gQ8z`~?}r;+K@(aCj=L#jYr_@1`a}@~&RT!~m}lxgKJTpg$nXE> zHJ{fKGPB#P=4s%H>k4JS5FqVkb1E=_PjN%;m3|!1e!M31PD#V#h3Gpo6H@(vJutc@OE#O?$ zOoDc@Q(Cd!x)fG@#Tr8P-X0m5_3I^4%NZ#&Pb;F;fP|}0K$yfAfF5~EkzqU%7Y^1G zA@Tme@BG1+?(w^~_+Kh5>+gROflO@Jogi&4rg)kMYA)0$nd2~TH2X9s)=*C&O{kZO ziqCmyY0NUl>RKm*>)enpDw&m4=bCZ$Cg}mgQqjsN(l<#(hL!79^j9JCHVh zydmX6^KmJ;;<%&_kJsBIPHmGy)e0{ifpfM=(`G1iq{c=F?UqK*`NM%UmBmj1xAPlN zc=QFrL;Kyi?TcsHw2Nmon5~yB1Q9NqX;{JdVeN9H!(Diq+o4?^AVMncE4_E7X89R7 z_eR(zlrrRIhZ|Nz5xOm>p%RIoN?J=cXA+OoTJvRK+0i^g%@u{Dua8m4V-=z^@7purP^8rT{OX zoU+^xI_aqL2_>hb-11X!ePx0+I=)A+^8dbEjf}q+$^Md8EC2G++L*2g~gPWli{W#c!)C()3OLkUNYj&D_ z?q7Vs$PYfn5nv9v5490RaL7Iug@OzIJP4fv(F4Kpz2FZ6u}3h9u$kS2T_6t5$Zl}K zLyd6oh3e48Mx-gYQBi@mq54fme3r1bcpI+YYNXGjdYprV8%|K&=YTx7XIi?c8`>p2 zg)9hUf_?PZXpxl}#51->OXo@B&1eD=|7Jt|1}zf9*n@$Kw#jxdaM2zB-v-y|e&PPR zQ}8>&^LIZO^0=J=(gM<_uMmE}d!E8%Zy7MGG78hDr&%Xv$Sr*>G zh@nhbPYoT$F|NjZS`4Lu;g6~_yk}7NARK0b#anZxd1HWc1uFC6x)4EttnVT}1S= zb0rGYqb%VO_6QRU6TnR7LBm>ARm*&piZAQm1KTfw|1Fjt*z@#|d-8Fo zZyB(KWuGCZ;NyOIFH&w^KGdYKG*~`0rk(xOBAA71#&NSI`713f7&>4&Ut;be6_Y{w zDz&8mgQ({-AU@Ool{13-$r;c8-5J?J$eZ{4L?#2Gcl8kPX`mVb-6{dm4xz%-5ppNd zFe`T#4!PTe8TlW|kmY*=60YaR;21$skN~pwl!7$;olsUVHT)}SB@F7%<%f(4xS5c6 zR;VwCOX~BY)KM4Slz3n^D4}3CQ6|UJ=_nVXgDPZ{KQJ2nEV91Uk+UcNhSmR z)8dCdlf50DOkA zp0;1M;GD~5A~*VVn6@xF(JncKeTAt&p&=HO`E1ub#2ORBB|Mdq@N}db1d9WjSGH_x z3eIOiERXfIAdE*Ej*qPh>Q+j4CN1Go1VT(s>;>oircIq2qBNezcw9lrG&9|oI?pZOF;cT z`A5F4Fy$9P!n=3IlU!<>%MN5C8>}hh^ZDr+GdqvCbYXYfBf;mw?y?_oX~U-5KXvKp zuI30x1x zZrK8W8r7lgxx5a;;Mut*jpVe zUZUp#7j?S&M}Al7B8jPQ1-P*7J9q+xB0j2p1`sj+EZB=fHooqcBd&+Tto<7f1oO~& zewaGQr3ea3WA~msSLwI}Bz{9MFw*g@;|3l^l2Hqw%C9W7k=Vf!4;8 z>k3Kp3@q0ZC6T}uJy9CkUdz|qgg}$@yFV0!ICe=X`bj#j zQx2hIV5*dWBV}S1izn+WgaN86oZ%$CY+GF+sV>{8a2$*$Ey%W!hJj(&iL>c z>PL&o5=ONbsF$hh3du4tU0H!4o|k8K{NO^tnd*^6)~k=Wg2GaM9*Hq9>|mE3?{VUt z1fxm{YTAQbc@$yTwzuomkLFu}+Z?QEkB}nc>k7Yfc7qraPyW_Px~BjEzjo@>XPh|e zQ&({C>1K!XN7yBp9p&PJU=K}wRpRs-MOX(QBQvvLl!MPdcm+?tjn;()AM`5ZH#`4w zeib7*$$(-2VL@gx@eezmeg(Ge(lEx_&s9=zfGiJN=QudPt*Ug8tp?jH=tus%#3&a5 zLj^#0=|>7p{2G!P4$5y(qhEXY6P_M=AIjZ-#nEZxhn-sXm0c@TkVUH6ZC zgAAY)Qr6S`#IAEoWc3|d*}d(CzT;Wo!cnuKd7JZ~73Q4qf19%?4?5y14 zMaBKci_7|%)g6IVOi>fe7`e&-ZGUIAr=9t{(W&Ks;O~dud!4cUwleGhioTo5>1tl= zoN+@=#r9BP)B6`5=z})Mu}6-#pk6s#XmF`oyKWyI1pFE}0Y~;ZX-Mh7lfUNQFG%}& zZ!d#(7aRt9R-QleD6Y@RPvqD9zMG#09iqi@7bVwOqT0*V>jE44H_|N~+e3$4vd4mm zN$$dde4Uz8L%WMr?V0Kx7!2vjN{)-V!oN8y6GwlV%Fp#|y74odni0TD)fJw;J>t9S z3h(}1&xZv}UNWyrrpSKuOgt~=!}$1iEnHG$<3@w+)^F?dV2P*UO+aXGl7i9?@lyk( zf_~O#e^4Nkux@oPOJ4(W8JMe0< zJ?wR>hEdAV7^Knj3!k{_iD~8$Gmb-l8bVxuDm~P{$Q^y%+4$%2=ia++T5;%4{<%Q< zMRJ4x;(YJA0n)w=lzp(nP|Rw>QZV=4^}B@Dxl^qAQo8qBTDXp$)BmXmdGC7qbBF%? zE>M=~YW|aX4o|W{y22%6FG;(>x^H*moNLMuMpQ_vK##J8N3~sX#6I2x=4IP1&gB>J zsIC}j%Zq;G(uXb}h9+Ph7_32BR>D8hqQk$D-^yQcMvjaljeFy|@;UBL1$6suVAxC- z^3X$#e-?%;%g0mMDF@-Oz2<0e3cKg2f;!wW?J6Y1p3H9A@|;l;0Fe~ zokW{ZJ}5kT@12W^!Ca4&QUSX6I*rS-n;HY-qdKq}?AijRx>Oo=AhF^o4)|Xmttup( z(WZdu1rq&7{nzqZ!a!Z6TNfz~1Mzf1q3A%ORT#cE3I8P|+!wnI)Re2zC~9oESlL|NSS zM-?zHhmR5&QyWmn%9ik%T3`(l>`N?RVE7PoKCHCfLc35UJ%Dm{8pF>p;#i3mFZ=yg z_fvjaybi7jI6_7o2OJmSJ{Zw?SP2?*iuL<3yAR%HC|i&=WafNH%W0a(FTOLM{N^ya zeuum?Ze31mgGJj)ag4Z6%GNfRp?3TCQDDvs1ENYh%@-^veF)eOl1B6o`$}JLL@8DU z4{C^w303r)oe~%qh%fptNr(1?HG#=#736G#rI`GK#LnIVHlP?9e_R^h1O~1kkVN7m z8xcTlhM%crfEKv{Tr~rz!qls$Ch7j@#CzsSATMf9C`W7#xUmZm`^f$ObyG;(3JL#$ z!0QXaLLA&MIO`(BCV?vhcNLr)D*tcA|3Be+s7t{hWw5kh48D=BCtNr!RCJg1KU?K@ zTQB=$iN|k9)ud1#Fn>tAQEf?NQqhe+t1tb5L^@=2cobsPOF)q6_mS!peaXqF7Z=?O z{Pw}`Lq(!9J_V!;lW5W6XVmgq`Ch;K4_`)RzvFi&P9bf76KMNXHC<1Gbc_a){8%;C zmRUsG2B%W zxh}GGI;?+W)r=bvG^LjBMdSBND&W5N`o=pE2w}?kG(N3pUy4`Daok5^^xDxKA;_RwMK(T!T36z1bC@|&c;`xl!?5dn{2VX4^UuNG{Vj} z1nv}I^{Ggdd>i9Y<`l;h@psteZ@pSvVmZ#K%mV`h^P% z!mQadfu;i;mDTA0=xGScjkBLKFzH>*b0n>PQ_tA({SIalS%uGxf9r$=-Yb9G@9rNa z(^S&ut`HMoi%(vA5(Hqfy)preIDyFquFFP7e+t4#JZY2F(c)s?ZS?3Ej=xpf>USRv z6mJd`-ybNx4~lP87{t9c7I5)H8!f*5pQ?ug9UJJnE2Q~11Le0viQNB`_&89)M!ys& zu{ls;lTH3f6o6p7PsTH9S*;9kR2WX<PN~o~H&S|C4+S@@Vz_SIEJ6HIwBc5#4RgdBPBdD%Aze7H?Y!)BsXwp|4S-8VR@m^0Jj z;la>S)TAPJT6V}RlUij-H&fzDxDjPtsbbPBwA%^(n!tI^ z%;YRsoZu5SKEP>BP>m*6teyz^f=W5F%Hjk48`g|+DKG~Y>q_C92h`Tu!=!RzX;sU} zaB3Q9u^&)uagS2J+T~AWQ6qt9;ZAI<#p`T*mlZWc@3ZY6R1g!aW>ZV(1X~Z1 z6q&GV$uD@jV6BY7GlU(L*{NkH^IsCG&A4EI>_JB9{iuYTHwt`AO=I2fyF7u)(9O-lkj}`zweadA^Cp;@4Xt)uiuQo1P zj>HC=@@K;h1;ie*Hw_rA8|+|btgJSsLaf?aYF{O)(5P<1O=@sMok>;yH-^zlRT>m#tmcIr$58J~n=go60 zF%@Sl3oDKYa~}I9s@z!>Fvu=%n$yHu*rs83qen=8Ttgim7Vdf6K)pRI)IOfa47*bX zg}*&sOP%ow53N$EfPydEY#GJdc=fVUi$VR4*#eWB=M!pIW#IKf+p1Yqv`+}FN~Mrb zm|QiE%7J=S*@+d)5qt0nc-*xbv3I~CNAoO*k(cub)JL1Z%D8F*J|JAIs(wH}^kskw zf7Ex7=xbz+PEw7?hQs*qb#_o#hl}RW`8A!=n%T8A|Ezh=F>jrGs!WG&{LM!Aa{7lE zQz}c&0(G2hr*%3z1`4O$mSI8Sphx)m38OU}^bJmstc%rYmfCdyG|x>ZN;8PB*?ws@ zzNSB3uPsXO#8BI`XA*bMUK)@W9 z9^!V|>LfF_^NE+7>a6Di0You}m zNP6vP9l0J0o<1b!bvOX2blsYa`cEhlS!w1Lijxe8u{5WOG6 z3wMtlV@0lYK}EdB{h5Eev;Z2&2famY@Hwe=c4jLGaHJYg!ja?VQ43P*wkR!Qx2WHy;Frd@&e@>EerIsR(zV%t*7>FJ zuk%-41`{|)kUzk&v_2PWpDtn zM9`0m6_^#uD4YMb0iR7;pp?L1a&5a%`>5U;3+f2Jdy)V41A*<*eR@0@s}BB4Vj6*j zL{M)Flz-vLFG%?ppgd9^k~GI(Yu;mhCCu~6P(<_g0?Ll+4;o`TD_+_2N)W*14X{ez zvjV|^J@?Vt!Vw6~9VBwBEzroft-B;fPhPc-$Q(X;WzVCNo3}k^oWJLlLxbbYI6I>G zE#sce)XyN_r5iTmtZ$u+s|HT!6Vi6+UU;Wx;PIWCrQCZttoclmn}3v)Ra+&7JPza{ zme&@d)Lr(UoHLq^uQ0x{>6M7)xaOTkYzH!{9nL;(RZ% z8OuE&LqgSR4(}J_HLEKtjW@e1FK=cB7Orks5?*@h z>gZf%z%Xxld6zbW0XXP`P3^+OgAGJFQddZ3PL9rCyx!>JI{`^Y0T zQm?8dlxI?PAOl2Vd@7wh4n@yO1tbm!MWKd|;s1O9=PYzoQQ39IF;&vfD7CD|KzFuN z+PZjJd%U@_imQ@$(^`frtqRhzRa>jRuc~U3&AR9$q>XIWd2;BX0T`?sI$I8^t!v=B zz@Z|ziatCT@zhQn@^L_`#`0cwmGI@$3D)-p6}+YC!*w<=uZSKllu}StE1uS{ZkJJZ zArFS{9a<%hLBZYkL(Y)9A0EBoNi9a_*+LLLIs-afpq0g+fz7A{eJkV8ZUMz(jR#t&peu_&W5xccndGD4r~g%_Sn!iBOwV zeI9w8rD@15_XxkOHzxcx=!E5$G33Q(H1jLm&7m3(KBQql{jm z_IVy?zkfZirbc-M&+`TxCQRKhKC$x_WlKQNG%y2R;-9q091AQ;Kmz%&VB0VgJB6P% zq{XBT@3T}|J~Kx)?c9R1cY^uh40wr&#BD;DwIZ$p2=5{HS0DqbYTFIO0TRmr5qAD*E;+B}3wuP=jt1+d=^kjS|hzZo;)FS!UjAsWXEX zP}pTtTet90phA1FE25RWh=%7^6I2)RCq$lioIFhh%~zep(7Fm06;lDqqaAg3s3?D2RlqJ&eyw&Ue&Hr!bza&)_ zeK6iU8w}i4GXNI`IV(&I9`L%7Y4S$-VRL1LcF6})e(kBNa&4$~GngNcZlmld1-dl= z$3le7FMTIP&G^|lGnw(q*XVOE!TPYW1MnLn+vh9*BYqK169v4%PJma~e)m}~lNixO ze~NeH!JxB;n8ctiA~LzKMI&0tcS_*nC|8+f7Xa$rV8AQ`h!L9)uq}X!z_Y>qy-lP&XLr`rQkm!}r@CwFppBfRdjF zS|OzM_f7sW?iYXn@^&2>4AqymUf$9r4}nKRyM*G6arkv%*+wl^3tKkEQEI>N(Z<;d z=@{8dj|jsXr-z^RVJ!$E;h~%y-l-0{zZPa~%Chd3kQR(~*MdQP%7BwRR})(zXCW?f zCN(bILXX#4;##%lO0(D&VQFp>B<1n&^{*62=jT|!((w4nt4KYi6?5~MR+0AgKds48*m<@FpE@64EwX;Yr#jn?ufBu zweB%S{TyRSYyBWLviO=)#fR{sv&KT@kAy~-qybVCd6eDcdWh)WVR_fMrx#Nn^is_G zy$s%AzV46}6U5OAU%wQY2ahd5@@s0^X+bIY&YfnhC9PH;F0bdHCa&) z2MB>F@W#HcPyqtzZG5~XKrqVTG0UJk!mBqB@(|bVZo+#d_ckA)uO#LeuZ_Cw#R`=AQA{f9z?{?_{CDJCPH7pJ9%!5g@K3fx{nNj99 z_REjy%-Y9Sn2$Ty8Jf3b0L+FQ{Qw`wnsv(azk*EeEZ5G7v z$`%&HjoryeqbRPd2;=rtNbdVR3T+r?)m9L$)b0LfyML|%wQfNy*}w%VZXMgS&xjm( zZ8&!juC1F+s+3rqsem`34mX0hhuoevI37py>Q?eJQY!PhtG|k9^}01fs&2|Pmez`4 zAqxx8jb_{XE>`AspYYx%vG4p?5ZcL{SqS1)1COlYM^Y{XyzWle_t41e_el&`kp%^- zMT`kpm&aaE6j^4rqw)7jK~*Oe3J?a&Z)YtauE}3i@Wk1}#?K&yJyU0#d#0fmh0uIX z>mojv*LJ^W^q%R8JIXt*QpWA((54?OznbfeANJBR!}(y#nb^|&V6#2cV#QRG$xLdm^OE1kyoZe2?4P(;Dhn{m?S96;m6$bz>;pAnP%k~3S^>tU zm`*pZAOiq-Hii#UzyS1LJ53-|!gQ?3XujYiO%-|70Z7^5y(vna-fuaO#gm5J?lONC zd7o@$@#Ird#NlHuP9ZN z99P}ORJe3J9F)!zK6zyUUMSG7W{xuX6kw#FguBA)zA8+6bu7*j?tQhCo8i?2R8z>X zzBRfVrCf7*fFyyh%K*vYb!U5pWHom?x{8{*HgxCEl+%U=}yu<6hNASP?JRJVd z*QP0+J^0!y7hP>|+2q*%My^eC+By2r+7`ur{K>r% zvjV;8b3X((m%IyJ!ST2bB*3@mIj?)-pm5@i`_jsR2xePk@O2qrsELyz8WDC>zYQimS%N;i`{uee$7n9GoEl6w`d9me4E@x3%Hclq@; zF{yfo(QqTan!39(e^KlQ%?G^_e0xWklix$ zdoDVuR{y`r@KL%!+-7^fHx$Ew3t^}}JdO)(^1AyJ-pFu651ujFON%u|7KV&5F&U!H z)PVNoN1KTcg5g3*QQ=jF=l9_J(O%^HsDP9V3^$89^HBk^-Z*Mw`44(WGlm}8@Q(9a z7pFLA(0CL>GkfSz&ZFqZ9(iB9X^=py7(uwnI|!E3WGF#iRbU9LcQg!v^2l$51ct%7 z{CC>K8e0v3;sx7Y7sXcOj|^r|3>q2C4CEc{dkqF-CF2I*<*q#QTEU~|sl1AOLl0}% z?WMNA-#Z$=Z~UJBh`;abJo|%92jN<)fHdq;xHT{kmm$dn(0T%m8-XhZM_9xz=^yuXSN!n&Qo_+FaFGL;@np9J6Ic7|F zR%d@NZ_6>G3_i#cnj-U}oN`OTvomhc^iCsZH{QVDCxTDn@%9;kINQE3Wl3TPpD+CD z?E(#8&TKUBy3#Izpn-InO4+GY#tt2;sUnYi;!)wwxaj&c{NtAAyKJvdHU>^ik>v@WX(pL&-qP_`L2HeG;h5YI5R=kbfSxa} zjcC!l&h0QVGFS}yC-|C<1F8M)^I&A*cIyX)+MVe!6u-k#Z4Bzf11P-OC_67JsNRc$m?!>qB_0-L00DI;7A{3ci^c z316rPokqS0=mQut$RkVD_|-SvgU5uG?`GgTgdOj0Es841YvJIX?i`EEvcni_cRack zbnRH1ntU8S&K9g@ymT`5()4yC?V@O~zL+hyD^eK;k*~h#=bEmY293!*~;tGfppN04i@PlvV2SJ>a54jZ&z2%Pz_`=h>Z(1u-5qllnz<9)- z2R8-WtK;CgG`L^DT?aP+E)&v;OVB|+xNpEs%K&-`{9nL9i|D6x#HuGCRtxC~;C|AB zF-Rsnzs@H4a9}auSa6}>l;99L*!zAAKFBsGv1)dCu5sqmSrf7*P0&A*Jt=F_q^u=5 z%W{#R`XD)L|3ipv0!O+be=WDdUNd5MJ%ZSyixInH$w>aa%Mkky;js_K7W}jl<__-k zQf*bCqDV}KRFV9PB{HRPS(dy14zJ;oVRcJ zDXS-@tVaH8@7n+r@W}GH4I}xRAiP+}{BV(M?{&Ww3vYawBADN2gfBjfVAp}H3z|q4 s=DZ&*{Qlv1D*i)Z^hX-}|IA{t;WByN3Sbtn2TBJ3`va|$W0x5N0OUmc3jhEB delta 22011 zcma&O33yY*`Zzpu&Pj5*(4-qp_be@Rg>*s6qNGWCx&$nn%BBR1dJvT&crA(~Wzixo zg~Qd_x`S5)g|^UpDOg)Yy)IXO3DA3i!ljB5XhBbCA*V^3eD9=q@9+QppYM6TJkMn2 zoY~%aXXc%Eo73_G)$jw=a*o24LNAqVi>pN1IE!G?o*Hk7tBkAIVM;xP#E@Ym&hjF0 z#c1h^U~V}vrof6{{0Y$>VCn9=m0xiX>J zT-j7j-9-5bD@~Q>9!%g(;=cK|1Zx7n3y<_9@GAH(gi*eMMtWvIY!>Cv*fa|i95R}M z<(QG4J1Ro?28gFXY!WFd)LIx!VMswskdtT8=@P64sHYPZlu4v1QkN2oD0PnC!6p6|EA!A-7bf6QB^AoI8OHEkLM7Cq^3SwL4RI2L3%!RU*`M!$4wLkWZ+=2i%&?XNPUl9GDy+m4@3;QGHI_jI+9y%wS z%jUy6lDJGOZb0Iol*!{pB;FzXOQF?}+V9`|=aYKTX#PU_IFGbd1BfDR6ha$(5=V=HO5 z)lA=9X*R)z7NArl032Bnrb)0Oag`V8lohlFi7UN&*lRYkS?n|Gt)iZc_rbraV1AfB z)Mx(*W%aQz64?E05{Z97eGG%r-U~tO;}D|T?Rva_6~}M^&phG1kZ9qhkQjU?q>>dO zmP8(cP^XK_{6tHa!>EUIpp6U&_ID8b-4i&AZD$=+R;VMPx#i*eoyR}rSg zzYjC|0&4+}vr8`+csruS^TSydHN0W0n)3H-NDTGu;Zw?c`Q=tDF7qYA=mxzB@SgwFCqA1a{!C`hq3sKS0=Vfj6S5C zR7vv5f>ozU@?d;O!s0~Vh^v5KirQSLO9hkgF@#1y() zVttztJDf-+3#A1-sn&qZQZ-cc;7Tpp%>cw_B@IWlkST9%MC>oZiilMC{o@cj^p5a+ z#031I@JWQ8ni3(LjJQiaC4x+da8Nrw^bRd94|x9R54DJFpsMyB&GKH?xMXxx$(&xX?-{`x+9Xp~TO<;Z4Pm zi^TWgsW;f7Z5YOv*wT4Ld;xV$i9&4dRZkVeMQ}e{Mf%?dBVQ0S^)WW|-bD%3o#M_( zXfD#6k&p^cDT4jkXd2h6;=5r5AgQoY#-R+(8EAU}w#gbX3{CIDxzYU5E}V{MWE!vW9N{y12$v?vTSI^EL&&yW6cjwa)I6;Hv2Ph8P_ zM8#4RZAH2;9so!5z^Qd@1Jz2Vml9tKd;{I@cFmP^21aNox7_POXn8Ss0;pq|I!jiLsElQmbe~$#* zM25pbi%#x(ApfCk9k$M8>yvxJ>7$=DSX;As4R`6G)x7>;q~Eg= ziAx06_<128`86F2%PH{#p*SuZuMr-P(-%DFe;yVy%II;bG?dsqf-?3vu%2G`gDc=U z;mfRj7qE{8A4cN8g%fdRwa%}DRSYeU)t?aXyyb)4S1+`Tj}h|KF?hdF zrk+Dxh!b8@=ip<)3H6=0S-|nJ@yAAGO{BeRj-PhOb^+J4_NOhyFt%5O$?*%So*0!i z_uf9IyGISsgVy)1tEMb)O=eNGC-DK#-^rwkQNx{ARK|eEaf~brwwQw^DPcMN zPNb2M{kTOVe4CJr>jhWB)Nw2h6i_G@L3}V&i{G{3P6;9EVp6PbE)Vakr1~ zT;%jng`%|Ft726wcW-5C#cbT(m#8?zW(yPTC)3~`XAsrIKJ=8J& zIMUp3q3j`N7@W3lN5FG^6lGj@UUp667Qyy9FN{l>V!JphlG(+UZk;F|5z_-E|I_L0@*-BUSYk)pv7LVYcKE) zG7Du>wJ(tJRSduu?nQe2(_}LD3SViKj++g97u{m$R6<2g$koQ>{>_hpa8{TU@TSmv z*(HbA0Q>7_I7y7K0BV6cH$(Uuf=pPejZ5DMy|C?!m^{LWi4fvP##z+7x+5Ie!$f{v z2hu3SZ-q~^sklS(w93WYVZp2AaJ5jZTTB&tg*SEisU^P7 zE36TV8$Tr?>F=L?@^4^LQBiy7>~vl(9u}_aW?+|)sh`YH;$E+?On(O>7bi->Yx+B= zI-BsL{$0q3_XAEiwUIjxK5G*-Xox^OmaGVT#V()HBiX@@7Jk6>8{6B0fo zWKX=GiX0YRoOs8*vBP~2WdM*j{r`4tmF`vj4#!h0`qZUr|8n(i$%_1*5eex?Dv~49 z=J!lLUex~8YI#K#_vc`KKCDM|$5`46JXlfZ;)%le42^oTbVQnONRZ2Wj!1J2iE^q( z!!cs9B;1`b2@Z_DC$O01)2so8P}rU^4c7`MGUioe`p3AEfz?e1=&c15^9Gd}v8(E>QP*&Mf% z0Y1+79%5$;+cTezEIb^|t;8`^zb>A{#GXD#M+uQxxii=b+O49nKAabfdUKdn?9_64 z?w_zEP#9}O(qJHoWsQC94U)P$`tGX!*>RnVvzfTl2WXY>Tvpy4vdS$+q>1Fi%m860 z3L$k0Mo1mYhR_Y))|&chop}@CmwM&6C*b+AE8uyhOZX*gVfhPc|Hf}y<(axOa0Yp? zJJ0BB#pxe&;a=Hbyyif$uGLzgE)hHPxT`Mu=B{0NRKdFiW_`_+fdXWOmo(LX6q^ud9 zZ^76ZXoGDxiW(%h$Sc*L4A>6P&w@kU*P%NQg{|7a}G_>4+2*e+*b24HlDu z(5qY3aQ?5&Es9D|P`It8lhT#x)U7Kzv&g`l5sax|rqzhGitVyZnySa~z+&K- z%_ytD@pb*el){oDzFR}wrf4(p|HA!~6)Ebw*)DT`$-04grJI;dGLe?8#5i})Vudqm zPA)HOot!lp57-&%yx57;esrbr*pOr$0<@~g@_;~qlG-CyDY$U%fsU|ElZDaA)9!2S ztlsoV!kWS7qfu`4pF%HOsy|>-oFDHj*wCw>d#X1P{ZjRxw42nHN_=wBK+>+Zwt+oL z_FQZw)~om(MjD3mtt*+k?kd=x#pMB46kihXJR00n_S4WW<~ zvT~;js@x=bO}h+05gK#SsLWB}vz!DRE}YFVD1w_n6()RVSi+6^4cs6wO0Nd`fnF#P zFmGK5Z4WS@8Zix_CyAaZN-@$yFiJ39)NbAchlPB4551|dVkus_D4EIcA(JS~o}?5Kx$wF!e%u-T~Zr$FDfMtmF&yMSllHcx|q zhYYTWfak*iwJEwHR5KqhSfn39pb%&-HXBIY3tXw5yJvv$nGV(pCuGPrvm0QlCv5DogCYn1b$EO3H zbHbMVJ8gd+8B+zpn)mbsBp}MvDu&Z_m^VE*xS2MSy4rx}tgm|08hEb$(^AFF(^`%S zp07Y!KKo`IN-Kmuft@Lf<_l(zsZ9eOdbE#Mx6-_p>*X8E{QBIgi_({NGyypB&?+%0 zR=hVx$7y0TO)Fq9BxNO7`GLXC)^P5d@{0Ix-;+L=hh6KpmF1P(W=}E&%31!2J&Vr z!~h16kt$n1y`ZW;8uX*a1^Uf02jh+nE<2;Iq;Jor-BMEDZYi#N;-(dwe%>^@Uoo+` zpVsb{#y6PyBXmmd3sP8{(!1H;;SN`3oKfCjLYGLH;&47;6B=2Ru7RkbbZ9fPo5X6Xas598bz~P?N?v(442Iv-iapLhN=#YwKD5g*3>gGVL^qDx_Keor{{B=8O~rO083n3U#LJDuDL%vI@+qS=w6IAehL~B3|iXF z>-3v9xdx#H>QKjJ?Zzr-bM&AH&)$QJKxttcx^)m|*@gxW?!T3(`6o_KvQprZh9_{QE}i-jXp6D@IWA%p&b=3 zS;B!c-BC&RGbqVO^&>D0fHKOSPDk{-V0oc3nUCUQjk)1Q@gqA(klL-4iQy>QW)z$4 z)wHr_lf`zs$R}+m*C>Y6kwP0Qo7=!BBK~YgIjVCTDzSFMoM=9S8zU{Fo@Cz@UeikP z^H+toW^xT>T3Kk%+KO+2QlX2d`MUf^q|Funy(}TJm2_UgPl+5 z9tG<8Jfxo8_@QKbpoLKNXV;TPG})B12r3*LP14gowy_Zk5mH+Z@m-cA6B0}70-lM$ z+>9x*&M0t?ijTA|Wi|OrTxh~YsoQ>0I`b}&*OuQEQ+ulVx%kBrTLaoTL#k0yB=%ta zcrkz~B-YR@MH;f5v<k4v0GxR1c*m6{jo0 zdPvS6026WZ-cdG~_c$weWBKRKIM>+1z2qbVK`msv1w5@Iy{?N2)H4Qfj4KA%I2&+3 z#?X-#iI7!t`jL~5kkvm(t_Jdv%8m%RC1kfsw1!oQi2Y5muIKT}s{ZnX$1O1Kor(N- z9_yA!AvKhjy^(K1yVPB99MY-AI3QbCnCU>x%f0m@N!khhw0yZG#ftTnQi#p)fCc-) z^VHmujn+J}p{kseC{lB?A^-=gy!TlIX@e#Ta3Y6inRkI@2{5>ds3q&;H`dFedM-+{ zKVLIg8rih*Jm?T9Q5msjkOp034KnsesQv-(;@3B=pAOh#Np}XHT+w4HM+0HNX-xO3 z^fvOc2>43eZ0SJFGs+2cMHW&Z#TxKrdhNk#kF!Lv7v@e1+v41K8M>jUtkVEcyw~X> zN6uSb*X5$^{`wjG9SQ1^gQk65lekpx^HMS7t@G|n40vAhPTO8z@}b1qdoSxOOK&e) zn{BA)U@DLnKou}2KVD9p!)j&jSQPLq^8R@^)_}4@d$Viopv;;7yZvvi1;l%Vzyi>S7JvaHW0Me4d@)FWqu@cFI zu-T-6n)VD~>I{u74QW%$Z?y$H71C3hoF_*-r2#Fc=SRGo;PG>P^glR6Jftqov2s2zS4{+|l|KRNtL6`YZQSHQe5^dti9)?J|HvG{jX zP#nzxe-u$A8pBPJH4$k|R=>{v@E7Z;rzoyl%E1vn%p~RCw^H>GHNe~ z5Qw??gbfnL8yGB%)XiPg5^F{N38_y*{(lMnUkUzS3;v72{~?XvGcVxxR0pO7xyFDt z$to6@rE9az(mxxK(V>G^n<@Y-Ej__Xl(U9m-{?2lR&NE5AS5)yx~qamXn!GU@>c#5{!$4=1}i0yDz z9<+B45{cn!*vmp+_IMeUX%ycQGH2Z%w#LB>84IA;tjC0%vlb{y9PKxaYs|vHtW2BX z%m=bbJ+v8TuCvBCF3F;L7%`lw>aVAj8phpHLW|+_X^D+#G%CFGptc|3F!PrZTX?dK z=q(YTP<(;XE^^V@dqLO-M*z)pE~J0mh4p`SQR$z%==3g^z8}#)26ay^*J(g#H_(j4 zuD~@)UL^>|TryZ=95wWwaLzahuN6XypH@efR1LlVq?)T~|3?DSCUf-7_y2^%XM93q zap6799f4~q%T!RD%edLC_#-5KJPa1=jMH66Go}n=#P_@?BOGjNjMxoK7HkWm!4=Uk z4Vz@}yvL>C`d!3IOo4_Wtb+mdx7HM=Kq}b)6}9E?EK@3;J{|bZI~)pkoGe{b$_|+f zXNblxH_(35t}Hl7XyX$B`2bRFUBw*M@q76FrmRyx^MZ8`FT7@+P*oVH=Gj8R#+QIB zM5^k+3?p@>gJ@>pa^Tq#IPQwl{KJ*R{osmj$2$X_w*y2W0?KyKopYeFBsR~$HDXG3 z2_YptVfDoJt9rL=#B)`+TJnJwd^|v*ghdPjP%Nq`QyxiemmgRF=5)N17HF|X_@p!$ zpAo(<&BWgeH%n(kc1w?~8fpD))e)1zNlZWg5{kLR)Vsk%GVa`;B@ToNirxk>Fi?Jm zUuhy`jtS3lvuxjk{tt+$l*!>HdLP)QhGn4KLE44A!ZWF4>O_wBr(w3ocoSQtZMgX;*YeuD~^+ygVa(TNzLo2w@AsX836MmZ~%HHMkFD z`J6Rnrj$qt&!8kc3uO<(Ga2fx*3gnLPR-#00d()63$LNMkiKXMhlB4y7|L)v7bV~# zRc9Cn@3K*r&|MyrMwQ@cG^c78ObQ1ySw&0Of^s}g!GxTEF?bqw3Af7cvW<}KxvHit zwH>z7N3^&W3>_bLQH{iUbic&-K-*9pI$Ot^Izs1!-W>+Ig&cc3z=8F8E0BV^dn9JY zansFH=F-8Fjb(1vQ6);N2bU}o5D-ifE85X6umgj#1&Opo|Iu#Mt1XNTESnc3Yl{Gy z3BvXxQL*)yJ6*{-Z~-Og`FSwYc*u`K5&LBj7gC6Qcem)n6RhU)I(j&eucvy_%I z$K2V31Kryel3jI14IW`pU6fBTwOq8bluv$#qVJeHSDERs z9djF${mya`vs5$S?*JtbFit!7yGubdtUVLz)`XT1p+(ERFM3HcY?plEG515t;WnfA zq8;az582DVZ9}>pedQv>mWvE~&Q&h5?7!e&#h!K@y@_ncP91YUqs#@c)+@8%|50U{ zGh@ikr+VvcQu&aE|J-%VouyPcNe4>-p_D`4f9dJJf(7csE&_21_kgKftY<%ga+8#2 zg5`|jx-HOo?H+jdm@*9BA)C4jK;>^Y4K1VE-H^)%bM0&X$VIi#G346$Z7vvpjgsoh z03gO*qT0=_{qBcg?Dc1lxvOD9KB)^8FVYJ@0y|T8mV3vtSYi$k9I;(Z907PP7t=Kj zIH^D$7z0NX+?zigb3d%K4gKj*CvE45*6MTjz!-IpmULNdCP+Ky{f7!pf-Z%Ju3 z5OhK)oMm#TMM`OMszJ{X4txLt)s-eRS`1f~0K$+mri;1q%6-qPD9fuYO4yaz-++3P=F3gP;xcOqD z(px`>vT5P3wyx~{fps!HE+DWYSoI&aK9dw(a@cgF>sA7qpcX@viOvEprVqbSp7MDc z-uayiH!n~5w+l@??^25@rMe3jxLgDejL=ZVG~*dMIPq=)K2o^B=0*%Kx*P>A>zQ&lIR&S;lMyBjhi-@1k=o}@7#!%HIeE$ zT?YNBWsfGkSjz0u@oDGiHv(q55l=g6I@6`(2xtn&h9sGD5_E$JXm8=>u_w4f21=y2ufuewIw z2Tvdf5(Ly82tbo64VRah(nV%mFRJL5Neng6WIcc91!@XtDnm&-jb-o)2>yFn~0rvFxYI zxQPHgzx2hfi2Vlb{E|>N4z2HslA@Cc#b_-1dvKDl6HocdMF60nR<|o#>vZ9~1MW~; z*tcyC*I5ov90!C3w$_Z7C5?g1Q>?Rvll8IgKoN8sguJZObLunGUj`I(VHf!MaVKCZ zin@?Kwj`wlRy6xXDR$mj(s-GGnE3GY(3Eo%EbuE9k{oDdxG9|O)1;1#Q}aYdQfa4GONF8_y+m>A}?*c6mq= zcOk9_e8qHJHpl{YDJ1I{cLF@f>ba2fhWrDia$u6!uJ=o?oiu*63*WPIz(-HzN752O9 z$Zy6l_irjM^{*0XqqO^Un3VR`0y7dRFtB0&>58)-Aj>KRYttLJxdR3)j)JhTjxn?_AFo&dyKF-3$81 zy)E;uslsT{9{?!n?Hp?8O$6Dp*$hr=uU?qXE#**S1@N~26toNC?)omUncKl#cE#TA z4SHIw`ArV6{e3lojp;>RdZgtyF6^NaJcFHf80hXb=N_<|9U4S-p=NTc*|+&NN< z2vk<#zJ+sdDO1SBqmaE|@u}$b)m^z`xJGjbHGPvTmprBxYUXuf) zM`**K>NKw!Yz=s>Ndk3GPUw)-2XbM+BT7QiJ<}H#f#)A7rG}M0;4-bsZ*2*}NA+N> z-*X1u!bmf*6Ny>JaWH=Icug4*)@BF&K9KkgxKk+SFkDt`lsKvkaekpt^dPZ9_~9Pn zNpk(3c!m~z0U`9>{FycFA+u%RiKMHgvPhGYefnCQEprk-(#|V2AP>EEoG9QrfuUBl zN6prQM3LekF6^=y!rS+be|Wq^i@$)0V0(ZTe}m8l!X_i8gV08V6h{2{XwVvoC~(82 z*pK0=M0h3AtJ-6@`I26xZ6*JBnu+`uFyQJWwcM@J`STHQ{oWcNB)^4Iwtgp}n!`lPbH{fQJNFGPxduZs z4@(nUiGCbqBQbk3(tt;HK-M4wHsc0J=#0oovS#fJRrZxL_n>h_8etKUF^JLDfzCcYKx*44`l5@`K3jeZ z{+}x!g#V4@qAMvKv<*{eu`a-96%C4g0S^_($sKb3>LN`KfxL*sFYB0QTBK0P#q7x2anz#182Ytu*Z~ghG|A=;LAX7w}I0xBLG^B z7|xNz4$!GLCDumQ6yJ!VDXn53n)r#71OoR7KL_e+3?QWiPQt>b#liqK7{z<)n8MSp zd;n^(TX8O1-=E8*3C22`{v*EOF1#n$X7`#>mA~Vi=*2rY`w#^roFNw7&_9jELgyQZS z-`IhD52Koo1A9-XzUWjmQ^EWzkdMTpcB)woJw0yoFXj{tL|yUAsM7U+Hq{wyYR~^? zQzwE=3D8uN!YICKXS30bm+Yk3*Z$LL$0!+?k+xkX3vEBtc*X&9?f+vL+CB;vu+wXT z1;AY=<57p=qZkb>X82_sqm?(vVYR+Cn#qw>yNi?tGs2?FE1|i^q4a{@ui8>_=bjFLhI?Fl1(rB9LyeRE%Atg%t!@?GGVD-8%I#%K0 z=%UhDL$4l$l^RV}>exD6GJ4_HvAsBFRBTB8os{2m6&#xwP?4O6 zHIW2s<_yH^Va7HS# zSLsD?{(O9w5dFZkcm)W#+||%0WHgfODnSRp9JNDTJ5vL>pJ73{sr(yU&NFqH!-bpUXUu$FKTSd8qd zY2N}WcQONNP?loxLqB0sm?yFx)duh4*&yOO^HFB0nb<&kRt)YfU-yRf=mg%cv+ zDH7cLL~Ix0S7qjcvo3MaZKe5UKInG<%gzo<8oDn-`mj2*rh-3F|Gk~&6IZE)<*SPE z!@_&3^tQJ@gM6)>2e0hU0@sM^6vKhv4@dw?*=ec4 zklm{1vMRsP8ezbVw>?_Nmco-f(iUu2@onHut}Zz;oUhqGK!;v>85a-%x4BKQfvFhj zb+5eK7S$%0qMWg|_MiRrWjNNl zao&TgbK59M)}7FX3x3|#+(tSPf~}qcZ@}b|DRpbaMA-osN@v^+A?IPoyBg_~A%yOKO7^{JY z+Aq??-+bGczxg)erLH|9>AGKSd;cY+_ob1jw%w(P&K0(o-hU|skhBwggx_C{V1vzn zw4p36h_1aOM3wR)bbJvUv)=;lh`6qg`R#*B$<%lD!|aYNd;Z$-uy-|4s~XBs z##@dbTs7eLPB19cJQlCOx7tQMyM4mUbxF46T{WG>t=+3lFKu~gjObtoOlTKT)oP!>hsm@m6SR<;@xIW`8YHpn=)M30u zLmUY)hFEkid6;Y)xV9|5ZC@ZQNsY9=QNPpPyg^W{1)~J+fiJzFJ3>jtF~K8>zGr;qvMtX2kPM zK+rwbP?+g0=2520(f35ab6)_EWWX~3L56>WJWK@bt^7F7&S@XA@J8*MRvxy~l@Z~W z$8zwqLgeFfsQn{?_3;eq&m+Q%k58bs4-0LN=ci0vh1i|27PXHdb}G=HSdQfqxK$hi zn`VJmpq`k74+?ot)Y(4u{w*klt@0lxHbYs9i&P^AfRfuKG2QbvytZL>KhAM(aDacs zE{Sg7`tgK@+Q?dCf5@aW()ziPqLop4U-8?V3qZI1%8-194A`b0>_m-2e{Y`t(CiL3 zrJUgCaMQ{h_{X4C`pllgBe8K93CcCawid7%x`@?%OD4Q681}djSW{oIFZaIUHp0#^ z27Ytd;mtOCHs2^M)Fgm(^FJ<}xzPzv2Ao~%JR`knc(arO;`V0gS|`d`<0SQd8ijln zNu>sm=C7{0%<5nbl)e0a*HD(;1639{v-zYN;M{YBzBLK9H%raVMbeVV3Qacf+(#uw z(`0Xyv zEc+|eNV?sl+8H6z5hS->TGWTK_c^fUI^>7n&SxPeHM8GzP@11$N;HUv{|C@R!5d73 zGQ8T7rXy0l4A}2cPZ3<-Sf{ZqhI?#99dIE|rf8jM{X;QV9e zz9({%xNL;5PytVfGw_mNy}673QpuvrQl2LH_`^ z%^<(i3y!kL>sd9L0Z*q#Wnlg!rEA*5IVK|;^o2-_)zZnSD0WT;43Yr@=KD$U+!hn% zrl^=+Bck<`p}MBKO;aQ9qxFo&QWK(QYj)IpQ&ZC!GUpdp$ef=c^tpap1{y*MCsBHd zdh8i>eyD!`QX4~U%*PSW>U3Kb6gDS7gT!wQaX z{h-zkP9hy6Wl}n->A-jHseQ{NJ68nYzcaE%9FIc#?t`2WZ~^lCDfym;&m`EQ+iLNh zij!7;#8U_71#y<}dX&cwp_&QR{F%ju64hNu)Og3cRbVb4Z$>VJc>X z(GB-eF0XL!Gn=tnIQz`&GQw}Ggr}ZO#b)8p&)yIBDhHp{!kxj`jnCm$LD)Dobe~t= z$hVGo_6-ZCH=2^4A9lek%NTN@G?w`p2sgt$-!cvqW=Q;#Q1F}&8ZUCdIjrPBX0oGfn{j&bl@CkSf}<8=ejpX zRjq5paM_@XngmWM4FwlwLoa(kVbXFq#GM2DJZVpsLZ8#X@_!+4(REf*=MA(bS?6-! zO6p>`NDgBddDPS6h1;|=xybymwR(mA!M#$6{mZLzeYk!r_&&VTiqZ+i8grrkR*EUU z=$f6z_~g3{g+If*urhKog~7>mCpX{{+qVVp5GHeY7r65Kn3SkqdOv=H_?F%wyi=EG z`vv@-Wq^_*xP1}ubU+D^DFM{gAmNc3OOH5rQg|sH4CicpVnJbpHASaLI0d>U0_XlT5>Jm1OG-{Ezstt!i6nnSkl_9 zHatamZ|fA0L;tn4Iy@A_cnzmtIqd213*5Gh@i+Yc-Q{CfS|rcIBjn<+(6lWETZKd0 zCTeGbBRr$i0E_W5=qF#6u;FEi(qLiO^Aq4*^2`)G+X}EKWIsQJIxr$U`24-bL0F5| z+um)ZY~kQ{m9O%7-u9DwwS)o92V}f3{GJU=CUD7%2-uQm#%CmVjYy%I&b@GlP_RFr zB*eT>Xro6`D{$cx)(HM9DcqjYkpat5=FjOfKr=|clV7UFJ&}A~#~xG6`A9yqGqfa$#hH1pm7gLhi5J7pDQCC&7H zY#qB>7xc&~t}B9jjy3HOpeDAoHu32knt-P_S@nE$YcrUG(S@2$0@C?WJ=|Sv;_LX( zk|wK}=d9geBprYQMquh^VooTo&!iZy@L0VXUlq31=h^)5DU!go=@#%pH_O4vWha+J zxcd74TYyr4iE7xh-&$Dd6|4B(|6W$61LnAZp&} z=P(ynNqDPsa7fFw!=95qBY@xr32vDR=~FZJtc(H|E+5=$t8ayOR+Rg-W1+MRK&S=~ zx?OUZ=3&p@e3xN&hsw!qNm_m_xY}o#l*kCd_E9|?w%;|)Am_ov5u)uN?pbW5Qo~x< ziUjz+!4j+F=^KV?XgVeMS&~!2yyz}HH?-45pg#DuIzaHT1+5>~2O*Cn0@ zN1U3@Vb48*n=Z-{3PVu?<4GND0R<#EQ0stVDmksKgWS}Vs(ha0Pop|~KrYpN)NKc~ z{h+ozVt)_(n0%fGeD_K0$M=+mpJ7hI6)})-;BtU86JnodJx~g0%i3& z)A`nQ);~arCZHIOyJm97T_(`dVQ>~TTTi-3%Rj?qUJ^eFH(*i5tf7YwP2={vl`Q4) z#0927RVjte~?Hw!gF(mk5_$${m;MSAZ9&3eFOrXN!>havV++ro3#? zT=43GMk{38*b&=@(yzI^z_3Uz!ixAjKYE3CU!G6F9pa&v=YkYg`pPHx31RS+(ya7X z5qtBMG54|)U^6-au+bLUN?W#Ak)AxEu7{vZ*h1mKS09V4h7VQvJQIOHs#@_IKF?I) z;;YYr-tPW}OhxTcw%z9`7G7@9Caye+bjBO8kw{#ARBV5N-_}B0-p2E2@&e)8hRHZf z7;c!i2t+68qHD$~lZ%A)UG5l5bGSA2p$ z0w1!~=+A!7y>Qscd&%;}jl^erjK}kNevpK}?7TO#2>4&NT?QYh0WCFnhxd5LHrwc@ zs0(i)N)K|^(dU^ir0<#LDh|CR+U>;;MGy8sImZW)&eDxuu=5=Sn{Y_Y#+isQ=8ws|+-FtvUGnzJ-7 z5_cM3HyZnK_-uDp>e{~g^^I%_tH*QDZ-vlU>HP`ulB7ku>03hKBhkgDLZFqz)sQ~V> z6|=tZ!5t>W*$wJ&0E9Y8j6PTGTe)u&_O!M7{9=Sp6$t>Bus$TcTdKGX1atKXy&r(IxO1@73+;O$8uict(+AAN@dBX>j z%o=aF2Ycm%RsAt{YrWy_RPzi1!f>j0D}WGBKqwCJvECO;ZIoAj13^*t>2JzkK9ySZ-Idf8n1 z>&c@7RKzOa2XN6v7t5V=S-F>8bzFz*VeToHfva?V?54t}l|;M9x=Dk>o$Pr9Xi8P> zCJj5=>$&a&id1dZ=&fFl%U7cDdVYbAe9)D8xV-_KVV525-jh$Bf!0-nL|Yr2Zp2>G z%P%q`@g4Xi-~YgOOThhIYzJ*WF{zQ$@dtR{K8&D36a0_mZwJTiaB__}_*u6Eem>j> z4uMYtk`KAD6*~A*o^D7L{AAgGKkY_M0njvV3A>r+y&rF&7Z&nxa!oIyFL48{S^TB_XZIeSc)-k3st zdrVl;n4)g?+2I8KyiE=_hglHdTaU@0%zmHH(5QK&5bo$8gVYWei0?KBzw4H7$%n7k z(Kl_;^vz8RnkfO+#Jk=}Q01-Qe-nIeyVAhUgtQB!bVIyZW{HRKehwDQqE6yz;&ZKs0n8QZnqsN1B%!e>E53=} zYzjRCAC!#RY?7aqRqo{LOfP}uQYG{@>EY%?peY^yQ%G-4o%%UQgiKI2{0rQ%ae&6A zsB?`N#dtw>gj8Lj=Om+E*Glb+<R3Y|J)SE#)*aAr>taxWU)(N%m9G!mw zZp}~#ArjNKV>w3Xb9h$3Gl^Mv?u0n>c76yvlk#D=pTlp*H!)oCWz1z;&KY&OvM>i6KCXNCxj0PX_Sd{V2S1 zPD1P{h|d}h|NFgs%n&2d8{o^qapl3W z{P>6dp8-3MlY5tlyH@5iaBR&3>MR7h2}sWe4x9G_u_X|D1F*l=?h0|y9$WEMkd)na|sVut^3fK@ezZ#@G?cO682GLW4=*>`C) z>w~xd>lr6+T&g;`U?I!oYfFVVa)3ivKqFKpCoUA7%(_gS>CckMddrj;B_;7v- diff --git a/boards/modalai/fc-v2/extras/modalai_fc-v2_bootloader.bin b/boards/modalai/fc-v2/extras/modalai_fc-v2_bootloader.bin index c80dba5421af4f096554e4f4240ff2f8727ed3b5..8675496c4ad19e30819220007ed8f5ce2b21525d 100755 GIT binary patch delta 22047 zcmagG30zah7C1a}?@e;UB4JU(BHSdPKtRKyVy!hKaM`rDwy0HuXkVyp#ig&dwI--- zQM*vD?NjOE(#2L=1*H`&LaTP~dx^?>DD{=r)+lIuBVaBGknc>e@4f%G{J#8tlbJhn zX6D?PGc#wK+v}uuo~Mpprf`+eLFsMrCGmxq<35j%h|!8PwcAwFg0x73#CHdxOJe>X zC8LUvxY>uq*nT9=_abp^e@jp4D=j^%UMUqjbr+=C30e_TXCS^H?Yx`bIpI$jBz`e~ z#89Z`96&93BT*u2!zht~fDlSl9YkzZ@us8aC6uk}wd>5i_N*@;{b&gma2?X4o^R|V zHujvcKU{J_QYUJAtCnfSFv=vd(5X7{f)odNoy$z35uW4z``l|^Hv9~A#43O% z2Rc(H?*O38Vy!0JazRo7stUlJ21r%nSZG9*NQpU=I3x|;a2=kS;zBLRNR>$wUPTc`BbrLliU}0PHEat)9GatQOrC)_ti1@e z%r+6zXCaYTazj9(${ zg}66c)ja$L$c|?J<&U8*g#6f#kxKYc#@R-dj4pc6N* zIzs5bHf-q$uQ^rEaE8y2c>jsn^?1rH7fSuZ0rb39Q4AEFgLOAtDE*oP-e@fq$mw($ zKC3Dq!^Scw@sFPHO-N_g{L!P@yylZ?Xm4|mszy=dlu&FAsq{HCf;3D?wEaTEW+?W1 z-h(k0UY36{l`KT0g{grh7?lpw2U8Z6{^t^`Dwy0DG&6+PTZ5b8_!JASMPi?nV#T|V z_`I-Lq2Y!XayBepLbTb?N)5D91vFQaURB_~DV$Xtx3P@`j4LV?{f0$WS`4EX#?kH^ zU3pd=%9WVl?Ixd-K&XpgTE~=%_6(r^F|Y(7aAW4;$YR=UG1Gm^%_fP76#!aQg0!ll zU@pdj#N%G19Z^JcNIc?&R7~^^LuvtX`Na- zxk&e`yIGLk?r%3isKN$odXg;|n{iOD$M@Xdo6|*6odf{}{-Z z2^T^lZF>geN`mW=nCXj!SRpq0Vgk>0KNjEU$KumInfQ{#=#+)}DpF4d7$9+qBoD+# zBrJ{_7;t4-7oi4N{A!qo;}CjbKsBL=RYCeJgzq67h0qG&FocOwh&4Zl*q@W*$b_Lp zzh{A8R${#Kv}w5p?PLJOOA^OZN6C7Gjh{6NFNG$^ibf!ImQWu$4lfWch3Y6xm@pK2 zABpZ8!O=BCi-htKtMEsHb3_9EPH>M%342dU=H*ALnmPVAD-xd+Qo>fueWRa=zo!H8 zMOu!;c6bWuc%gm{KZQ?*Y5K^^#LJ)*wizgiy!>E2Nx#>x>CEJ32Ous&{_mF$twega zBO{PAUHCa{jBT&P#CHU0KHE=lZ@w+Ku3bU~JTa#@+*)G_?NC`;VQNQ8*~Ky*CFeW+4KF~gRbnuj(uvc< zttVP=5}uM`GtQMXN9peB5vSZJY=ZOe5;FQ5ezSZFO_B<@?oPv-l7U;m)7;o~6r3dw zuLF9Ua&@~-te_*!j609Ix)~@Lkl!N39mV1UUccw-q0vBxwD>;In(j%z$1zmK)8y4& z!4t9JV^_GfR74@6B}FJB+!A92%n{Xne$8jy%fgrrN<8HM8oJ-v*;u;?xH}g~)Pi5!u^6o7d zi_i7T`O>Z}EK1IEpl&wkpqpin@yxVV3GFQeG#B_7{%BqikF#gN(|F&!ymsM8xH?8X zUjjxW+2NqY`+V5&%u0FQTc%Oxadw{YbNJ{)y|0?byE$Iz#!6a5z8QHA*D7%#YJ>k^ zbl$agKVpT}I5myM8N%cUbJX(#*id8o!-+Y`g@FcW@rES491$1xvP9@z)u`4mKuj*7 zDPl~@u=z6(#Z*hEN3 ztQATk6Ij#9>(C}p`I<;m=!38>{GP*pQaoSyJaP=q6Ml-!#aV(TDrMw|!ABn@^x8Y{ ztC=y#JK0llA#}iKc@-y`^>X9!nvGgBz`;q$C`L(Ky>9aGCXpt0#IZ8 z$xZ5Pf|pu2Hd4dx_2Xm(ztJh2et1-p&UU9ku8(l0tY_SX2)gxK>h)HRzq(?jRrfH` z9axUUhlJ6iW-FVAxTbl9l-MM!9;L^dg*Qj(vR)l}9w-ecDCH`{&B_D8L9liDk zm)~>Fm$H5@Ebgy-a#$W|4x_d37!uD5J)_J~lZLcFz0k5hP=Bo7^R`cTynK{k89fRg z7M>hElRBpsz8sx~|1R{5o`#PI8S0VIe;<_XA#L4s{JdSZBexf={&{mQyw-kUsd{ed zra@U<$K9j1bke$V-ngd*5RsswYfP+HtS z{A{;!21*PPaP$PcLCA=njz1SxN2i3nJ$S3(Ie1%+hoNrSAbb!Vi{BB>MQb9T8pPS` z#Nf0pC*ove4Q}2b^hb}ub;9VF$)WK;`i6Q8EIcKK3X5VA4ARL&0}@x9L^?$y#p7D6 zQNyNp&WHCPom_)Cx!B@EI=n}&p&;Gl6F!W2I(Ctl(E%^OS8PFIu6G!foMr{c1-FIi zv14$PusAjyQ^NMx$M8y_KQ?1|vRB3z)+4t?k@iF~ub!9zL)G9rV)8gGFj>)FhA$(f zGHTrD`^P=O@#<^>vCsD|Ko|jny$fNKp>eAF$F1dfRRE&)KM-v?3hE$21Y6ut}=))is;n2EN|K^gyC6H0S9I6la&!tfeCvh4Qw zzj7h%Fy!9{Z@Dfu!FIkGn4DlFAhM-zTJyQ0{4ll5swXWeVCTKz zU13>kJzzOzy=r;eH4BDdMt@Wh!?)Ix)}R&B*5PKhLNmxci{kjG>>q9*9VLG6MSFsZ zcA9WquXDIrQUwW6sb;uN4WwB9bD<=DYTiU&qV+bc(NJK9jP*mFUVma`RK0G)ArtK! z@(jWrlGB`M?Q{8WMgZx?TFv$0fb`qm&L&kMAzn({eNu>z7$tPZ%R{$$$+*K32Yeku zPka_t>=jfa4X|r0NGOV)`>7Xz(v!l{G|t;XwhA=pG^C6rCoI9JM4 zF+c-pUId3qfal&XjNleluJmG#K5A$VgNiG>#@jfuk}tgzQuPrWh%ZT$5x+)@`-U*= zqD3YJz|8etbIBntg%$S;@E?Uh5f`Bw4+QN2#Fj%~N@A_F<&0Z3m+nKlU<>eLE$xDn z8;9RG*3X^7_zj^^J2~kM0A(8)ag2` zjUMHc@NQUeKos{5g%X&0x!55IOLRPbQg~Olfcm9>M`C8eUwzHjStAxtf5w8W`^V{z z{tY}U%4rOmkz|#N<-+X5sg!R}csX%AGvrz86Iv4|F*32uFL)CtQJ-%YGL!Z~!F8|j z&!kDXT?idJPRUs=YNPof&)dSZu@mqM!ee7~)Pixxc8m?7V1GZ5ypqAkSFnEPUE?i@}gA!HOL+E#KBTjH<9$9=k)-2 ztWJfK&yf<37Yl!+jEso$BTm&EDUJyH!!be^x$LG(IGVx;0aELP_crJX3fsbuJzhE~Um!sTB3yyX+&Fy4>scVHP`(9X}e=ei_HOS@)_ZeE~gMqfNchYLk%8I$D2n~jJAF+?3q1dyE0W~3zbvIa;!^Tus89rAD1 zW0A(V4bGw#zvrbEkd%(5%`1Ff-M8VJdU=Yr9gZq5cBdGf^;q`?AL6AwQ%t9Ml_RNZ zgzVRbzI9|_#c4{++ImZtI!|m);cvL;z8!0Ux5!fHg&FC*?SjOztv#Vcnt*=k4dp$# zG`)^U7q9^kiIE#-DDBV`kr>%Rhs5OM*6T!yZiUpaut?y|kkd!rAKD>uNl6oMD;yR} z`(f_u)o^|cdd?5QCJeGlRU@?iJhU#HdpInQ-f&qS-WELLqQvHOC_>sUN=%uI%Ln;8 zNyM_V&aH$~q*3WW?ZLVO)km1Jj@) zQ<1#ssQe1j(M3#Fkad>{@9_ReGz=hnZ!_GpSXLqjHH=CR^0(e3G9aHKJz2@5eKle& zDxIu2vRqaYUipn2x8bQ?C(R9d{(6d(8$)Si6gea-mY1l?!z;J`55$U7(1wsce$1#} z{JP56rkrNK=LdhkD}^Wf{SSkJWqjJmsz&ohhX1$x-ZpyUeMO7#qOvhewlJ76t}v^Z z-nal$-R4NO)vg$5+g^67fei5WS=>fD_Im_Bw^3h&wLpS7n~WT<>!N5vhO5NKp!9V= zIp|?hnhB3&8#A*F#?ai0)}Diyq+=DnHtohBZgkO|hBGmAt`91RjoX}@v{(+8JLd!5hWG%2I z@FzCPHYSulhPxL48*JWj?8};Y@!5IDeRq2Kjge*|F`2v0n(_G2_p>eLuDrF~v-3AH z8)YIbTaI!1fd#BH0$zeG6RZxMa|)2ER(97g~57O8PWr2;5tNmKAfgYfx;DT@w$R`VA3uVN6cu3>_?oFCgXjj2r5-s_SX1hVQWMDj3qG z-Jf2Hl7Np6Di!0DSJ&yDQ2Jzr2L3CMUC1OsydO{Wd&UgylAbci-Dgo?>ckl|H#u%n zjSVvWo-in!mZ3=3L3RzKt~f`Q5Y`-NMivr9W2uNiX&09q40@obWLPnvdPK?E-l1i% zVv>zo-8NlsRfSGuXx%1Cr(5IqOd2r4npYJ1Jw7RBu!uAF4ihGs9u}sDFt&e^ooOS@pO@o{ zAX*9qS<`Ic1H)=G*nT{1e#r$Rn`_>{fJh|LoZcvIvZKBoPplGoOpdij2T6)?Tae%L z@Ze4ukX1cr=q(WMgy9-aKV^WIhFOV~#fF-DjdOLIDxQrLEnzYT;~oi%2Uv37l+NSQ z=&IvVv`uwfisiz*FAVLJMzyjHqZ&SQhlGu754+8>Wm1}mT9PIq_9qAvAxxe;9JfIn zoiiLX5Ko8DJaITo12}F2uVC7!RLU7IM{T2z={69prEZ;WLx*Bi+fHe{A(?*>HkO5D zONrKX;VgnZ8LKUUNl*6wS;6lCJ-Y54X^8=*s+txPXsl0lQ2G!D(qD9fW*U2msO*Zb^RLcHHeQ6S45vM14DZ2)Vvb-;EWZ=4ij6c5`WBge1VRU8`v zCKB;Y`@?iZ+v{K?P?v#OBzdIq!v?$qr5eSwYRCh~+Tywf0vS<_(jqQzFUFb|XOi73 zng4V58uUp0*R5PVWt~$QRG-4v7HDKaZJUd}4(w>Lm9(vX7w9!@g@c}7`+t!yXnVS3 z%p)=}Oxfg?ht2s>)+do#%RjMxyjw$4^pgb=+9FPx<^m zrR>#cf>C_5`gQ5veJ4S8WfYfH|5Gxoeg>vdq*Z|E!fIpsAztAggATToipJmsuWh>< zzv}ng@xI#~3~T>a@9VJUDQyn_NY5tvc}PDKI8vTjhj+g(Em6TSGZ?3%eaafLeXar+ zvU$!bi8CRwvfA&tJaAW}ex+T3+f>$Y%OaM`EOVi8{LCIjE?9UhW=+*Q#ZT{tm=%yRXzC;hc*B!tcDR8v8sm#4PF(_?HUmdOtCt3-Jx~&D5y48 zN1FG^^4AY*6CF8+`Tv2(BYKL)IO~E@H9p zymP^|;i10}Krh($4;N|hZ~b2g+owj`{?>mm*6(?~f6CUHy!R#6{>e42c+Lh&6e$&K zGDkli=5C3_66p_Ki=N49WbTnb-p};E)<4pK^lV3?6l>7euiSvOgkxH{?zL+xH&9y1 zb%3$;UHB-t7`D18x?Vq=@CusnLa^OUAxj&M;I&^ALgIoI7=XFv-qyJnEGK{azaR5C zjlnZIEgGH%nRi!#3<(5Il%iwLCA&>2SJ?- z7DBKRwo5BF*p|bruUtn2l0PvcZ~aQK)OcPB$kUAX}?%UJ%O|# zJ}N3MYsvEH6^zZjUIxdxF;7%6k5*l5z?qw+hm6Zb8>2|wEEO6bUB9XaL&*WDxaz7C z>Egy2lP)*3N{QvIk|8|KV3#Bge>H4iVG>bJ0bKx` zs>~0z;i$6l#b>4Lva@h}rGr&Cu1sy^vQYAII1OMk;>;2kVwO}7nI(0cU=p24U{dsR ziA8Y$CA>U6#x}Yns&G#^A+?2;1(h+y8qt=k>D_=K=BA0VrC~fGCqe!bPLOW31W)r?Z1Y5iV*KIe^mrxzfLc(nq7|^q@AgnjW;WFVh;{@>1 zIA?rPUDY^Gt>#O6_XE|9;eU;x`}Y5Jz%y}Bn3tP9e|MArrmAEzXq{#JjC%Y5OjSSL zg_19}fSH{mnlwh7>O;vPV3uOUgs{>DCgSmt@M`XBepyOC;3 z307Gmo7)(O+R@!BUUuJc+rNR7?cTlGL08f{}qwgXbCk&s-7Q z53V@=@2<#3a;(4YC%OpGQ)>o1)Buv9vR z`H3)%pKkjSOfpDZC#CRs4}B1c5BJMJdw|4kV0=`<9I%apo*Ec?vNl=JaJ_h%ZO&=L zS}>hx(x5$x(E3EAW84O`qT=k0{46BiD>3d3=&WR)g~Uma{uVpSc5A4o`KT@+fZIp85praY@i)itr%(%UCS?nw3X3| z4#_1%6(-xZ7b12u1oJ$^n&QJHJe890bfoVGgF4Nt8h6wO<*}g6#)ewZVIwWa$5bgh zRT7>-OSlAqV$c|abAVWQ$eW7vKIa`5&ByRKD||gl@j6v8RRyX>Dv#ky;%iN;BT~W% zNW!rw#p8^K8Blm?!0x7M7UmS)7jA*I-C9{ykkAN==>u9^B0u8e!FIgZXfv2wI|#E|wS{;r(AZ3g+Cg zS0qcV015!Y_agC+%_rSSVXOmZQG(tYFgH*7j^9;~^s^x0y?f$FDYe7x04|FS(iZS} z{PeUL?I+#(u=^a55OZPo+8ig{y0Gbv58Vd3qd}=JZSR!b-$MD=oIKIaP(HvN+3x5)A^x0A7rOB?LlrXD6bdITk75Bjq0`ASlDdk>`C{E zu%+G_H<83~MqaNy@0$js-Q1ZcQcRx6Ft&DAp2#w7@ULRdyN>rEThoP;?x(|2p~H1y z@*S`FnhP+;Gd8_NBJ2foK*(qBfF;l5FUDwt1pncK5-$D>h;Fp^6#2V%! zfEpim8K97R@n-0D-8+!;XqeJ@KvviSXfD6oqOBLL`x_Klp~&)|BD9WlW?#MyN~*%B zmPF{7?)!*@NmMoH(x+WMGwq-X@Mxl_8 zYRQE&-=6^sbHL8;`uU{$;V@h8#v?&Iw3lZK(lbEdtgQPuf*LT4#EZZQknQNDw1dmxQ#`^1Jx=x>=>N zo0Y49$}5}hjO5u5n5^JDygRxcs3qEvlIDnUGhyR9cI2mBCX_?op6amSx;^>HmxBOL zTz8~dLbii64D9wEoJqfR8s0R6z3Q^Oi`X&<4?#e! zem``eO6D_C;#)}jI`ENu31U)@jHKQ=?Fuysw0}0`FjimZ>#ds0QN3s>nbD}0e9a2Y zt^zVoOh-ll#Y^(^wr|}iC|xr==LXG5w=yj0$KfXi&<=7N@O~HGLkO%mzotd$&Y_67 zv$MsZc_a@+wf>rx2q`jdSHV}VPSD}uNng5bq$7OdMG%Sx@&%2< zgzFAG{TeLd`1d906HRpBJ-F2yD)l;81}Bu2Fe#0l6G7NC?AQKgh$ zHkyjysk}QECjjQru$JWxGIX?aRu`thL)Fe64$^61o1WOu#QxeqAn;Bkp0KBgI4Cba z0ro-r?c?^m+bRlnz#e561!5cROcBGC(4sd6rW}d3kL?T$(<6BiQgoUDlrC@CQ+r#B zQ$16X;j6JOx5W-P|v0;acyz`jhcmCg3wgo4Oa^*>PSr~cCd^iVI(U%*PsRivy zeSZ5-*J<(oq&)bI%*&g!Po{J;!I!{i2e%>3FD}^M%71cbW%F9>4Xq7*u0(MZ6QoP< zZV8N*EHGLW87(T!!5)6ZMb*Wwe?TAPq=0p$1hX~9s@P$}Fk61l_JQ-i6~VAa!=PXX z41AGF_oM47SYC>HTZ>A2nYC?!c}>y~S{Xj;fRcY>b>F!1c#})Vf6G4z|MOijz4lV< z1RlAQ%IauX>dL(>r((LOu<5-EkMuwrWG5i|pR!vH2i_^0sjuVD?S#yT7PiRYl}{Q{ zIq{^=`F;5*KOXF6(BAwLz$nY}W}L!xS$XmNy5IKl)1X7NRPLtadTUfmnPz=pjsHrz zrDMA2u%8?;pt6y>aiCnU;WW_hQgutZrVEfUXl%gq!3MIc;Coj^{D=>e`8nRrw||6f zH3DRlT?OC#iSfO=3hw*Oz=s8VsnTyq=Ez?3R2(no!}z!s9UM%sT9hNf+3DBy25?Q& z@@C-9p6pkq9_Ob9pp-uvGT+IUNm#$Oo27388xF$C=B992^Js`3G3`zt|zv z&f)$N?$mVsyhdg)XvjhB^ZYu1l1@bq5%B1gsT` z=4rBYpvV<3gLMatrQkM`r)u10isWfW+(c+y3m$plUW(_SA!E zuU~j$ep=8&{hc7w`8{R*!uk34fZtc>1F_Tnp1go7DwTqrNGv~v1M%mlstSgkSBYSP zME@!O&78(Cu<_{EM~Z{ML4Bc6w85SxtaucLTba6cpd3)DML_!;qM zi4org0gMr2fORJV2qShhslf0|v3@^hkCN*Jjo|n(W1ghrwDsg4-;)RbLe+y&L3{f% zbq6c}-XgsCV4Ur6$ty=ul7a`d{H8Hg^lR-B3++8E{UjaVA65^plvPl&17>d0w-P&R zEBH2IjuDsjkE;jIO;FGw@h_VYynL>osbzq>xDDbqBbxe|I?dDs{q=Ude~twDla}Yo z5L*Yqwg9pJc@F|4Z4W8~OiD(@>WJ zBxNu|;K#g)t|QVpEtGfKN_(HK@_Vih$>LjYOVtFZ2gF41{i?RcGs)=o@6|tD2Qemi zM0gZpG|ND-=N}@~Df%ZDqgh&bC-C0`|4Rx*S6mV>X%iXoA&Jq*Yvl+1p6f$t>AlY1 zTsVoeeJ;@U*=o9u25k|oH`>J0)mR6dUNFVM;2Ie5J(%85sSKt!9{jh|rvmwi0hJU? zjp2Yv(+*5rqM7U_;O|NcFfGP=izC-ZHcc;yT_0JMdpm-rH1dOJ+((icWbK1P<6J1I z)m6r)@WE~zOpB8LAFy5+F-XD&n^Bxy&15@WnSfn+U=;pZJrZ1HjpCYWeKd5b+HOL( zAFT$>hYj7fR{tcuadZLyp()DwHPl!Vc%Q}9iA|b-Q8wNhV@U$rcv9YB(?};7CzhV! zB4Z5RToHbcVF;)M)HSWQ&D9X^#jFkDk8(51YHSuhWddU(AS!bA_eHR zyU5@r2Ra*9jgltt#!j+QYGE@YhGRqF5bj+#(v~>`_%pE9*j!E+H!TsQapp5dCbgqswxly`?ixL= z*U3yIL&e-cL9VBB43aEm_`0B;C@e-r>e4B(p-M)9DX1uA^kPK(?BQ}slkVB9n=OOj|P-;nC{&Z(b$u85q&Yz@rjuMFcE?aOgxM+)?4h>gm z8Y;`5-dp=I5OO3Tqxe6R-&dF@@P)xG+V$$>sKJZozO%l z#OnjQF*Ad+Vo@vHcu1q047F%-78;0>Pg%lQ)Yc)eIbm(6TY)(^0WCuMVvTJ}6R8_t zQq_o(*%mclbCeeE^~M&-VXO+l12yNEx`@1$$!j=9i#K7jFcU!p9Fpkx$c~7amAoD> zuk=!NpxEPey(d8HZ=fk*$kROd2q@x`LD{#|Yv5U6$f^MQ_nJz3f6kW81i=&HcA(A{ z@-pN_HUJ{8LkxPhz>Dk`ZYJm-pLf_A>5-Unn!zi2=T9!dqP8sNWWAqo%r@+ zBUibF{C(1T?(YqAa&8t zxZ@Gl5GDhQKeSXeZU(*kLzRqM4VqFcR`_+m#mFy#_OpsSuLfsH;9@ifR&u;X&{*e= zH&;f&NlQ6`@?JFo-vbQhX3$+QSAy5mdfE{K0cW^fL6EP2AiQIpgy#w!)@Sf5!h@Ch z@xKfbc~$Pn<@W;RM8nbG_sIQ$n^vN=u_}id^t=lm zzN>39?;FUqq7;{dxOP71-zm*E;Hg{S|KH%9Bb9EkhVph^v!cXm)VyJ_LWftO{^~UF zYR7A4Qtu84v(_Y2wL`+wYsOOGf4_fCW_6@_%y)HJ~DL71^Rv2Q5UI3oPxsm@bwO`p@xf=ka;!j()wAoHUF%6 z#yNMre5y>3Zhvnl!Y=)7?v#q+3&3Y4I%vJ#fkCm?Vo$RoalwGVtuxtHgM!}$ifget z#ag=_i9NnME|g*vU$+0;V1)6V?f>0nhv(<*plXrkaWPex`-cmsJnMuf1J*y~Y?t;L zc9|$pY3(wtaiX*;C#lyn2<0l0G5{HT;;K$r9;kuzmjA60Zh8Q!%yWWbsp`DzGtl4) z;<^~yE|VFcmT(GA4?M&PX&JZ2zDrup?OFYTOOrCusTiL{TH$I<6P)Jy80*&nyQk(L zz|}ofBP}&* zxSwIfIrJC!UxJpy=^R{bTvcQ}Q}dl2%)^yxxbZ-C0fr|xDs0HTL0QOqJvV?p7DL~2 z9Xq8(5SKa`_s*b;(#~1wO`tWAYQPQ)qy54oR{d6$b@Wzs-tm6mwqmZngtJ;2>KX*o z!4{wbt>)#|8?Io2&wc^b3m6IB(SJyzA*&gWR2bX?peBStKKn@T+>d^62 z@zOR(>X&c>DqSh_6uyU!_TX$AR?fj-Ap1 z!yZM%MPh0V00V!^4S-ca$MNq-3*pHEhID~s2+{6 zT^|%-BOq7Y$Ylh$4H1L|q#O1}-Uic6{E;0}mHmVyH(2yJEfyUTE=n&}tvdEEi8%_K zE`oYn0sgr)pAh)x03KqG4w~Gv$~m5LP0fapVmcPLhxZEjC6I@7>$?LPhCu5jFGvA(}Cx_M>vW0xVXQD6EtqR#9Jy`YG^)M86ZutL=>ood8 z7hn9G4H8?Vr3O}~(pZ7KmK#cYN38`i+gtHG)3*&$mfDI6)1A(WEfQUObqmwCXzhVz z;U#BpjL2sCjB__jvo@WPW`J+$JkwM@q!^2H2M9Yg>}_j7-$~Anx9TgrV`dqt97`i&dJ}qz4TQRL7!WzzTYiL*RBEs05}@ujj}> zGCbWoC<7BJsaMq)!ZXQwSWQTbOQsXYqLDL`fj1b_k3ef1&Hw%o&T>{!nY&D*s-z!L za%q>5Zf~Jm&o~o`T*Pc zfa$jo3L(sdfC{S$Dvy;vS%-t)510p8-shU11FxsN=?JPCTVZWqV8~P5hs1dAD7Ol17!_K`0!I|zZ-ImO zij=&!h9Aw30sSD{fE%oa|M!J+Po?Acgr2A7!g*Zq^vaQCgK}Q1N9hS2o7XpXp9zb- zjKs0RS5ND3s?hy(0-FYRpTL?vBt$%u4EMaIK9geW_q+h6Y$VFgFwEf+(Z9lJON_N@kq8tzbdT(pBfcJzP-jfH>4WCD-_#}I84}XA2;UL{{N0aeP1rzlRsmXITu(}Km`%PKkPGc zk1(b>B|3TVu(iT^$P!tatzh5eX5DmI63KF|Grnx9pVYf+-i za?rZV0ya(I)+UW@D<1{+z{MRAP2@f^+`k&HzJfm>8pu|1F|`BN?XntSf59@sWlnP- z9o*eDOzA8Fh&_X<`c-0x3~r2$f8RRk$_(fy1e`R!KBjP|f#d*R4e6J~)0a8GUL5+j z>tB*OgFY5#nFZeM>Rh0Oe%Pi5Jd?d}=anWmjUTpDl0y=(d1o1?e`* zfs&wGBZzK9GycL?QdI7bt{I7pPrlBO{S!GFk5~nO z6aez$Kr2MN_`2Rd%JUp3P<*c@SPs23zvYxss2^QB9(t>9+ZdgcbwOliX0T+65@ z^_GMuWB3YCtOr}>TH>FSTyw4df1?)C=83zmLA$JJ1`sF$dE`o+PMG<;9uR-(c^lk8 z>wkVC-Y-mep(5md@K1+(F3bBp!G7Vb7m`OkF!bMrQ3V4Q!b_eLK62qjxcx#DZV(hT zqhvd50w)G$5$YdV_scc2#ewh9O`mSzs)ml zpb!wq@$Qr!QXySJ%7NwK?K$w$QG@n+$g`mIbB?Qz=`Fg)S6W(Ka+ukEPv`*ImxJUY z{L}JV0VtYUQU2-+CrpPRhdsZ`H0S(*ZWK)OSxt-hY+l#-w#j$CBlZ;Uyg`|ET0-i- zwfbnMM4C`k-zF zx_pC*c-0aPCXEp8TT80-ZBtBMszrav7xRJo(5zHzv8BMO5V2ya*=!-Tw|L3_Q{LmI z9gYv&ER_Ki<*DyCB{D+vPN2!r9H6M%r>bC(%(ZmZFzz+*^Ur7%w z9aMk^h6+v+pQlfF>6Ou7JbU+*5^knf8!+r4NNVR$ zQC?wr?JV3aG}eBEHwqQ6<}2sF3icZaW}*JoSlMfVl=Icc!k>pPPqB^a-}n=cy0|cW7cCK7q8x+atrlV0S`ne8KwMQDQS2WknO_3sZy% zI8CS&W3_K*|YVf!RhGd=>^2-C%Y5 z$xFB}k7v$jsHNyRvW&>4?(-}XUfnr)a!N6|4{V zcsJdiQ;)q=&lhfRZ-pzhAzo@Aw~HRJ(^%RSSEva&?UU{#cwh9ezEM{p-z@hj+`COd zm*To|#RoZjDl4yx&O<(h=luXQ!yvam%Pt0` zRlg75it6QgRF1JrZu~VCjU7{e(TH^CZXk08tYh(o?Iz_Vln%~&!oOZmu=U%w#FRsK zn0t#y>75RMyZ?%dYV!Y^ppR0G;tu=1?hp(J7XYe5cq|uE@ALF1e39YCE}T2UM~gKk z7Es2RI6hJ5Yrx|4o!!hU0bPI;6+TsXUKh?A;X_03{ba<75TxsU{op-KP*M8S0Tfu@2ta}I z%5Mh;&|uyEd+cJ3y#|KjIr~93#g^v{BhxP`hmpxez7az&12Q&(Hw<3(qvv1Ff8-LC zQ=Vt+VvT!!)Xsg~Bk(@c*Zh0@0~h8x7S|tx^Q#>4uvg*H0wQi>f*D3@H5xlSt}w}T zyOB(>#!L6SYQ*M0$L!efC`<|tF?Y$$(Dj|SOpKT6g|V=~&_nk*6VAV7N{8+%^6Fx@ z!Yq64D14)`fF^R~z7aj!?+!4~M9!%5+f7lIsQb$EzKP+x5TD~3PrS5Ta{lTyH7{K& z$^YPdQ#Zvf?+zJ(a}Kz8@R#QJov=|kT@L;k7d5p!FVkh>9}9B+qNWC6VW|@DVfM^8#N@gRc*8Nc^l{4tETmuIjLs znUVMbd~NR%d`N^?=UbXk3o-AJ^X^}e-_nl&{vG%qE*HQVJj@2yzQ~8_fYF7Rr02jL zVgwSqD)6L*PuOXDRqzbr!GAt%r|q=|asYL3bSED@BcJ&~79{4tXSlFsxP#1-r0dT> zRY6MB|5Fli5{ciRBwyFE!6lARaKcXB*;3jI7I7E{bNmQB;enOy8qnF1Ll}ugP$3gs zqVG82?cLB^AHa%-PHk4mod12k3LonLlpw%ov*2qCWMq*FJ)|oU8)K{tuPynaCs-a4 zl2B7-J#8BEwBGS{&eqc=8GM!}BuVB&S!LESPv_pI={+XSVY-bWj)#~$$2oEX&uq)W zq-F8Je4a3FPre2yXBO&vMdgq{-9S1`rW{l<!JY*5;sHCH zp`SO%;Zqqbu$)Uz$pB)`fY7;zv%yek$@^Eq9g~`A*)z?(Rd5xjW?E)R7JNd^o<-*oOD%cBWOAZJl6!b?EF7(AEADvS zA51DlVhE^L5+P=NIxr%Ra3+a$LZ2sLkkUjz97{w~5I%n$^m%p+N?O`GH*?|l1 zcxD3GlV_yG8m5qKyyM9mB$bhNPdS*v0%g=)*vbEar2=&)+nb;J4u3n6(Q5e7yE`_j2YyWC2RefJ054V@Y&upu>alIyS*@~IH!?=o4T{D zGV5+rjKlfJcJMC1y5z*xo=qr7!}#b#?4#+OCfZHW;BPWZ?ocE%PNFY=&Ck`}G86d~ z>4eYrotSej8hk;(Rh`82-B^wh`T(94@JwR(atV4D;-I_bN_Zyl!FQiS?#7{k_}G{G zW3cT~Dq>gbL4O8u21%zN_FOXDoQ4n$=}#dq3F34JEAEDm(h)mmJYwfV_yNKS2&*AL zvuH7t)f*6d44yxNus93+Vc>Zp+_Ikk*owyxa0~>F{4x;|mcBE1%<`@Zt7nyEn`Znq zV|>QM@rJ)-PRy7%F=JWQifklQy_aYkxfHO0FkBCzF?Z9|<$$#nu{sNU$F5?y{K^XG zY1wdk!txb=ov?1*Q@Q4uNz0+@#gBqJ&q~BDcpR~FA%5x+#8yIxgpdSb9E1a4>e8$p zu3rka1?V#ZZ5>Xad?+MH=!K;BCuexpgYyprlH@V2w6aZfQH42T5Cw)utbY%>r&e&+8%4YVzsSSYl2IQ z+C@FKRp{c<#o9%Ka<6D9wA$Y8H_>{pO1;wB8U?i{g65C_`QHil-uwOE^FPm@=b6l$ zGuu1wyfgD|b9SDldfe3E3l!#rcFJH+s6^TXt6$N*CWpECcCnf1r-p*7b*zcwLXft~2*I@{?>2RN@`D9%ZBMw;i|v8BE=~9n&hO zS3svdHPw1iNn1n~I*)+oj%tf&q9guH_c*E}Yy`L(C}V;$!hh0&&0;O7%p708z*3o1 zZKdJ;|2D@4$U$lXw;U7s4oaqrS7_A-0HeXl$$%3ig=H zp>j;$*?TI&`E3x7hS)4pRJg4$l){jLmLMn3s?#Oej8IP}Dk!r^Q=~2>7E$VKzuQor zQ%S=hOw%nrXgX~tkoTBYz{84I+i+_lukGn5F79zmO|*s5T1e+5+M;=_2=7J5)My)q zGN$O_9u$qq`yNwXG<2X7P1BNW)Zv=4Bz`+R@%Fq!xE_z2;Xx(TENRqsq=q;JLMDV5 zlL?KdXvHYXj&U8^iXzLYS!xIjgdQl6!=PD6gQlqSYmC_p^Q2F99unKZ<{VLkk8~?;4j$N7Su{c!`7my1hB{c80bVOh;tx)4#Lk6 zIv@lwQeA~u$dPO2#9N0}CiBsCbdTeyRZg52?TD#+%6Z(0^n`wYYuwl!UH74r(HK8P zqV-sX6OX;&LD_$}EIp1D^2%5n)^~bPuE(W^X9}Kw^%y^`DFZ;tg@f`Gy}W`@q+>;d z4QUx`qT@{C252zoI|u~;QU;|P1!r!8z$kW2lv@!X1RCXGwhLnavw%o*Q(#fV-9Q~< zn!+bXat1!4Ifcuz;cZClma=%f3yCJ-Uka^;)ZTadpHJ#VljRHPqdd}94WN^>Q3!1a zYWApon6*j_8i!S=nv!`Mmd>0M+FPWbU(kSxVO4H52iytPgbMYfL|c^z#5G@Q+dY3e zj<2M>HVb`wp~VcVSb$Q|0C03ggeJ*`#1(#|Q&!L#B>u&(hXrQ0Si}yC-X`kFfEWB# z1(U;cpbp0`D7%A&k-(B?Q%L+9>WBn9><&ZhA_%cf4n01&m}9u0Z>q32ELM0iEDleA z)G#*8n#_|R{AI+@tdF&HITFY9=0GEv5L|l^`|V$FHrvFysO)f8Qu9wbb{P`20uE1O z<~=9-@`xrplbYayPC6j4O;~&?fB|Ag!Wy;-iAW;<69RxNkv)bq5NlZui|XTyxU&V9 zW3gI@AChLLMX8_Gt94^4^v@W%G1f6vr>@Bg2LKispHz=y-3TEcmbXw+h1@_FeVlO=CB@8Qt7f@?)3}SPy`KlN$iu>Uj z(*MyN{en=lCC-laUXoDl8Sa9FrXbBZ390btB3O32%tP8$d>hQ>NU5+=#-U8k9c+97 zsDGIlfyQ;<+*tltE6%{<4W_A*ejD!E5Y_BON~8Nn37LY8zuUfp7D@SEx87-dQ!=Vx zH8tqOY6^=q9=@`Aez*lURM@#kSMHzx>juVKLLqSjK)g{(*@ndh{-E!xfdn8vTKv41 z(dnKE`hFZJ=V&sXSMX?T{MZxAM^(&4u{NZO-~n(%cb!?$*j24$+9~l=@N4LPr)P?! zLpVQzr@g`ZPV!NmG+ip`(G?&PLJ03L!qAvFdmXonQ*bCfo-5|mx*8)bUJ01E7o<89 zEuIf>DU(m+a8zLtC-2&bvADfg&Q*183`3bEF4Pqk{(+YbJHjy&+9b5c1mLy>7|vNz z%;CZ*@bqe6M#=foWH-`ON=)Q&{xtu9ZEz5#TR3s11k6HQrprZ(?*_1O%@TRZTjrss zap5GPB_<(#N5H}1-5QSdVwM&k3zU?&Jj=v6=q&t4pwphm_90eCO;OWWoF&A@TH?O% z!^S%EA8xFXJQ#?A7U^E$@z|7^^%7YCswTCT0qW|OG|v5eJ5Sq?M%6;v3V3RoU|2mb z*HGfE0fyTKi}6T6mdacJ8WPVBWO6kvj5i$}waLY?0S$*TXz`rT9y@VJB0SOJPlVRQ z1Hy>7H1_%9SD`Oh4)@2Ihg8D?3i>_@lI*3zn{mUiSvV0_jPr#4xUBfd{wJOwgpK-t zvoI!lXL@tc7bA?1Ps9%jGvoERTUZ@Ge#qNFrbEM}^Ii`n?iW6f&%z6ZuJ}Csu`q0C z!dxk+X~u<`9G@G`fkF*e)Kb*MaL7AJmI-}M2~KHdyfZ@S%3x75l*vDJEm~95g2dx} zaQcaV>k~bLHB_NeV}hB@YG{WN^MzN2YVmQwIW#wZf6(SM@EY#&q9wfkQKa9$5I8}h zd+5}#e+_7wXOvUo8DVmQ0k(wI3HpK$2c8GYN112cDh(yx>_eIRU06@A_`wtOoeX5H z+5_9bnSdNtRgTNVmmfjmzlDD!SYoFP=z!#*;0{kVa)Q4Q4_6`?gTg_G@|#H;z497|N%@_{8Z| zZ}iI=+V7s(ZT&{*NE_JWsVNIymswR!DSXiPcR%Sqrnlv)$`tgujuWb3n4fDWBcs?r>ZqDdZe_S+S^Q7qnjL(m)AB4fQ0^S) z@vlO6(wHIlzydQmu?}e|afC1?InAg#k#0od^5aOaXreg04Qth~ua55n9$PQhVvQV* z2c*aKaxDevQGLSm$$5NK! zXN0pUd3KXu#+5sf*QUsMDw9)>&Vzw`A2?+8xot4Zd47hQMRH}-h=lt`Jf-2(g`~uZ zz`Ibw1SK?gOPFM6gzEkgD>R%cRN~-&N+|zRf*Qg8Pl?^6gs^GY==o~{goh&sk~$ov z1A43Cxd$rKGB+JQEuq5-*xuVEb`NuYnHY~kD1D{4c`P>tCbd~&xJAuFPaw@L4>I() zBjCjLx`MtN{V4N>`-*2QHw#wk&q8AAX#1sp8Mmn!<+xlLF5IiauohsM2YtJPfA=8W zV96i)Z+NaZ!$Gpup(6*1YQvL%T@SEr=vLJYhxITDrs)y?)^5TvIdqq#y2E(KLr&6~ zh8wYx5`+FlwiWz-+Y$blq$;l6f4i?cT1dT4O-V1t{XLFAo6X}H;3T;UJb zC_N?q;-~8AhMndf_aHq(r45vT8=zL*lYb>$)qWrf;O5EiqGXi@CjNoVCZ)pY8EWdC)-iY@K!!#9%C4Qu_+5RLiHJ8j^ z^MK$Xjuh;gJl!b2-_rwZip)ycRZY{Sd=&#QkMkqF{uwgKJ$r@InmJRS^Op?s_sPAd@Ld3OA=+muhQc00~ogJ3bO*rEbw3P$RU0hmh-Q0*p&mVd<{#h z3&PO-h@B}sr%k}$3$JQN;B7}*v?nm$Cal(viQWd8Y!f5S4=~~*5atP=>tm^leS}99 zuIt&6KYWT>34=>E0v{Y1(UbA^QM_Cn(~Eb*vIH8rcVGxGwaHGoSllb<(mA|ASe!na zD)$Sg((}Vs1zN7MCM+Hng6Z-2??QaWcuFxKOv@O_z^UCUY|OZafu$=6pJm)b)!KzS z8G9gOY_Cv1{2l<l)jL{hRaCM>c?sLomf zm9&y@I;$jt5{F40i!uSSi-I;g@t*I4NVik6p=gdw=72Bmcu~`rOXL;V+^g_*z!wQ? zP~A+@{l0HQ#Nf_?WA?Av8lfgT74Y;*c6@YIker;cVwCa^SCl?>!FAzmwl;p`K*wK# zzDEL@WkKIV0oyXx8T8E(A`D}(RVXz~#{prtA$jaS`uF{XNbo~Ik|E{KhsysG%B!6% zS0%FVo{(VfQ8_XZ$)7A>de{s|<3B3KiWx`Qb!YwBp) zCaK$E@2~2dl+ZHUz$ETgz=J87L| z9bxI(<@jvScd9k$d%0CunLDHW1@*w%Z=CWh-8ne<{MegkayxOxM_i;|)}3g6i&MFV zcSgy7YaCcf)=!FliACqM6{t(ZmOSp7hrYdI1@JJV6}f_HBxhIiZQVnN2-C_!-}Kt~ z-NiJ$k_a`h@*PO;(EXnqkOElPu}-~60gg|GPCQc90?&6~>&X2YQ5IDT%^c#uy!uykyP5fN3!3n}EWcYB<2K=u8ewn6_F98igx`>$q8y1_S!n<1u3ZdFu*I>c); zpO&tUqwZYQSwsfZ3j|>*m}oU(ZDNybou+Cj?wU=D$bzy9Twm4ANG&Wm8o1NLt&6n~ zK}5KjCr?%1&$e1ROICDEEnUZ~lZmu!A;!7;XDi$>lXH0?EM!MNO7HQ^Nm1dHgf zfJ!HpfN;83UWqh+c1z}vg*hY#7wLeY$-Iu{PRsF6LEi--cJu`Mt9^r7D4==Y*`VZ6 zHBpNhPSX&&}(X!ibJf-lSLi!Stmr=rcHSC;KDPwfvBx+7g&==@ivRW}xFHWMDEWZFM zB_c>5ZCrU0sFiTc99x7w78GWnOuBcP6nC$_XQ0{)u}P=jGN{vKX#ILhZ`VH=^!+nn zg0;_<19uOnp;#95d#$?+-QMvO!z~jzOwO{SeT>(J z$P?Zc^nKj7Q<{+X=yS`uPtthTP|>E`2+upE)kgAWBg6m(>?2k7PI`J(XDp~=P1E)3 zWiG}WA0j(bprm8}x}8!=$4)7sZN$3y>waA~sZ%kcxRciIl!k6IcSh-y{uiW(Mx}rK zK(jYenR!lmiwU12Wr>?dBX;&ZhKe+YSu=JJQ3(L4}80Oq1i0c`jzDE!1ZCT%c*Fn(tK;H+R$DVor8PTIzs{(-Ea-r-u+@u3) zJG)SXd{V2;2oqMLfh|fIVx4sZn>=Wwy{G69hB~7U(cFS= zCRV@l&vqyFJb4IZ+bepO9U5#r1{%N5J=pZP5P(tgs?H7Qf1A!6aC;s-fk)A9lc++P zmEU@(QR(hzF{sqKg}O01+$MZDMr+3k`|S~j{(a?^+}@)N0f`gNXeXn{J^d_}vq3fk=d zM1*JmC$m7WV(+>03C_0nbboU2if-*x$i4Xq>96aP>Gn{Eo=^THwvJwuY45rGiEfJ; zAZ4vI?0|8tmL3WW0}kls?3KY?99U6PKnwYsHJ!NIse0T1j^@D8)o|BCtb% zTFj9_N1c7a`aqma0=_Q-7$#Lq$O z7*+26vO7E;<(9Y}wx$f12iSXdbN`eIm!nZ8v9k6x>E6A^0r4i$RQpdUXZaeKB#~AD zkVUnoTmz@@4nqf8P5Lzdh5!;~!+vl$fEunQ1$|!!UW1iS=^lsO^La?ES^K_ZfA}!j z)z_>fjc7oYE`kc5^rz_Q0K01!6e3$~9mMxpQ_M&#tquA{^dk^Bh_3CN0-sg!(YCp) zCV!3x4ZkF{IW9@(_Q3Xf_z%UHvsIm3;%ten0R^Hl%_J$3&tm;hF^DQ8*4Q9L8x3yS z4&B-eO7{rZ@qX!RfR18C1}ogKpZiIX`2gHjh?^DESxQeTj#EUOB{_crOeE6>`q@z4 zQdaK8^3UA~o?Q+2hskma`ka03o=XaJb`an=PaLpuc3^)@;eCfCvaOQSkDPpD zTm5s()j&Q{IS|=y$+lZ1+9Ik%#NJe_IJ>m6s_WXuC0^DoV_GX`g~b;X>|SCpFzz@ ziOQ&D-8866YmlikO7%UwOI%sMavWffCEXbVa>ZG5IqHf4PGg*3rMHupMZj3%25U2F z7++4HE3%RTskWdm%kKzPTgnnWV}v&)VuO3_73hYdvVQ`A68&xuIdb0gd#)619;h47 z-;<;+`NVvnbtISOe_kqvycPZf$wA+X{;`|uO5T@PNBb3>b?#lFwcC5nev$@T3!n;^ zlOL}nPiD0;Z#)9w$p30@yb&3~+q3Om>!x>7dYNmYwr~K0{wL_$B}|`?g|`dOO~@Ul89-VxSYAS!t2QE;5I&nUP}7tt{C$GP zo{qF><#!r`z6$9nP0o{jzTSQJuxgdK@;`J@dbiI`U#|Uq~ollmGuO zCOk#BHO2Oj?V$xf+v;I%3c#3HDlJ*Nu$!irtRzZ7drb?0h75y@O={X1vb~}w&7vd3 zq)r9P?zZv)-@e{g;Q#H={~Nt8SHT$>d>M=zJx?M~kKG3vp)vhiD=3cUfIo_=5>1h2 z$(D??X4`@htq4#U=WmxL z6f3exjao?Um!hU#g*uN_Jf-RL?Fphx`of?zd{3)GS3SAfy09wAmd)GmtYRA- zYcqftj;0fi)&S?oQK^cQw58bg-)^f;;`iVBd4;a0ZQ4oc=MiTh5bO3yJ0w5>1GY`- z_6}-}ts?)V)S)5&zlHv9LLk7mF(H8|j_4vr0RjX`aSO)RiT*C$z|?;%{x zDXg?ezfDr}ngW!0w6#iv-AH4RG?5lb1^Ma}!7RFSz&sh$7%GH^O{wyxyu4?PgsMESH|OW}O(MVlA~g+LmgKEGNd=C@2Mru7RNMR_{|9g4RCY`$Uri zX4{C5SQH5%{F5+bdY`klj{Q6p7X!M*6S{B%u2BW_*U&>#>0Ax0vbks2=B|9k)DSx6j8ri1_&N3XH-z z%+ckbAA`ll@J`z?)ykt(1bs?3ki;CHBvA5+o3EtO}37|1m#d=<6`EBj^EE8G-sdrl^1OLd11gZys9u*&9jAs%Pj#>fmGFl zj!A0C0LjJ3<-oHwc)}B-`QDSl{osjh!rOzsw}M1p0LpC8O>>~pBL>Ofb%G?1u)O4K zL>;ljs`ixi`I>~OrSB@h;{x<8SO}CRrY)4{`YA@d8_bT9?C?B^=>oM;Sq(^aMzA`Z z6AHL2{GBk58z0>!J+ZjYd2{hmv%*bmGXD}j;F8nKpdB7^;Z=zPzMG;qK@2>`0K+dd zlQPGJ%iKi!cVOc|;wmYN!}at5FdX&DK>vZnm%;2A23kwDso%F0&`nf8=%EaZRlpDRT>{yX0XS&!I&3EXc2x@_790btX`#0Q ztYeM1)&g7X#{+{~4Qqm<@H4iB;D!-9B^h@ate`O zG<3V>nhniZ|GNzfW#!6;zLWG@up!D#M#3WfdeYBj8`#dFe;I6M#H7;Qg2(IEt6IRX zWO2|ZeMUwygwrl2*c>*1jkN1BkD(UPBwg$$J&7&}RMEoW^32E^Wr+P9!ipK7kbFFH zgZ*4$4emhM0e4NAIW=0s<0%PGM222?CWGJM3@?e`)Eq7lK(`G#xh+bBsd8~ zpiHlORuV2!wM206&Oq9^ z+^njFJob8ohb!(|FatJ?w#7ANX-%-+KA^=#fY^^(sa?dj1B4d${2eC#u-gVroSKjA3=rz*qjbVnWb87I`ifN?+iZSJ)gQWuUdlVhV zy}8OPI}|l4JKg0XW~m0i+lQ1u!1&31&|3;})T(pgUQKv;51RFee~X_q!?wyt9QQ6# z_BNWtEe@Pl-s33$rV;73c9e@0TP`x}1y8xivj2jA75kIt*llD#e&)FMS!FKtwNjZ4 z|Boxv-I+ZOKFx2hlgfKE{O6wI-fX4HO*)thh@)Kk&dbmI6)ZdNw-Sg`xrfc=VjcT2 zlpCo$7b<5GS8RaJSM7&)Pbeec9kQ!i0aSjlY0@%UwG(prP_ARypSfsNnxEu4_)T`m zu2E90nE=G#OSEde=b(2HjJ@vsac?zD$j7ze;w5@Ih%4u6&vS2EXG_e71V?OZJx2hZ z!o{_Y1-2uY2d1|^1^31;$Gwj#?LAK)3g-ZXa-}xHs|ZtOu?Mn5MObF5Qrmo;ia=sX z;7!S%4pKoFg|p2rwMZ$=ZZ!zyk#J}t(DP`*W5q~i2_Ot9<60R#tv_Opyr33Y<$GPU zoOO@k^t=XmzFlQ_Vy}C22^vmHGOj?vpQo50a$y-qs3$<2Q)vamVyIqR#@GgZc zLBh$4P0eFCBBXt@essxq9M#ZrrAo{VKk2Cw4dHE`W6&ISX~urj2pvH;mpvyNFG`xj zSeS3c_3BPqnIwEZDb}9lO7=2JL%UF#b>RfmA)}_+aYI9C`h^HDR^Wz9$x44+H!{$| zUt0~GT`OdITtI+DK<4i|pG}D^IbuHAdM61DSBqiFWOo4<*MWDJr+(guw}0!w4UeS$ z+k-~@>`{vN#47`fzSZ?0A{*VOKbf>sOlv^S!O#dJ!$FC$)20jrubWJ)W|q zl-Z%<(=X7wgBE%h9&0~lKG&+`2y6=1>J*uKBy@ubY;WR*6Q$wqH>C{C=8Q{-d1*xhorWZ9rp$&%G@8OkopWP{$0>QvnNk~%`@X=@R1p;ad z2BAfjhRe%JZG{%?M!l$_UxK+NRnRCsKj9)Z8Wefqq@i7950--0*9BM~kC17MYc16- z((WoF6UDUW6OfGU@{wo1^P-4c?chWkwI{q`%Hcl`KI!=guMq=Cqj#14as}5Dpr@5? zX^lE))J`i2_u6rIU2BXKn?m-8U1fg{%@TIw(O-H902EYf^BA;l56=708y@jZqsw!i z!y|^k&H`&`{7aI?NTw;?eVCJVu-;%1bQ=P^tkierGxK|03c9cr{O`DvFcn3uNFQI4 zS^^}@eo>0u6H0d3uMjwsfSzIWBYRxF_0WHv-$WAb)2G^a-%j@lAKV0^@3tlgaY*jbTYWzH5n}>`z>HipUrYMg%?wzG1ZW5+H)u~ntNI7lJz)CM97 zv*N6WOkjqVP|D!uwX5vI-&y@Po?~2z$HHCUX2bu3o}?Z}70^`y>YxhR8*QHATXHI? zlTuFXnR}?4v;kCup^boGA|D0 z8?+iNwEc*>HCNl|u@81fwvJt8-+F+u3!)BcxM}_kw;u6tko0^ENJG2IzWfvNiMz^j zf6wHUAx%~8HK{7L2d!3cb=*)crBx4J#;~NrQn-r=Mc~?{;|##qt?UiUKF*y4hp##= z>}O;Choy4hec0B0rPogz%&$n+nMNYK>Qr zO*cg6Tj{Q^XyFE0W4x(|c>9JyD4w2de+P7N?;M_bT@}HIw_RzhB5!?- z)8gQiFp=iw0pAW`>5Rm&n}T6_nn=Bc>W=A)$2SvUv4*F_YyC{>)eE;gDk44g61S%N zp^qUKNJ%1L*@V^^dH7MmJ3||5g`A!XKX^*Gahx_(`#m9JX4>$3{oRYLCEfFHhNK1~ z^f~O$-i)di%i?Zl(05%D9-o;L-XnE*$T}4zVb9EQI7euonLJ^@cMetqj3^7ck(hk~ zhvF?KYRZV5HYw!wfW)s)6g4R)GhFtn7_na&=KeyVIE%yzVe|uOsm&mo-f0I{E8R`c zm%#ddA4eSa*hw}UBmN-?Pd<=uuW1UKBm);8-6|@ZbTcZTUxf`aH}U^$xmp9F(Q7A& zx{6d+HN{NQgD8>eB0lD_@%84!^Ga(2ctWCT`Zg-4H%Fgl#PD85JO?@^uycyPN{sj( zh;odW2;O`|Tw%n2HiwLPhyv$sYAkygZZ${d=WMWv0p+^&PD7J2+a_-LLi0p4 z{pQqjOan>>X8?M$9sF_`0nlo~4auvLn?WaCpS&uzrubG2O=%Se(1?$v6p+SG4sf9E z#Q>68It_%*h?x>Ln#7s4OyN(Sd;n_a02%wUweg@2Gl@^v8WN#1)mAgQRZ|OU5Ief{ zMC~PTF`dmFG{?EWh8o*p7z!lLuT5_@3%|^cwG)J}^i&T)CU|s#$+vm{W)!qFZMVv5 zWxMFzR6T}$6zBib14k-wZs2bUiV|9E4}!R3*k(3~ascRD2upKASTfY2j8WXk4wO6A zy*y=%OYvHIC(fQX2^az=!0U0t=(Q>kpK;zA z6O+~62t;Ju(3voz$IXl;i2Ts}{W+MP1B%y!zKj6^yo&C+Li}rA3@Wyr^pJIN3Km@r z>~}{YeGCFwzu(6~fcIoUy5L#yA;>8a!?=YSN&rjaub^CMyY;mLIQ|H#;RHwo-1l9rUtLem&$r?oxaZ2dGU6 z$~ZBV@dTlm@;0tSbwlwWUycdi$4+sku|mk=EDr+fk;~Rn_CFp~bF& z4d8ox8d6sVhFcp-C%T7QcbV^XUy^nnCM8NcBO+!4sP2Km@@EESl}_w=L8l{p^1JZqLrGyj`iE3#Y_xbmxb#r`u;;;;DQnNPX?UWX z8t`2MC!iVNmGv7;_evppUMyTa%b2It&x3L_Ig-Fct!fFgYHVtLz}M1?bwj)gtbt?f zd13K9ZP~%*RX{wc)|w`i$+oJwy2G^ixIei<4s98imns4EDdHGbm}T1*00A`2KS zC^4;7rXZs%q6mc zz_r4)N2>5_VXV!9pA(+5eUASrOq@Rze7m=U#QcMBasK=vf9ZwG7Y6EQ&0|1@I69A_2~4yfbctR8Hh|%Apb|WE|JvU zwTc#lcf$g>axRtFq) z_Ak+JT45eP-Kc7^ERKZ(l5!!vU75eIe#{aL?Na zqzXWkA$>%xX;}q-vhF(v%_lEb3(Cif;f}%7$Mq50K7)L%gAe+)3iijfl&eqJ_xMA0 zGQ$i9euFRk-+qJ0yOuR^0pDo6mv8}*SsNM!u#Ft9ZWSnh_BDs0z*$Tb#; zOQd)w8RbCV!P3-o&LwgG0FSs~C8KMXiODhm(P(h$IeF#RS`$pw*@3}ZJA^?LUjWB8S>z4R zs3#Cx)U=Uj7l-`S;#S77o{*Euf}mhrnZ*7yAc7~{)K;NxMRsxD0M>7m<{AMJsHg=} zn$gV`U`EJQo!P)ITpu7XX9jP=&B5#L|IN8H0Hvq=DokEsu*-sf`h7X1c`Cx+i*Olf z(_!Mc?HEo8=&lDjAzb1??viS@k+YJ1tyz*AZHA&&n;r{4NiRAGon*VtNsP_NL+vdz zar)jg==8mbxQc6!O1idJ8uz`Z^uO2_)3_6E-^{naxbMX%6!xH zgGZS2R63X}ZUU9fG~xm%Ya|12>J2yQn+fk-V*)?o)|!@LXWJ60(ttO(ZULyJwf!U}eSzecAc=4aC_MJWBA!+F~b+Lcod;v~M?oa1uduC>o{EfdwU zH66=(rr2-^o#i`6XWcFa4F(n|nJQu5qbOr3m=TcpyJLp*@Wfc#{yM?2f3>h2jAQWj zf@7yN%Lo>A;09sN!G2f-;QgaTIJo=)TG#(Kfqqh({hkXM)a^TgB&uod$I_Ab6XElvwf5h7{}vMa77rZp!0igzVGpTBzrN-5Zk-zZ(~Mmfveq~0(6 zkgp=CG}zkz>Z#4D4%I-0NB*~lvUDa?neI05DK#J(Q`^MjQo5!ol4CLrurYw?TT2g1L-CU{Va%#tq~Dj4$ZarFUW$rqHz8V28LMmB8Z|ZY z4qDG>tTkbJwq|S1*EKaQVUvIJgiZbxLWk$(LtvDXa0juF&(K;GTdIuq7 zLdb=H%4^Chj?8?f0Y`icx(8JY3ukb)5Lh+L_8;sxC^Id+I>1JB)+NbfT-j7XIHAnpfxI zcLdMs>G)Y;{Ig5qALy5Jq7yj7_6@6=x=t#SFCe%Scj8$+&J->^o5p67jZX~r3-UFY z7zv}+WZCt(KrIq34 z@WZ%mV2)1Zh=Qvb#3{vvKA)lw@k}Ndqcgi*CUX%Oqo1%DYUz%o&0vGgPpT!_pgLfc zh!W~=1L4A%HL+10P?wmaS#SdBI3e_`(ZKbT__bs33}N!x2dVB};k~u%u~*1??sXZF z3~GcgpG(6Q;rHj};Vi+jPD{P-7am==7CVK@>&Ap1@XL4c&OYB!Nl3SwhwYF&FwHWC z+*FNce)SM@`tyf}fFch*nIUYjYvC5myY?*VR-{edoVSbZY|}|z=AO-~V76(Y)iD|WCJd>~N*vz*5ns)JXp42$Z^rrc;I&xXA96bo zs%qya&jUqZ!1p*Xk~J-R;A}zS44^EO9sqUVceQKqTSD1-JEG$=;aXH zw>^9$%$oy(3TaQ4O2e8C_=JH=p7WAAugjTYo5Fn~sf*!0I*g(3ao;b!a2b~-m!==J zRnONictR&|;!B=M=}bVr(^&W`ObaU`Cs+iW zU=z45kJz*+bZ>ANhj)Naet=1hX{Qh3-NZ@s9^sD-$@br1^~eAv#4jf3Ylada@B*ky zK;=Yg{CVeg3g}1=h7hoSGcMQ<6Y}>!CS0bIaRIn)N9r~}-EgQI^gZ0ir0#8foEM;^ z03{nktq_6bYiQ*K(1ixtkM>3yt<9I&&F%6CxLdSW*uD{z+QP>h^*BRtZ%n4n^b0pP zPEj0eA&X^+P`YViba6kZ$28>foE&b__WH&OuWrhFY(^02!J+pVxR#o6+e7ZIiA}K} zM#oN~hSMW-d<37|9AUG<^{5!W(J6p$di>gtN~QBN`7;t~J9!OdOlZcM>9(QI=xu4w zByrWCDmU1s+ftvAJk$B$zftQkX!Dei`@97Y6P7=3$6CSr{AgS$jCi3s@@jyvKl+8e zzIO+N*IvjRI?(@L3Lm_iBKb-Jf+Jz5(D_0fzE23gFhZLIwHS~U7IQCwqVy%u!NE;G z4HhI{EBFIRz9gZnt^j1QHFcx$X2DtapvevMaiejMld?xz$yLGt=y1q&T*B_=11=Ux zd%?g&E^846Q}QLYklbY=g=$*JB}Bnhmm)0OTxkErpH_hj|6+^czmy^!sm+-{jnVx% z9Y$yd>9_N9)%a{QpVz$K9QSiHpVjm03U}GyJL!vhBxo zZ0BDy@9)C&J6$xhw~N8sZ8zMq3PMQt`aiM_iYW+~OR>1t1ostdnxa5~ZFSc385|mp z$JN{Pe5|tp?AGXFO$!0(YM&nN8P@Z)e0WK{&BAlGHn8S)!TBQ0*m5t3m)o~wQH)>s zbc-5a6V7hQvvl?OY0xA?p5bK~MqawO(IcZ;=V?mOi}guoEAU ze0_ZwBs9tQUSF=00u4Ab5vYJ)Vw10yd~JQ?YX{&dL{{B~0)GEOVn-@)otGFR(x#Tf zinX&K26VKkFG;J~k}He5E-y#=>wzeY#2-P_$6P`sVZkoI87^}V*k#nfpHjz;f!>px zr?s$QDmksanOwS*ssg^O6EV#J-?x5s2X)tz?jWd-k2>~(vlZ;x{s$%YqnV|V=a|!Q z)eGb)aPpV#g*f1IfCC&c(mg0KDe|uH2(5^5JD_-Z(glT;pF|u%*axI=N4tUrmxLLu zEDzeUk`K*Ko-vi$-|Y&QO+J0VJoR*L62+lxo6CKTvb0y>qXe{6x4oa(lFWLX8c^8VJ7ikh9N&R5u6z8zuSg!k zi3H$=g&@8%jXK;blx&-VUl3m1_AzKpE!#`Op4yJsQV1)A?c0-OO`()?`_kxT@U;v- z7-twx<;1%KK8rAF$8-24;o}`yidEp`7w}CMF7D7KFFb~Hrd#pRNPOg&*z^Lw=`eA( z8_J_m(}hG~6wVeZgsHQTSRh^Uj9-ilZr5D+|IvjHnr=l-C9WVS^K^R)97F|sDchdYX46uQrpIbVyMIMOq?ly;=52)qd zpwS^F*6uc&ZVj!a?i*h+H|d?mBLPWd1FC|OPPzmIq6Xe84Lg5tA_9B8LzLCNS8BRN z*=wnydrM56a??9qQ4AVB%=wcE>A$>&EP1ei#TTgN;J*n_D0_Y z7YOR~o>DMFod*NQJ6$Ye>WnnCdbYxNP%aXka4itPz($xc0>}~nhC66vrF*NHI

      { zKjzq&G{1|+SOXZ$J>Y_}liu|J=4g$dzVo^X`zeutd){QU(2)QH!JHHo7)k&E%&~wu z#!uOM?xOErhxn3%pl^#~5Ph|Pz7XW05uyNlcZ7hxdsn~+m!GGK#+H1S1i0f?dA{;$ zB5A+8N9T|1PO)hGkv{B~cUN`B-LLgWdebc92?)Ju{*3@aA_1W|EWrA=l-eo3{1$?u z?D_fXFhE}U=`E$)`47BQn6_kZS2%9{4+6_NaT$Oi9Rmb<$SmfKJbkP*2f!Es6BuR! zcMrv$0JXWQ^ee7{OFEO_n&&*y6-7PPg%t{aWZx~*B=FnunE+EG(C|U5jIC8 zu3b@c{Z}ldzn?zVMMW)!gC7@N^03@#kBxiDQ_D4b9_60$7`aN%M_wv&Y)Pz#&`mm= z;-I~4Re+9H)fA>-CrQ3BeX#XZmumEIM&fyQtaDc52xGYaTjRyK+ z4HE5*y>jrCdA6pVpJhSf+r3Eq2YlBA{MEˆWkU8(2?c;D2Eph7+T59V(MPx44| z?>F?>w!KkM-}?I*?&L%Mt~*XYa`!k3w@`}9)biQ2C>2D z2ZclEGzH&)eo7ky@mL~zf^_*uf56w!FM$EEt`Lv-!czy+IK_l!Ij#y< z8g%x0I1N66K*JsXSr*!=5$z^2-{*iF35P|c%B-^T$W~U1wUo$Ei8e-i$2YQt0l;9+UZh;G0`HkCc=0HU>A#8i2X9)`3VLvMR30n%iQt385FL* zk)2r2uQ!LEgAY!|tT)Tg%PP0?wdNPWe5n!)Z|d=TLe-lY_yggoH`B&^4w4@ek^$d? zOEE6^{y`CZf+~jbgNz8*62bN{3qH#736zqBN_`p31YOss!gp^zg_j7$Z!O2=!jZRD z-T+iLil=54ji1f z_iW88YKjBIr%^I~Hox7RoU{Zy4Ry{Efb&$ae$)U2xeU7{v4++IbPVY;? z_QY(sJq_U{_}IvD2+mBzVhG6)W3qcAehjgmN8mQXg2DW~ix8W5H$CeASxRb|eo0BCqqDDS3ecLp zg$x`&3xG>(ih;fW(*9Wt9QHu`5;*ey8;Jh`@!V1d4&ywCS@VIjQ$Ra~7>pqd23e>C z<7C(6=7!9bz<>v0kh4BlKxoxsebr*1RgBF*qZ%1FZZ|;09|PI@C$C)|&3fVO|9ZyB zf-6)fE39CdY_>v(;{kAJ3uuH2P*8Mo>I!Yfn8_1YC^J?}-nv4bcPB7~+XH0-SQr?N JO@6q-7yu|sB%J^N diff --git a/boards/mro/ctrl-zero-classic/extras/mro_ctrl-zero-classic_bootloader.bin b/boards/mro/ctrl-zero-classic/extras/mro_ctrl-zero-classic_bootloader.bin index 0a9fb48ed280f9295b272615386f0c7805038ec4..619a9added154a2e0f852eca428d3e5009c36812 100755 GIT binary patch delta 22619 zcmagG3w#sB8aO($yGb^ErVk)}Z;}?;riIWJEFzL7?e-C{<)QM_K*1A44;Ao;iX;Wp z@=z;_oL+PMOr3`GoV5G*``wfNfI;Hv zVI)REz3+xmd+`{Q&e}0bXW&8zrT_8{VrwckA3ZCf0^NW^XC83me+u^xS+IZ`kskGb zhyC`GUW9vH;G1gPX6!nfMfaSGt?1l0G^Z+ zcsut$8C?3jiqleN`ds)og#HWDsX>%?S~8|rLS7D3K?<8pqq$WTK zrSC!{CnD1%%At#hOh7Z!G+;DAccJ@w#@~4xKr)#x!reK$G>~2?9xXD76o3z;yPy*j zknodGXX?yd0F+mu)x=oONh&~90l3ousY)LYji}Nov5-<{54p}s^Wn{nb4>#Xked(4 zEg;Wp;d$+8xIZUV5z3fM0}d#!`r}z^hm5?@45%OifJgvHg;0aB&_L|}GzhT2HzpbZ zt}2~6T2o2}tdX8Mn0Ev>;^|p#)Q*hQ0%_8VNNY5rN{UvbQ5e^;?FeybuBs(#7UHn> zJk&DVMNFT8n+(foiPfBuR7|=B3ew|@W>FO?(OAw%IRylm@C1Q9BUu?FJ|P9Yy@B&m zSAkhX)#gw;T>$qzlz$KDc}UMg+5_c|d1f&Pt@Xh3FOdHWq}L(6UXXKM65&RKjGrL= z3DN;b2MSbeqi=y6XwIL03-lrs#KQM7ZpB#3xC$8P!k9XG!13sYCOkRD5nK0Y)2B^H zM;QI5=B@oPb*Gvb&hQZu?>aH32~Ydgjk14p0za=)Q~*a8V%;@2%Dw7@H(E!9a(di` zk7`N@*;odp3(qHw+hBib2C-8!blDi;`(ip>A1zBPx=Z@Es<NH%2#DbxtZy@&TKjUn+g>_QdVa~+X^ICQd z64QkDm1)PE%1lbjg(21e7u$lxV}1+>G7{$479=8x{M-G4v22Ukl~99wP`2MyQ%Wd? z%doigBx+YiP{8gmrW%&VB6X4xQ`_#Cg>`q#-l=6gHFAB;mKLPp0OMDKLREy?eqm%v zImh2=rNztsd<%Zp#^>LaY^8Mi8Z0V(m#!g9i&usiUA{HnhV>V;)>xUcvp`v5&jb)U#3l5i?nH$L@N!gBC$h~i*Jr3Tf&== zn0LEB32qc(yFW3M;Rs^!l_4x{_RGYVB}S(#BUKXpvQX7&l01|ik+3*P&_u?`zXXCN zL<+Y@CQiSfMIPPVWp%5*9|S!7aj9QEB*`a4jk; z`U5GGmmjTZb_D@D$PgY|~tR8lMTn(c)uLWl##s z2$aNKytj$mzdfYs$>ZmQAijtE8y63)MtYBPaww-%xDcH(exJmoc86*{HALQ_?HBP` z)IKH-vANg0l?)%n<6V1r!Le zJQn;Cy5H@tl5$Xl2S+5@KC$83!;B@87P(>VKME7`O|pm;#KhXS@q2g$kJ88R<-A&3 zW1z)n{bl^KQk{_&pYZd^vrpylR6!vx@7s#8_}q}3uk78*qRe6^>SMzWdRX=t&&=qM z(7rN2c$uH!j~18nxS$H2ruyd>caL5m(qa-V^>W_YA!TYhS$EgD`8 z+<3^(0l&R0kup__TEoE8Z$eXSO4g47hOdX2cg!zKWiA3QiC+aW`IEhl z9FH<+@iW02JG0;jJkjDOgy+PDK%X0l4X2R!@~Pl;q+=?Wa+8#=!ufCOeXgLFKluyv z2J`2^I8)^PFx7(I!$DGUsn8mif{TTJ#TDUvAt63%Qq;&p4-wWM82-u380p>VtwC@6 z2*=Bg8rtZCNUV{}$(UC;aXo#I7E6Rj;&pgXcqx8*>Zs+IA~myw*pU|}olDS2nE#c+jf zNc>d<+}}oUBWUovhM`VrNzwhQ9BL--8jDMe-Y#=g=swLSL^nOLgUyL1U`$c68de5FD9K^Oz7R)6< z>0Lvk&kh@Bpu|{VNIeNx30Vm<@mIpCgskXyMt*H3Z_e>R+4d^ojf5n8SZGVo#MO@A z0(MGxPA^Ox8NqH#mEcK8!3Tus#M_pPhbd-g!k`0C;+PS{UAGpt5&rkPRV` zbRc-})mxERJ!rUj?-JK!`~h7ky&{W&Y~A>Ym0gfT?#$xGiOhy=O$mKi!IQoKB7p^QbW33@by> zyEpiS8)-)&|331o`+Vzf{V`iWh6+al(*D-3+PwC|9e~T`epMX@T%GJkjSN4^IaN)h zB?T<}9^XpqI@+UL`!2F^3a)$3{BCSCyrfs9mY=dTyr;6hE_=4}QAsr>2 z_o2OE<-1L|alkd&EUAJ7s8lyvrw;B|{u9BRIz4TMKizf{re`F`TE?b;cOaO)D!xg# z@sNpj1-v7|tEuB6-|_Xds>()L7BUNESGCNO@>C2AWPuOC)j)pZW8tOePJj{*DeJ_AvSuHmyAZM}fs#^}}y)dPIge|HJ2KC^6#C`+UEx4u# zP24#9Vd#aDSN5vnBF+;bS6(q!(s6mPL`Ng6OK74&ajjogQ>royxoZxP4PPvkDS^oS z^tdr1D>I5`9S>UONfWGSA`-uKpaG)}>axcM(Ig}`IgSk)Aw2@AW0FyP-_g;JG(qp@ zL979aZ$?7K*chQo!`NSO#1GU|p6RCzeFl$+!O5$qX3t0f(8Z zoq*ZQh;~YcphiRwfsg2ovWFV$w>nxwornF=c{;~&ji?Gb4hwZk(_7|XPw>uv|FW57@-Vgv1jvavjY3JF=0y)AM+W;T9tl1(n2lkgr`Php-H1R_b*Cb@V?67JFQ_%Y#C-9qZ8 zAwkmRrTxX<_6uvo;>RDcU<~=~C-9yi11AML?+-};}=e( z=dl|`GI^Q!ub^-gtGgmWM{30lXWfd>N;^|<|%1prYa^RottwmzTe6q0Rv(@tQZ2l$44S3^W)m68W`w{Oh5I73k9?wRs@MTtN=KaCr z(p*ELT;6$HsxlEf1OcMAuzI3X&V8*^)<=g&d!Vn4Sg z=w0Bqu3?*k-uZ$#dm5fCJe55Uj|i^pB>Y$5*X-MJp9~nBrq`{0cm#^5=yUnK9=-pyPxK`rMhya@wP! zu+AkVmkCCl`4cI*P;AriI{rMdX@s*zB=rYD|1|cr)Jy7)_`525XN_xHsAtBVKSaj} zMLCnF$}6@Q5eGV~I-F>)g*|OZN$TYflX~V&+v~dJUv0o5jd3T48|^{wbHIqg!JPSJ z&!`7Ce$^z;(sqF~;=`USqpJz)Ug0Brw0D~6W01l!dZT1NH4m;Qt7)>vV%9cU^VP*- zTNZ!KO%Lu`2f}E+LN65O@`>jpmhI?|Bnl|>OK)7(UqsXEi9#xHW5<@UWlo7HENaq; z6x{)LqlN`iY=)dc^14usXs(u45L-DcR>Fp9_Fyj4t05;UN;PsjoB32dC8!yUZ zI>TqdG%f5_M0B2)m<2Mf1WYm+B9@(j=CL>=LAu~pb4YaJYT8KiH7%A+GCqP|tcW-- z{M(S8VgteUN?q(-i&A5XwVRs!{hqnlVy<6k?)}6ZE~HI1$Y2aq;lfEns<72iXqQ>! zV3t$q!5*VGi40gUkRDz*gu5ECR+Uax5w}cciCOiP9CzaBJ{Qf6c-NjHof{)*WE43h ztB_k%%VJh-`yYs9r$*Z#FoiAjDu$2b%}wS_-N3(SlLH66KL&NHlHytm+k)Qjf339dp$>!~w@F`)wZMyon~fZ=>!oPIk88w-q5GGEM7D$BY9j++ zPnq2bL^cngb)P{>?voV$PVJ^JZe01T=DB#@0^I-tgG#-5Ue$>A8=r1dYz3uRj5&T! z)o4veHL0oH)CpZsAXH%Ob|dMEbo&|P!Q=}`y&nQv(&rq+l)ZC$`8orByzR z`xeq7GVeO}dENZfg5u-;TLb*2I5W}0&An&Lc;dLb*miSo@w&b_C7YN{GLe?8z&Q87 zLe>=vFTpMltdp`Usqe)$oc<5@9EmexL$YdhZs>4Z5+1yQ()WlD~WY!`~^S4q+?YGkKAHWzfL)gK}|Xq!-rI zXarggu;{j6K?UN75OEerpEpYf^W{^x3wkF6dTi<@+NR;VZ4IRXUCv#(l_&!=rLamd zS$So>?op**R%YP80JWG55~Ta_l%O{y&>%f-kbBOc(9nsqXzsS;sdaY940@xXaK>as zt`4&6;O>%ZjD;v)NHeC47^f>m42It1%y6(K#%IE;0&_LW)D8re!>r0QYIWOn12xq; zk)d^)DV=U@&^vY52&;jjEa>&a_9d1Ey@x;^BV6H(1obZp)D@t?K-4m#2gc53`2Q~^ zjVLE93T9d}uy7n<(J?~=7I9!Q4KXGe9u|g&=rVt>ooN%zpOxeDV80M%=FhOl43C;# zVPW!i1|>I8w#dAZfo(>lIlWQb>_CIN9$h2ynCx;7jgULWV?{yl10%bEAZz+h(_10k z4dfcVf7}2s4Wp7IONulP80YCWS3eaeTBBu7#xn*cPtaT8pVo6+8dq~%O0cVrOG#X` z@7cg^X>14EJhu5GPekY6?fMEJ#b?`fSSR zRRVC_Mqa^mQrVO%RgOBx9n) zPlu82P3b-Z3{5R9rqNiR?WFV(PNYBYLRn{BAb!Sm^c&F|j~RQ-$oklr9xU2vx&E`R z(|xDuXd!N@&Q9L(^hlHYPmjIx*ey3f=ABNI{g#WgN9o78&?Ngn^%1Ctxg~Q%vIz#Y+6{O}ZLcVKZ3 zRGWKo95K|VTD05ajLIhSz~*(j&31P;v=M&fyQ`XwmC&mE$iLy4K5`!jnD&9-2N>`l z{@~-Q+KqFd)cXPHalrn;XqVy#e=tp82xZy_u79A}9&A=rgc;MCOas(f?dBh^f-`2V z&;7?b=NE%PFI>RLl}{hNEFEp`mg0@wl9~gDQa&)`I-N1zs1vVM>jrvsx`C(G5oY~H ziU+0qkRyYR?gUtyy&IPARO8eLqj=Z>8HGVjLq$>qxY5K{9S_j4oiBqUNxcAEXPIM+ z?=|CHDBCFJ)IuIW)>kw(6Uf+FloNY#M+MgGoK04%O#YA6iV~0eez9>)lx^;+u%;}& zzEmR%>)cZQWoQLUT1DHN8o&l_2kmR0???H<&L=D>56VENY4ymX=YB665M!G|`q9g^ z%_040AEb^+C9coA*pHjgi2sEdMYG0P_c;h5kM2+I|+J8!h zN1lXX6loP8x~SHedx%$fQqaNnO3@ge=Ckkc;1`45TfVpY!eOreu zKLhtqhPIF=*W*3!NcX8=TNz2#(SBteSuWQA3|TCzEXgJ$uBr`sFAo21HF=>+fjd>U z80%t|%Uj?^6ZqNviX!j=R`!-AER<*t2CIedm2)5A15+c2By5f`BsDIrifd;UM*75w3E_hSCAIeA{!m< zTpfCEPEWbWl6LP1tJ8)`|H3LfSn)TP$~}j->tKO?S0asa<>Z~;fLTepf&Iewm3x%` zovvgK`NKq69}2q&2!##4@*7TRe9@+>( zu^K26wWgn@u~>tPdZS`MJXU9~KeYaK1=Y#wNb`OW1B>9TgWgGgRVb%W9@R-VT3V?_ zl24E-1czn;*y&R3en$udHxk1#>q%x8vsie>weadF>Cc7G3-|xSO&a{`(5F`mw*~5^ z+omR}i$5?OY@f)d`JR!ALS+Y&g5GC_rfsV$en(;*A714u=5C}!ky63JbM%8zDVTV= zk^bP-gxRb{<{5(khbM<#8X99jdbYboN;2r1R&T^wA~vmF|I*df8!4^iKET)q&%GaB z0qfs1-9Qkwc?C@bB3J{bk@*h$@H!%!oU?%tFwZ>DG4Gu92tzM|OgHv(=9P(*B zFRZ&G3r`SUy(2f}`w?Ip!2dpp<*!+Z?gHX}JK=|#7QNuUgR^V2z@tUdqg(`^wRYJ1 z;mD($hS%~Vke6Z!azsqI)eOExC0ya)p@%dR(lSWPAhkhigR~CPI!F&fdJxhtA^kGE za=>8)aR!8(c(@ASN`_0F3GQQXA$LiuH`-UgaIaoZRFgk2Bd_*Ch17CZiYU~HXdQ4L z5Fi3LGoo-IIQzGi87Bn1+lT7P0^Vms|67Niy({S57JSxHIWVvmfhly@>k4cwr+6Cd zHpvkt$(n?DlQp3IbUpPb(nk2H_~iWiRwS%s?4AuWkUEUTqKbK_=6o~G+afJ7t`O~v zB72KeW_)PFntlu=2c(LcD=wrTV4JrHw@NBlu2J~`$YnaazXq3vmCnnXCJWIuh__7U$N2v@(;gm z71HBwJj3hKtqMsS%kHtcLGeTPf&adc41^9?2c8Sbvst8xhriHhzln9#%Rzyq4=gXw2R(5z z`Da7_5utxo=s!O6uZEQ?S^{HZ5cmS%R11O-I1s;JV#OJ$V8I#Kw{jt5AbEk>#^s~T zS0L zNHeez!&RgagE-8LG>evvso1-$R=d|4@cs}0)qUtuus})1VXy5Y;=2z&%%TXm!ah)< zh&K^Scw7Xd!%HC55so7IWDn5`$OVgI4_slxM`6W_$U>WsBCWC#j0X5=$B;0gEbVWWEgc@Tq&J>6nRhHYpqafpFHQ{$*sD^L@$~@l=F&G>%nKI%GKgx^%pC%(N@u5r@ zdhRCpVFHryQIR_BrIR(K#I!|RIjk)LjND@+Q?jg&iiOQ$%%NlbMQONj8c1tXoC?o4 zS%w%bJ7SvDMQmQV!InWsblzDq`Trc0_aW8RRl`kM+X35qrmS;6+61dG%RGMelwh@u zg(wY77fZ|?q+&W4kEFH?P=E}44m{5ae&mkjzH=w@e|N{VknQ~SAhAY(qd_z54S;w_ zoXNx|zeo7Q+!=m5ahI$1l@5EK7Tzd+ONMM;8j&!&BmqYYe=14A=Y^+BvhWwek&@{# zA4v}ZQa4r|Hz{BxM&dcaUy_t|4ZK2;7hjTi15wJKh7=q!0min%L|{G?rtmZEpMxU= ziR+~-9`7Z-vImA_UQ?3AgiOwym%QYr(ap$$|DL!oX9& zedjTtmDOjimEL}w&N6%wby{g-h6ZB^SZg+?S!JVD%IIffB0gkI^+2>tw| zYLF0uguH(nz5<3i2KuMPMwsNjZdDsC{@4yQ(U56^wX6Zxnyo=^bKt)iO$3Z;pcW(U zk!1W8TZ1VUR2x=qfL1mH=~TtVpf_1~u2hGg5SmKInf61=GI$%}kdoT)blqlE8`hvz zLGSR#1h+_DvnoWN5p1BHS8O={3b>EJS~5c07`^C}+(JZIrd=pQ><+jr^AT%Gjgjzl zO2RXdeh5M+XkOK_t0}CQ1qTB*)Pq|AX*oWzM%km1@GM%w76jHjV&Ro)ewxQJH?ubU|JrKx7E(CMFN4Qp=Vh1Px_)C(tUI2}q2(C!{ZOchd zMl|ch`IMlyg<=k-e#1AEX8a&Xc;DV+QcCUeI6+Ke!?dM*F+VeBR@X_7KKf2)9HdWJKWn?fJX~1u0GfZlZ@Vvkz+q=$(Uh|%Ju9Q{_tklb>Wn8B4>*dy zYDU^EJ;fr$6pIYgw}kS0lsX#HQI#0DkS|CFHhq{OjeJCxK!Q|;-{@0<1zaGm=-&q{dT z=P#V}RKpM)tPK+{)AK-U_^S3B{#DCjiD_&Fy0GngctV9TKEAyO_U_zTtIYcSEY0?J}W7lZF25cn9tke zMJ74|h>DcpzEQ@B5z%HR=_%@L*PQ-C2w# z5J<+Ux0QoziKjM{lI9s0u16~3Kn-}r6474IH}G%wu}WnhD^~-juWG%6M>$6E#O6DT zFYr`Ousc)pWUaMFG<`!ELbggZ?Y*#_+(a`J;#~o zVWKB??<&c;NO*<3FV&43_m*T{3*;_x7%n>2N+l6ah=0fOMRb z^}2*doU4Ah!>U7$*$=KqzrGC;|k5+vWaIUe=EDue#y& z?K~sYmogAdm~BJ)TR??0{{N(c4y?wlJkz7}1g9B76w})X41uoXX$TaZdl3+O{7Vm_ z-|JIS3&({1hSp-R!fo>L2w%&{(cTL}%bF!|z7AlbKif-~*3YhtKL`n9i1 z!d7YcYfJZ9D$t<3#w-JHAp|r?NQrWJCQc_*ESK&IAOj?lbA`Lf` z%J$+s`n8YYO((Ng+=jOhn+aDAT&N=$g!WaL{N$|EcGA91RN3k0;D%Hrq}1DHT%x9e zflfJ!)R!fCo91Ht0J@(HVSIauW~HW~lnfKoJvoHp1$l1g*B%s>s~H_+gXW}18J+R{ z=o15Ihj|QmzZ>r*992a7r zo&pB^#I4tyb>qqJdBVcJYIeE5fmwptNDrrkIW+w_i8E*w(Vf7I%&d|~7hinrDxUcV zTbGu+*{6`->iW(7QG(>np-(fOrB-Ub&M{j&@b`Vu&aB)WIGO z(`jLIo-)KF{nSh#@NOiYaAb)%thgi%7Cy(#p&o7rXcIsqzw;TIACc_njnvKo7+{f(j&ME(I?<~rd zCp`YEgt*RF0E9j2{#(SB;y8Gt90MHuYk9te4wMea)4Ra85+e54dIN@tqj=qXIA%>yO=k*b^O=-z3_jxJ8{5K ziCrMd_E7oV&G);DZpx{|UMhO#z@j7l&<0ud$nvJ_lf#Avo2tG0kHv$KUkfYX=sYJ4 zsa$yKC;S^FS>GS*W6-{m6ClsZi)Wp}jrql?{Q95w@iU-9bidp~$@RAQ_63>^p$YvH z>6T9HrK2x96Tze+_ux>uUc+gi-TT$;xtd-;hV*17%SA)!x9;lHsP{7YxxOtozlT*b z7F39a(y#u&_>P9sJAXFt(V;+}+-s6KZU8-=%***`KDk{7n-rP2V<4{Wrws-OKh*MO zkhdNmQf43Lr-z`F-y8DYERjiAzpjs^uYi>UlmWqS%k#MJ&HK$Ay#DDfp>8hs zrx=%}_lLDIgF!>~VZXO$7-gJFKw1O8=#e`fnPD9bNI8DP81A{D@=^aHd-SjFqc=L9 zeEnDR>f<-~Cqwy{$PWI4`}JRqkoS2Ac4?=voYh5VVD9x_?+_B^O|u&;bl>N+@GE-K za6=LP`mfnf9>4KL2$tz?zQH_+r#K*A;gPYIrF{_VxbNtk>#A@@^h;~NPq2+g_1#G% zcHa!4ce^gl1HqDETBKto{0$?1A#LV&@K@b&qj+R-FaD}} zlDnaRZa)v9&2&S+!|>4?rQs`!@pN|DF<5M`yAHT_%~vbY+lVcM1@(lWnV*KWLeYH9 zY#o?d#f#u?0mmjpC>5((wwvO3+L^oo=b;?QrA}0}ks))yV2$NXtpRV42;~Jz9c?91 zPSTcUso2n{ke?5DZwgKG$7zN~nABe`-gK*AY8)FPaa(tRdnEEAsYO(mFNJIKCqpb% z(%qW4zd^~s#qVGm+|FzG8XG0H3YB-Kjep$NzsgeFzwAaxWH&&s+k>P>Xv3gtGq37z z0(aYxu>0kLfj#NQUka5xlOC`nvRC>qdGB!k`$i^y=NA7 zA#vF$97;bqRZ~h7qb;Eb10)6^Vz96!8oV+34RPWK$WEUs6rB*vEG)ez4gV%Qbx#t7 zhlIWN97uq@dmVXpj+qkQnhTP_!5^5rlT4dNAVYRu%Y`^#4qH009@LBUA zSV!AL{_*X_Yawv(}c%WTKllYA^qSL^?bwCLS@G z^zU*c+_m|xY{rAKFePyCMIRi`!Q-D4aqmkFk4+g!z1afi*TtB;U25I}V zP}^r}=|&nXLNv(ZAJ<}CrCmhf6bHmLFyh<51(DJM;DS^M6#rA9e8h-vN-#8r113!u z$b0E#vgkmFG%die81JZv+Yr|}6UINTrs!rYO=;u@(S-LUHK^VP0~6c`LW36YS$wz$ zheI5F@E_4*GhNQKSIBE;k`wW~j3X zwJ2i}Z|osc%nIuunH9(3IswA{ zj#|uq44aO^xkY@~yk$VReNnVMZx#r2;E=JqT|hl8(YJBllSU@HyLk?TOKs^LH(|iV zOd+Fi$n@kIs?g-=Xb6@2L=Ya|rzX5cpvL->fi-2OTW%;#&?{-0`2PCqf+?>4vMM z`IkcQy8$BeKM?PPARP3wA&9LZh%FBJyYWDRq@avvG_rab@Tf47#mnt*^8%>=_U|>J z3J*br)lN=3qkLS3{9wR)A^;T*%3cC1JE;KhkA>jTx_hsZh4W5;pV$3ab82o?7eQ$j zJX@TV1I`*+bOpA6+3qadeH+NOG?vVCWmy_bcepM~ZyqHOCB63WaER>}{}vdn&>C1! zGIOB*17PPk!p@`2JagpZpGT)`>WJ91E;-Ug*j;{*(u|f*8d<@Gq?5{^_t`cw%aZ6M zz0x(ANAS+u0_1;Z;2F~u=UEVrV)Osoa;$v>>1g4FpGSq8Z-KkYfV+q+vh*q0X9!Z* zODxf|P$t{121NJ!BFi}|Eq>sOu%IS2+0pXCXPY%@Teg)Fm&0x>>&~=tHe%2Ucr_;r z+X}!u`V(;I3TU?n(hZ^YoSDVhu$Ueceq6%ora?8DY_JAmWmCFIK3J4!AJfu#lLEJ_FJU zof_92J9`zc2h>;ls74KM<8=ck!0K_gDPcT05KRb&twQ%|h$aj`NQnferd5Vuejc2jHmH{@`ekT1^|Vry@4pPb$J1BAj6HyY`xvEnsY4vWoGj!IFx_>YxtfA^8Qcm)4NyMwC7BG7-m%=yDdfJ%?7oO~Khe5sqE@7W- zDxN3&%l0IGL72CyWZI7-MAwx&i}-!OEeWt!1ikWL=xkDL@H&LClF-#A+6ICaamI6O z+g9LD=tlTqRS~WgbPwvn_k0Y2a~g*&=-n;Mc~C<|jtJ`?ToPLoiu7L4G^dHRu}vf1 zM8EK0jh4DSAUt1Vq!I#xv!;+4@gDFA5s%bUcMJ=!J)%~FL|wVn7Rft!%}R^SsCmU| zgLba~@FO{RqcHNwZ0fCmFl%ilRUZ)kvUWW6s$Y0*ZC+~1gAnGu9;BK_5qldDe+g)bl_oQpy2KjWE9^L%bLDXdW>!NAZ73V-+O?T3Iy%U4X(eB8xA#vfbki6bx ze+10`ZZLFRlAAxcexibJ0eCV#tS`n&&^w$5a5o5Xss?2wR zNvh_o`y(*+3fI>sW;dA30CgXy;PfC;oRF4tdmRnZ3U2Qs&$=~PQ(TIP`J@%D-Xs_v zO}3wKBCesd1&We?Z(QwSM4IW6Y=$~%fe{R^PR#uZkJRE>vc%yAV(Fpto@KgWp4?cG1zEVmhnFC z<=}2<&9G?XJpg1xt%m2Ni(M&pv3=Z&TUEZBrK?9|Ex}@yc^J zzrDG!SpXL}jK5a%{L9VC<{c)rOZ$8*FCvTzyU@Q5`sM+3KmySdw=nG~@gqo^EU=&Flzu@||11Ewy-JEg%Po z9(C$?s^Uvc8O+#>;dk8_IIIw6_L5b`o67t>5Ds$P5&OOIrXqBI(9tw#g5#H;JK*eD z+#b_JXVcQbTKgjB8c{8Ks%OnWl@%A$S>7%>YY;3oa3E9`o3Q@@l(7bmjv~?RI1iCp zan|F~a)aR5Ev+yJkBD$+7>O6*X#td61BTx!Ed+OCp)u%P{gH6|&-c*p`&)#_H5&Y; zFlkMKiW>$ugO20hloo-A>j?-8)=Z@Euu!+gDOfWTh2syYREq3&9{yS$lr5eWxIH_RO7q(kY-ITMt#F66ha|c68%b5OLt@B* zPA+y;eJRR()%l&fsHtOhtZC<#ow3bH&3jGQ2?Aj|tkuqk)0tuKQ$ay`IN5%0drezS zDN!+BIGV0iz#b_(h%`gqdHza~Vi{efNJEGxR+?`v;J%Yo4!Q8%HTK=_u7zzM_I@|H>~k`c#)% z@w6Rowo3OKSe;5^18!Pjs2mu(4!CMx^)t-icDS?FS67>E^;B<_==v*LnZd>D4lIwc zoVgZNzziDaZIP-rpO$7pfarYFbUva2i}Qwws1)#41V_&>qV!>}b>sv0l41_RA7=Yy z{6P>5z6E*ZC%Eh%!Jnb!>7!5E!Yfpom!x|Q3{=OWVb}(SltU0z9;yT$P@ng$;Y@hC zeT1AuB=u@qB6ucK50eLp$(eNecr<2qCQNkr6a^S|6ZjiTaK5XC%4;xG$hlyj^^qbu10=)53OT3ON~;;*6gVHvZkg@Hv5vB2yn957sy6}1_4_Qc<%PY zrG_hoc=5_=N{z>sKGulueJA8MWO={$`Bo&FTBVjP8;GQ{!=yX=4GQYDUE7cmw&2%? z6uhnJtql%{r$`$vl`>FGE1q#+!>cCQ#X@*1+3*^1EDGzn7fQf?EmS_9a`!-+1Y6$I z8}JOpS*vZ>>xS7#VheoUds~m7n(@`Pu7!qT)tyL8^^NtYz|BE&hP~(fKf|1pDlbWy z`|9{{dEq$k>lP)50 zym0yn9nKcqPo%Lqa7+z}I3PqlnTaXkwkNafLlEsnoVwRW$ROnn{RCDkhzbqD32G2t zhrN#tj|#8ErHaHw;G_n9K>R)+<03)l&`{%i0`D+FXu-3N3HV3hh$9KBgl`PvB0cv!|@GjqWThkmslw~$eCks=QY@ju%uuaksoI`kq%CF8>aP?1H|4D zRnr^E{-#u1f99H87opnG$xSLO?oi zm`PQ36I0N|ZCcSzJ`4k2qq)Ycya-h9fe9r8ijhDT2$+D1po_wLtOi9e=ygG9A(Syd zNw5!v=yPBj&OZP(Px~{WOvd}+;3KKK2kM4F-Jo|7bofU5gEj#m1%Uh@)Cy4?zHACo z5Ped+H7@1V&`eetkyv~JPfr4$>494D644gGxF9rb)un2N_n8#km#$H!YTMkVc~*$- zxQ6oO4Q!L&s}Be_w^k{rkIC%%lTiNj%$Qe4unx?xaQsmY2a<=pF9~~|p8Tixf=CB( zxsO4Ne8yntEV|edHyd$rv#9aeHhO~2mei`VR$IlkSX*WE^9HiuIxD~7zvps@GZ%(3$W|6LYpfNT-G1mq#dRfHSQ#=|LYx^9AIE1VBz zK!#fd=e1DPb6|UWPNFz040$KOs7T(ef~77W-w^C|Q}EA1OWnOQrU4)S+PtrcvPZyC z%RH6ei$W*7Vf*LvfEM3LKkOhU?rBVvbje%WMo!AC5h+yDc3vpoHqSo8pH_|w{%no1 zeI`XXQd={Dga0&=(_`TC;q3k%+gvs7Ot4LE-EWHjKEamN`etHW`E|FN59dX9osB9U zy^E^I0^TX}sd~u15!26q|{u6U~6w7tC}5pl+1BwiLSZJ!)d1)@gq`ZP=Kwf<5CnCEv1 zX*&|^ayYay2PHTGfx%cWc~v7RO=g?ky2ZBIDt}z^=8O>e9JJ}s z)C5(11@SWHJ1>Gn1ruADde?<96RD@f;=nA{mgmgVZBxN=hfB@w;YCb z$QwRPmgO+H2>-PF*AR2hG({uy_1@`5NQbtQ)0#-sKyWq-9tl+o3zpZObfi_3S1*g^ z_AisX`XPlbn#K@87j@F6M;fqSp&1T0N9#-b}e(SqOVqf{DB%+Hs zy9g}HMxeplQURoX?~icw7}|K@9*KeAIc1ne#F$WVRpLcOnQc}(nsB$ItU0YvfH7o# zJ8J_&RqZuaW=)hELpPFsETU(QL9_ zbd#3m`ZOU*U4&DlD0Ak3?a1U8(VQ<+|Pb$vYJ;|6crunKll}P zD<22Yg~H(T3-Jn}@`c=t*&_-F*-*hI_x;*hRY(n|6-EtjnLh9FFqWz z6+TPi^Zpe!RaFz-MD4yO zs~%)wwnYXX2Lc;6L{4A!5h2X$odai|?|z!hBeKZ*y$glscHcJXa_jpZHsaxH%->O# zvK#3WyOH>?bV*`*V4KsyXuNl;=H`gdzmD*vZ^w6vyluBp1u3=tef!sM5- z5_kW%RdM|PK!c*S;iWSB^E}eec5OH9=2u;4_HDj7w+Z{G{!cv+=?dp*BYf0w5uAtL zZLI7~F4IJO?3Zq(`F46)|JW;#Z}Am4GfliVD9f zrnnauNBL3U?GgeRLU%HC_U#g6zj?~R@^AJ|v*4IM=Ti(| zpS(ZWJVYo~j^Mt@KLml)1Qn%U9YTTiM*#|yPku8zga+#g-tG|V9Cbj7ryU196uYc= z6qzAWIf_gX@<#=p2W0F7Zy;X5Lua2adGG>NxUAUN%NqCjsoih%Md3G0U-EDB_ne#O zT-tOD_PAw`hkXjK77+0m)677vN6`3Dy22pST}Cp*8u&WFi$-kzgJ#D@sW3G>!rUu2 zL)W)nGci7D0BB(c(nI%!lg_?o%7yN$iyM=+!60$d<@cMZpLlJ^CW zt;q8k_}CptfuXPKfmN47;{G8y95;BPrrWl_jKmkfj=Uc%8>A#K^xqN*)RE?sb83{H$j{0y4OsNZUX8>_Cy}UzKJ0IWUl`{ ze|3t~Cl`E#4J_V-vPgxN=qzGOqK)CTmQVY`<*^ZIbqj1Cn^K<8J6|u{_OVIk!dyg# z%#ZRH*ixP-x=GV}O`Owo6GNH`DS1wI7KNVK_C*=XQ^WaUVZz=LJ8(`F8hk>@s#L8Ey%l=s;GMWRxpI3{n~h(NMa61@EQ2i|`p5Ut&INDs0c;m7HAyxlG1eTknH)=F<_<!cFS80Gl)DRE!Hq)Y|Ab0q7lN3NV|6#`+FJnJM8TL zz*3>QCBHv2nT0LFl2^j`?}zDJCCHixMYN}ba|~(bNg0L&v&@nJ6oAj1a)oWgbLn?~ zOH4`do*2A-@EIo;`S!~NQ2V{!R7p7eN_GOp@3GaIlwEib#nhT)|5ppw652!*MeobZ z=xa?jt<~x##v~Yi`JO6&*7hk!x z5EQE%FL--b5Ou2c__JJt;>SNba=rYgMcqJriWn4!*u#+Kd5=+Aebfh(2yCHB`gUPL z(6&J-EFFbsT^6$?+?fCLvcfO4=*c8VldXQ%X?1AWzfCZTG9n~HKbp{%(S zWV~>;v`hGTvNU&ceh-pQkRNZe;_x;>RD!)7w#|@2p#r$s@i)P?$M0}#x5J(~^PNXO z`1<3{{Fe@rxiHBgaNKSmB)J$u={4X(djWkBumNNoR3jvVQIe;D6(9rT0IW$IKq$ zzH&hKj*|2PjX6XIoc8n>R!xySbOv{Lw&DM7k{sjd^6r827fD(du>U2Jqu^Uyn~1<-tbH%_8&{5#Kiyr delta 22400 zcma&O3wTpS7C1h0?@e<1ph;Uw({~;%v`q_X3sN3RNZQ*+zyd|(p%Nty6WTtQiq z@>naN7B23VR(BC}MNnyqbtzce6?AodY=U&RP*|!cffn_K7IK@k&HqdayZifp-|zc= z`M$}0%*>fHXJ*cv*W8a3e;x=3M8=%x(z_;RF;w+d$Mx8tnwDZt zGyF(gI@sP{@k)FD+E-%AV|l%Z=~!E3=vryJmxDxp2#I%~#`+PS_Y3M-Y~9wB$m<3icAa^^k)LRLxE$}p4JaG+|H*+Hk-^k| zz_FmbvJ4s>sIJnBO4=f_(0Bwq_f%O#6CH8ye!x)`VI#;@Lm3m45&m;8*euqf^2`|x zD=g)SRhIIGD(W`MPh4p(zqlfiH;YFW*b{Au{60L?naHc)e=_v)02=C?0auGC2Vm2z zP;kIx4wYkuI`1nB=j-4)1+He1qQY&HLw6YN021WnS#`QZn-S{iL;V*w$@>9QUNkhI6HN;eZB$crNg}_Oo^|`NJTi;M0(}x~l}jZy z#{wz3JjNQ$M_6KQ(V>hb{1RIO-(ahh7|3UGF7g*`Y#VAPy`$m?YD@Us zNY21Vv?g;|He83qekqH`^+=p4{7a$LklKfC|8u=wG+928-pwPhs)2?C#$dyr2=yhNZaM9B{{5EBT>(l(1H#c|5t>9B64&~XPFY54kocru539;RSvG%Og$sO{57rj%*82W+(1A1JWmcX+Pg!DJhy zH&kOW-hcT9!nAmMkkJ>|3V3WNzHHfh4$5h=!rW(2H$BEFK-i zVr@Vs_DGCAtdvwq4#+}Pr%CeA^|*w^DFTj)m45&}xl&FR3rJO!Lk|a!1uEnQ?ca&-PN8t-)ma;?2Y%VC!d=iD)BwM z|M}vvHOSy~<%QnN6u}%ps8%mh8r|PW$P{e;(e@=kB;~)~eW&?#$*6+G)2I`xC@j)= z{Kl%~;TCLfEaRToczF5u+Zk^Wg~aWE?+z)s4vQ=NLEmR1@i5zH@vno7PWNok_svKt zN0Z*Xf~R2Pd!AT6s%$BWwIN*u4~QeW@7oQ{eN{@Pn-b3kKZoY`d*(?xg!3bK+8cb} z3?J1?)5Ve=UGt#!CRmjAH{tJHNF9(STM2nk*4Xx1uAWnHC_Rpw&8cq8%aw&Y!XBJM3osIK^+hemPMGimp6j=&r_y-GPqW7n_27NKZ8cx<^Y@?4Lv0Abu zV@~D5b@UNhd_O8j{UWgd26J-y*;PtbQJkhSR`4AZv(IjqYZ zmx(Vufy93ce~Y)o&KuFeq5;UkQ2p^i-|Iq(Iv1Z5tm?Vcckx1lItO1D{-(Zv(ig+H zk+xBdRXY@+RW*;3?W4r&!?Fef_NME*-LickTdn(U`)ugSM?yhDWyNd5vc~SaJA22l z5gO744tlCff;VMWRZB7q)!+Q2`Iy1B>nc;w=Q>5^5Zgjou_g&}_YaOfJ9v$e64Qmw zgh_a&AWNKuyM^M!EM@EPPt7}_;~I`khMB@|6O-`A!hu9>tT2oxvr{5+dSU6v2)^5A z3STFt;17kq#HnNMgGFX^Vja>_;sjw*Qkqe9I^BrGb*GSC(L!;!4r|rGY40Bb*;+5x zVvSs!I)wDNL9V6XK5t0an)F=iul$T2#0;)#2NLJ{M^PzkQ)rPm67YEhF-A=z@lzo$ zITt4j%aWhQ&kA2B=cSqaGOpB#yf#J7Gnt%vN*>VbtH5!y&uxRj%M(&k;v-H6-hyWn zJZpqmDe?NF|9MvW8Ez5OHp!?7?1K|FXgJkm0^xwLIc3`NEde5!k$p%F(=+#mSP{oP zT%MM>v+10KniRmzyCwD@b78F*heC9DWp?W{ZXS$5tHf}tTF0G6np+-Z7;s0xp6qo6 zeLoGO%%9xXJkz*Eu>39w(Wz7HSB7QW&Q_G;a%s45uL{G|g|!>>9SHu-gLI=MzaIX{ zbF=lA{^;Ef9n$~OuiC!;!)<`u_I_3Ec$mJEU<{V|clQ&C$f3I;)i&XMk2(o74L4yU zB?kSgY#aE)wiEnS+iRYAKndF*!+q`qh>N!41_1ctD8Ls1Ao9+mG~8lt?BuU+Ppvt-*23K)Alpqp)yQz8rP>8W+Kez^g#*CBkNSvux9Ki1H|s+2&njY6I_e%`ea47{|=tbjKw{MS5kxIPZ6=zG|uN@2|R zA42S3Abk%>dl*zl5EE(J8Lz66zK!$|A>p?k+U@A4V_8FZm++c4+5RXL%)KF5;AK3+ zv6Ij(w_~-nQkpOim6eUsw>X+(=*4qG>QsQ$y(e0>}BZ!F5RxtXd2NxN!G*q zX(`fA_fPC)qb$8qv}JxpFUQjQOrFl7{cOLcmqu%Q=_m~MmR>{~Y-?T2fT;iwne~(l z(3=(6PHB*)k4Ju1Bs;j;a^3b3h#D%lo-`WvpGNPs*%9Wq)BQP6)H1&`6=zzz0ALk> zT3ZSLO>0YBhi^Ncy5vQ)r7x21l-Le}2+oY^jf|=gaU?-A(k~x6W?RD-bRCrCby|8O zX`Hpj7VEkyi|%B^NajPN)H2?tBDokTKQFP9ohF4}en;Pn=~T;EiLG3Du9>V2q-nb@ zZKt%4d1&oY57I97REQ{Ys|RWR;K7<#J)nGfD1DoU)}Qw1p^>j(-;P5+c*yW|GzWcY z?ZKO);~Lc^?ANDfkPNnk5vu}>xE#{5z!Ou+W?$Ui+hq=!{~A%eW?QMH_1vtP2IVV^6AbmT6YBdc}9H}+Iv%cpDP zW!c=T@OH!(3G7teO74e!-+*jU*!D#hVug>hHNvLs)Cv27A4m&~iE?@82hu!alAP)! zGRpiQ(x}>E#VF-3t|)!%ikrgaY;9crNYAf>zGVT;+Mw^zfNd@74Eh!cv4&~bD$F%h z;(+jmAqjsgv>B%6o*zN_u(`<`$Yx2?oR23P3wZ7&DGY?i&xQ&>_+xXtZU!^}2MpjI zL7Vez^yCw<+)6yQ;>X1knYi=s(=oz3Ik_{~GTN)6us)I(OnOU%O>EP0dhVaV3s3}W zLQ;P)nPp8qEp?K*Blf|H-Z}AYiw#Wt`D3(7h|A5pPgcI&gfycTgq}7OM(Pv{kvi7R z;hVqMWbUPPmaRkx@0R1vpzmyZ(D!n?uqAh4=?m(SEnhh0S-LKeH2m0`XL37n#=Bgk zU)G;s{v*g#<9nmzKQxbQBs?)$zs90-+6vS~Vp|?}!$aTRw*dspDT-V{J(07k`HucE zM7eBdp>2B0^8VR0y^*M!z)&2(P;~$24x#|1W13ShQlQSC2}u~FtOcI$K;IdF!M2!0 z4U${s3%n@8TPFlLK?PBg;PX%XCD~|?efB(jWIf+6w6vc{?%YG1HzK38y$#Hgi%SCxqXE>~_Zbf)!*n=|7WWES2JLw{33T#+xktW+lB?;&dYy*TG zq&sq}q8!XrUYq%xbbUH?=eo`!GGO*0BvZjqs}XAxTVz``6;I>7#k7blD7(P*S?$8q z$weOo?hJ5SV=bUMvT{rBSqq-17KZcURE-+0n_Y)rNd z03lUmLO>!|NG(yT6(C_h-WsuWlJIK&G|Jf~xbnx&9_KFD+^wKHtF{t5V%2Z7Th-Qb zd~Q)+^1kNgzQaoPVq7`atN7g}8W8@%lfwPvDR?oP%LDN?p(yD4m5^1SANPJ&)z&5Q zW9Lsov!qEiq{*!C$)xGRkx9w&YLK)eIl(w7Jtb?n&vUgl=D{VY(M7tg&OpC+0k&G| z7F&A%YKauqO)@G%lV24ftSDH*4UZVPeh`CS3HAbWP$Ce)+Yx#($b<}(Xgx79#wdn5 z2_Xrg3tKE(K_HM%@1(a*E?bJ1E=pnYJIUAyKNwX-S>^QB#hB`|#Hx7*RNK9XOuF6k zG+P}Q1lVDar?+BIF}IoYy%Zf`TPr>d0!`4@cUM#;dP`^`1buG@sjabP;hF`wa*=)j zfsLrnQaNwf7w^|^jVh-L4RL+VXm%Lob<(P05w zTP#80pM&ypq`B8D8CVtumWU;!0YWD8R+>8}$LE8-i$c zdC*4>_wZ^b&1<=CzP@BcpIdQ7I_p5=L9Yt05R=2MZqz>$7LeO-7jmG(A0*_4>mht! z&=)l<^KPPLw_kfk;XRA=MIclzJlIox@Ftlc~VxnH0L$6tP5o~=# zVME%nrHMA!++&v5BJ{Cfz62}Z%mvcenfif|Dl=S7I{mIu3p+#Ww^4e#etppQ&wvS* zJX;D{6zq>;Nzj)E6eH9ky)#CkbT!?A>Qol{+ zV!UyoX=e%)^&H;1UrO%TFU5CE*t&e{_gm-mDkjYCrM3H|adqb2D4o*(f)vrL^luw! z^+qZ)yOg(>@Fh}~SThB&^Y26KAK?1V-K%vfVqdzOUWMxkNMVp)K>q#&X}_fENER8T z4D61ydz|P{B3If8{T5=q)^F5r=~j&E+%Ii1W^((4`S&GM{9)u?UeLD}RIE3p$Bm;# zD7ly>#}o5h)Wk6^H1S(E%5uBE>PN9(^_wE!cy>;&C31(9(h=7~i*{OWIMa2e?+hI- zwA`n+2YqXY{yXJ^zK4h2@%-x9x1SX~nk_28?T;>${hFJ=rzVbbqe=FGisPeDX5A@2 zPTG0Ln-RvQS_3Rf8B%X_BRf54qJ5z7IEFe?j?>(VekNAG@gCe+1M82YY=0on!@00fW-mkQW8uYw>Z(j8bqD=e1)%SI~)PN~#rGeRvZMO_i;E{1aGo9B) zxj2ZQrhpg>`XCX5+3vDE)<_UNcbC(>3`#apy$BpYV5xLu&{3T)SYIel;bZtXQ*IdgaQ8F3ASO*c0}U;57O>l5-DXVm)|xm<{DU&C0!4{#SRrXLRCTb(4;uCbHauKIc%k=ZXS# zjv_qPGZrK@JIFVt@S!G&a8R<*kxhwr{8^&6FEG~{FT-vAj2wR zmTXMeQY(+?ydur{>)QU}=!Pwq!1hdu%BZ#dG}y4Kk*POI^%cBJ*x0afI#7=#%^3r7 zMW?wG^+kYCG2O4ymywr+AUWbjYb$D;QA)5Yw2}g;wxBP|?+8_UnkA;)2yb%4cK4QR z&Mq~)@&bIe$t?Z@rGS`|dI3!xE+1Pq*%@#^0c@8u7 z+p_mn0O8P`0ZKm*1UIyTCZgdd(m>%kNt$X|1U%vsxFM{n8uqM?%2-?9kCS28RFKGK z8PZ;0c<&8yVN1lE9-Ee=?7TlW zC4B^GNtbyEX|CId3PQwb0=v2;Q~1aI8hbj@rj_0SwYf}sMw7FC$TvK!<#gOLpdu7W zL487b#el;GJT(6ksV6Vi_KAe@HTnNvg3gzC(kr!2h2@|E~?cTmc(p@MZ8m z4Xj6CrF;NvcTKTgbkaBQT05i$?kE~R! zV!WGV`|Z+ZQ<11*o~r(;8Ru=29yP5L?TjL8n^bCgYSY?&3^|9S@{X%+q)VP)%5XQI zkJ~sxR;G@=j{v0qaJcDR$ zD1FE$8(IXtcI1x@`B*=Z9xBf#BC6Oy$Jz|wWkr=lgf+l!@_|%AO4^cbhi`XOCGv-F zUD}`<=vZ(@x-{WiNF=!6%wo6!Ckl9(soVRgCAPBsGg6O+{QnU8zaIL(8TuDP{{xy4 z-~8Z+uPQh#Bqj#6$u_aTBHf&0k-ma-J!f*cMfzcmU^2z2;8~q4m_>IEIEI57gRsh! zW=}86C=Ca}GMJwZ8Yji;tvbFQec4`3Hojg zK0}N{rXk<4k5D^_JBWCfMUjxg-w#7WU?w1wsRypILc~S_H)J8*Q*z;z30%zcO(<$~ zw)McQBWtV&5@D@`$1;!zi&YgyqHRrJpD05DYS?DR-;(GEEZ~M+X8HnZ!1-w3Ee}LV zZ-gsGtsFWQy8@q@_D>vA3 z+o3EtN0`E|gYrJ4+Oe8Bq2mwpN6p#ae$NZG!@M9b8ecIvSjDrGiNIO}Qa`Dx2g8um zmH|qLk;{Q+Yw)xuM)Q>?nfuxk+k*E7eSZuRjUT)PVEpI68cTe^!JEW|?h!T@bw<<@ zf4Ayj$&jyASX}&;7D8FTWP(KuqJA8zE>V7v)*?R!Q5#9%rxO_Q2_c0`!Ck@(E(?Dt ztm0-wcSujI9&-M?`UA7VO&nVP5}aI8S`k?1$6S0>;*3NM-3eEaA4V8{rJ0mDCG>H# z>|cW842hehEDkpim)D6w8JI7S_%e8z!@#!8wha5823pe>gT9wW5N|TGZG|mZ2QDgY z4#2}fn6Oijp79#ds;aX$iVKivk{It6bXIcAgRld*{~YeWn%8!{(1gVNlf=E1V;uIG z!J2(mc&B8Neb_gFj3%^D0vcy2!FS#jS;7u1d3^)wF0bTjkv}F zjPt#bQ3k>S1IhZBZL5Y_jCfO$aaY0Z90QsTD>nj^FN1Wd0^rAw&^%+f?b>7LcP%v= zTCx5|8x|@`mH2C6S!sOHZD>sf42k%g`rGgf{Wet_gyyUc`lOEu-eWlJYC^k|5p1Mg zS9x4;)ke%dmxl>l(It6;H-(d>nUO!1Aoen(H4DLB_+;evimrre+=H?M?&=bAYP5uB zP!gVn41@4Yy1LI9UKGKpIb0xsCjrd-)if8@6D#3Jh`ESBnO^szL|mw9i{Rj$0c8uu zva#t@5uQeKsusblZ~@2)TEbS8<8upUWTa7F^LI)UOhW}j*d6ChR+RuFaosb97hY_f%SSD$cQyyh@5fSeEVBVasRpc z60fI2iPBF(W(TF^dlpMzNeiL^xDgIn=R6JrNI?q$i=B!CW1q+TQ{cAWBN zC|MUSpaeZXA4VEaxxm$zQ{G%_1+2F++wSGZRbUOIplE%Wd46EJMMe8MU3D&=6aN!;bYd8Gr6(l45k zZg)?qNU^0N!(Q~1iY)st_*b##JtuD?`>AhFd7o3}0$LlD+3^3QGTogy;Na8zwRWj= zK*RslbIO|yo(9suQXnYh()V6{_CxTez1>bQPURjqmx{IQdr)qovMW^1ByQLajc+;( z@19adz&m7Dw*#vDUC;m-ZQ2jHd??qk_FgX91Pw#3gWu_a{#Prh_Dn!x^d;J~&2!Yd z3i@7q;gq)u2IRe(aPbOV2?|J8%?0jH*2NNYjL?W}Z{P^R^SH6?(?Em>=7BeJNWs1K z-6`)AO8dZXj)!xALa9<4;Z=kwv)Ch9q9QD_U8!xoNkt&BDDb+JZU;F(jKbMwms+Hh zX15yD?8tTyz`;nP36B*cl|?`>q#WDM=xO~4bL2&}$SVKbN6T6FR8G%pKz^$)!LtV4 zQ;N`dQj&4qn>F<%(14MJ!P`&~3$->_)$M8ATYZY~@IHksUcyPMTkTUhqIP|;ZA#IX z9M#x%twPKVKLhR)LwJYhB!I&%&9pC?p&@AIs^?7eWl7V7h2>VV3GixFO|z>Qaul>XX&WT1r)?d^u% zz6~-xE+DugnDuWvpG%G{I${2x{Z1kpuNK3UN$vt}Y!5zAn)=sfy!Y=O+_)_D-ySsK zl1DA7l+!Uc=B{=nM^IC^HYdy66QLPQP0t=crj3r zZO_x|c<|xCTCXd)&qMC&N=|u$vt;gL$piocyr3RHw0iRNH$0lR5UYli3<-4vg8)*c z;qtOl+sTOQMHT%Lxk3#zNzdPZnVJGNxo`rfzT}Z&h^)H^t7RD(RQuTWV(ltzeF+&U zraPbDWbBqt?EKP;B678(<8IWR_J%3PUmAVV^ATPn29&1Mmwa~(HxQ&36z^(}I%?D| zC<^!D@Y?nmDK?pKjQWzlg$4<`@sv+J1OW0azG!xNE^v6l7+^H8 zv}U{{X^do?;@nLf_%*%3LTEOGc}cPF+mFqE?o-f{+abu2I|D;e*pBpZMX5zFquEc2 zvHSj_`fCKuM3~*s`-uZC{J<^X0V|d4fToIqwX|CKtoy`m&D!N|vMlXnO%7hCFvEDQ`9+i23eU^?X5%#f?m!Z(bHTVGh>>%$t5=9J#!4qc3txp}k#Qx@zqQiZ%2#5j*)c0HfCWP#S za%u>Wy1K4`aL2WOaKYQPk?rc{Ma_SWuk(-|Cx&`_ufv(5JmQqszDP;>$H8W?mcG~= zmR;5rW+>^pa-A0EjpyJO&v8>p0});(tQ*vA>_Xb_JfsQ#-6kB(9nAxtOmSR9I2dI{ zX+^u@39YD!E<&j_9;z{E)5C^vH`PeCH4C4}EB0X+rl8%oY3Q>btw8c5AP05<(XA@| z<c#%|2=7%P6Q5l z*_8;4UFOB1e1le_1=!2f?YY`sK*(r^;)I#hm;BuWbG;zysD@kM-+pVEf4ijTV?Y(E zFZuKy=CkTca(~R^lp*63gdJ4G4xr5nu9h3eCAaG#q8nCuSTc7xz7Rs{besX?z26Lm zWuM~CK%iYM7k0^*f2>#zLK544sQBhNBe-^Bq*q8hA$Cp8_j(@5|Ah!?n-*y7;~)-> z!IqRFkz&FUjher!e{T-EgfdPiAf1t0vTo+O`)#8}GLWSre(`+pvnj&+v&v8Xt4L&- zUQg4{9nb&ir=m3<{LDQcdVje{WSD<@{`AxA=Rf%QZ=te}b(+gqy)px9{`AuWYxe%6 zdS3Ih0&+il-Ybl$G(_iH>Aufs;V1OG@n=QEpMEk3WtB-|-URd8n@#g?sv;Qij{O&` z*=3I9uv?v|YD?Y(>Rrwqx8x!5AP!CmgJNzS@$Dl@z~nGJZPNg`rR~j9k+D%BKR@Ez zDZH{UUfVa!q+Y*x%cCOd(I5%+dJtL}bCJ{{DwIw5+rm8jq%gQp8*7D}fs0>zin!^V zmaFDTxL@u=Y2!`){?*o^{^dW1R0AWlni3=}0t}<7&9b`R8T8$hg!K>QgbzqPpa}+j z5OsItq3Me!La-t!rG~lP=P|F&cQ%FaqdKv6#McFHp{H5cjl}HJICR~0y1Im@XLCZ4 z3`qR^bYY8fF2iMSiV=sEVeU^9icTb!3HLvohFgWl9!{eACE>Y;^JiAKgw2sb9F=Yp zl}!Ln3g|asgUn50YTK??gZ}gT)5OyBDG1Q2mY6wu&>&J>BsyOSQ2R+yaf9 z5g!X1zv*KHb{!4h^>O;gtQ$J zDV+2uVkba33K}W^1r79zZA>Fk!5Lv$PsPA1%J%2GRS`D#cRZK#a5hEHWO(XF3q zu3U#25mC`&5u>dE6Lmt6)V5Rf6%V6*zVr_K|F*Or{%@U(k)G3Yx zeN-?fcfkFlhkzac#R-XLYnVoec%^9&mp`t-dXzzFUIco;@W7Deg67PKvmjzlbvpDO zF%Wy+1y=9F=F~2x5v7B3o_^5|vCWJCWHn*fHcI}m%s`_i&ui6*%<1~CQ%OP zb%kiQG(o^W~5t!Sh|`PU&I zi6n5nU3rjE|jCBv7099@fZ zhehXx`_QtPwm>;@c3jO^ZiIerLYwItOw^ zOu>I4=MIB;Nm%p#kHMRt>?6lh5L|&FTa|NACfiQP=<<&#)7W4Z`XjB#sSX)YBj#GP zYChXWiM8O5lyzs?G(53EjreXrsE!7Vp+CT!mw_n6lHZYwF9YOQV=ZN0XM7N7DbmB|5*O%T0XctTx9I9@qn+5+?c+vJ({7=EUd_I0pcpX&c zuZ0`SmydaB5W{vrUDB+k#NP{#tVqGLg=bb6@KWK86&Id{8H{;C-#r%!ltKt50h!rg47;myXnj7~06`qV>>l*fb zbhmsel=(1-w1oiq>JZWz;d*6A4;%j|9RY{gSe(_qQFv=r8onZY3jhB&@#88PW&bL8 zc#{EqRsb9whVxHngLj&V6R5h4maHm073_wUNK@^L3f{Zs6 zVJ#67u=q=Rb<1|JqCdKt@v6c8iN&2kB8SK?fJL*KJPSb(dLZcL@EQ%L6;|_=MpcVt zbu5sda>02XGsrFw!?=S-In3p+9;I_=S0W@_;Pr%q#a*ER!*wrzA6_76S3i$m7G7Un zoc!G|(Hi8g+1x>xOVeRH09R))6s=LS@5$t72rsTNtu5ov)PCszN8M_*ko4qiY!V)O zQa`5dV+gR)I{2V(_s5c;)g-W={dy0Wh`$*U-hc8@ISKn=xX>vhOZ#nT;vCm{9%&0+RPoIa&aN){U@%{Ew2uzI`VuZ6I%#9G zU_JsWweIDYnq%PJ;MTvK1XsBmN~*99)Te1kTqDIfNgqarjuxkOmBL6@4&~XwW)bvF z0)G32=f{^|kLtjAE7s&TQjk;Jtr^!Tx)`n=o}e63N<=OAqGwMlgIEBVhdY#@a$@cZ`}F6@r}a4C*^`><5>2` zP|V4SpfGb|B71&Bgc!E@?ZW;I+0@X8(6J$P{LK-9X=dSOdmLmIWV^Z~#%AQ9_AZ*l)$bgQtKUhY@wFdFx{gmWyw5dG2f z31Dn8_gr{;&!H!0HJ^LTyztPT4+h6qj0l(>;ZF*%Xz!TzR0y!RLh?4SvxS#hKuMdUl*Nq8>|voq-3i2Lr=@ z#2+0CrN?K*+78zWj>Fo`!aDGI!Rw2T{n8>M_{KpfgpmaYV4*4K`$wDb;kt(*lJzfw za=jM+S;$+TpxOaPGLT-wy(uk$3GmUduw?y2YSpl?YrQLm^pzYMneSwI);a8plZ50o zI_l|wU|M6M<^+UoYYLem@L>rbuc@OTB75Fb>crqpqM7gD$8Zi#yUNO&w6EECSiY%4 zg5#+i{JikqQ*)`FfH3q_CiP`N82|Km>VPCX_;h~i)zygYT!UEm(}oub-~5|1kKMkP^3g&ew|9xlztqH>vmC zFyyPqT^car4?Q(mRiPTlunpIi;1e~z$aZDRIo#TNG>>G4SljRA!A zlMAz7gICK^VgfSJ(;%2^DhZWLx1~^N!`#oJ??v zW|)DyW(>W={o{2SRScLdspWg%j>H49 z`m>Vlph~+#T4}5p7`I`EL?2}O*zl^~F}HVZu*1q|;<>6S^PQfmt2>z6OE(-|p|YO6 z5j9z9-6b(~MZiyHa3M8Jd~AqFWFx-uK}G09Vh%UtV}}3ina3@JyKcXNI|#zpeh`E{ zg7hXNW6RE_oqR;OO8ctxh>?NXu=Ne`VBmNM_%GD4`(@w?_4|s4GU4&xL*!&30Z`o% z$uXG*SnWuR)6ywvC~j^hP$6m%=?^6*aNEt4m!igYn-Hz1j8)Yg&6;X?53Of3*6J`l zTfMvb^Xlrhu(>~Y!sdPtsmJs4qhNKEa55!PPhBA^1_A4Dj~j%>o&)!s2-n+?P-%6E z`o!{Q8*#*YU{z4Hv9OzF3X07s_O}NW9PfN5U??1fhb+hbZAz=Sb zV68X~h4(xHIYYif0TCkfTg;wse`Wh~HPT3JYsGjJ@DPb<$k)&&!Q$Sz3E!_cXXA%_ zyJ5c~5ej}^-^t^sdVCe%wb)psdH{(U|2VG-JQGzqcs1mEHt-`cE>&EXG7r{*VK#+> z6NI8`xCZ{;52ape z_gosAO&FgT92R1p&%{WW@qCtj$oFe-GK1@Vm<-e8!5?5F1T8xVN2EbW9`dCOjS9(x zHb{K*B#8N9_lVNUa7*|Ut`3~asT{FjwSo$zxJUv|5YJ?SOF6UOWil6nOZh3Ap@!~B zd=Y%D`H3~e+*1p3IKK`Yd{t+u-K5;1E7f4nS}t3f1lpBMT5%( z?Ut!nBP`zX2<06VnzwAjUSY~_{~#lhze#ZaHVs<@?{6Q&Swh8DE%laPSif}(b_&02 zof>|`FR$mFL%wE7Fxt&2b&>~WgNz}EdE=PxVQ*u&-!+W^%N-JbBfMhQ!qF3_J&O_t zg-do0&l2WO;2b7AMtH$70sl@o?nuH|_|h>Ke=j7|WF?FrewVM}kJ)0K4KL#S z28bt|4X0)yXh2w6vpnfBu|_LEyyMkdcp|GTzP zO@y2?6ld3%;J9dYOB9%>tlt0HZX+mN8`8r$zy`jC4=-x4 zS$NLY0S?(d*m(rou9>~|9f?R|DnjB7;k#XVW3R)< zUxGKMlaD4?PRY| z-FI~z(%%e3VI+P7+B)Xq%ZXfe5w>r+T|4OeC}085!J*q#dLKUFU;gQ1#5BlB+T!VEUF8>AoY5C326rW{QA`_(ByI>dod&3N} zAxyYyY=KX)lq)r?l`VrW#ORjTB;QAp+-g_ol$u0{z+p{3-AHf4_JKQ zN;r8GSDYFrVWrBsA?Xr?{ZzLN`Zfe_dnju-^o4wYfjW5-%%5aStpVPthM~AQZ0J zRtm?{86&X~C0f1&xi{dm_~l-fx$KMp-(@$P?QXEeIJ>1t5_&bMu_-9sgopkh4jnaQ2@n88MfAxP6=JLe&wZw_ih)Y=Hg zNKxjjfhUen<48k3pLci~%J_-CWzh(_^iT>ecGgzCy~x{D=r#|%T9_dFYr5?NMzkO z9!;tgGK5JuTX;wSkC9j)UGdCVjSOzrQuzPIg^!wUMb0O#Ym|AeyA8IZ0>?LGS4CfX zqCR-GMe!bf2SU}>pjStH55v|b?pa3 zTc>|?m35y+?Q?e$^9wmq81NMdHT$Q=b+^9fWh0-y!F+?V!n%Lep5wne5pS2qkwcL&Hus(8yNRjOE0#_15w@s=CBI^ zwcHytI>dyU17_2$aW&KfGm4fbzS(>tAc<^1RZ!GR7okAZ$e)YDF3e0o;B|M1vYI~^ zn{H9|8me$+k*Qa1db2NzLE}@L=S@ie=?!GbgGDXAK(z+{O^`y_^W0x10U8ei0umm7 zA}}(fjf@H;7r+6r*=!)Pf45n2VY50C5TVWyf71=e4(^M@!_CgXh!_=6MFYY`Yye3I zixqc~pw1mEPC&OVfb-+cK9(`{Mw;3^yP-cQ7l}?`>F?9*CmlNym-o>aYk*F?R+HIcMmKA`hQ_9t63{zxD8 z%lj*O$3Cd_M|#sNGYATUY5pC6LIOcyc36P*?<%JJ@>>W>vKN-C!+=7i=XMoy7vAww zVcMcM`oeMhf2dT_i%S3v=_F9elVArt@+O`;S)2oCOn_kuGeKyE;$VP!v7-1hu8d3k zHs1A^^F&`1^{YOtQ1~NMqlfJ&cPL3C`Lf|m9$l`7a}Xf$wL9SRaO9J5@J#^?66*)$5Z3ZsbvM7r zg2bKhCBqi@kP8Hsi;b=DZJxUt(Fu6pIEbLU1O7=qn90^cBzPn_feYM}oWNZGM`^?0 zlZxa6cx;&tzA&g8P=!7K_uo(A5oF1C?8rCl?tQlZ33^@0owKkZ;+&_W)Qr<=86q-M@ zXpsXbMhqt5rx@${slj-qyW+_)6Iip=T;VP%5YWE#xY zvlpT*>)ltxL{Y6w8S~ie@(ub0O$hvW)H0@&*mQ`@$O*{eyhJOl(rVt)5m9?5a@j$s zgw##;v(w`8Lt_9xKk zSgg_2H$IH(Z&<#EKU(E1m;xem`|;7z7A!2m8g|KRY<4iBdDu0uC3D!%!A{%17Pf4^ z&bD1PyDKd6cfKp+6W8uGq&Duv?r2~bvLQ)eMkl_q13H1=4qyg#F>oBn+9-vIAK68G z1ek6hJ|P)E=QIXiX*cmv)DHtOl)J$3M&if&5`Ba*hHNK~Jw%V1@44|a=0mBsC$W|W zsJe(g*yWZu@uf4wKc7O!-Bo`!LA=f`M|u($A_D_MEv+5(J?MR|A7R9E#AnYFe*kXp zCEg5tL0EqoSOF#miAT;>`?`fx7Oq)Kk!pdq+K#_TvAM9{ZCxZTA@2+7NrjX~KdlrK qONH&%O_x}2df0v8HxII~NSZ;6KgUe3djy~J0i4jO65SMYX5)V+?1!oV diff --git a/boards/mro/ctrl-zero-h7-oem/extras/mro_ctrl-zero-h7-oem_bootloader.bin b/boards/mro/ctrl-zero-h7-oem/extras/mro_ctrl-zero-h7-oem_bootloader.bin index 1a056aee87f02d0b61b42d513c72c116b9eadf5c..51e7816dd033ae84f24281d94d8c4f873ace1e72 100755 GIT binary patch delta 22150 zcmagG34Bvk8aR5+y*J5C*K`5W{U&LlZCXedpomDCw6_~rR%O*dVJ3(U6>vmFlCo%7 z)XK$~LPc3zP*iB4GZd_?g1gQnK*!R`Pz8y!h&Qy5+oVn2cT%01_kZvGUVgumbM86c zS?+hfbI!M&+wP=#oYe6y3Rer=l-`zHkzCr9_;GS{yjG;Cy{6hWq(vGezBv?E5&!=v z8C{0NEj}bB3?gy97m4cz+xjbCYU^L~Ql;3VyCBs~(2AHk3-JYM&u{5H6Mlz5;@Kf2 zhC{t?hfrJ5D3r?DFiK@0AcRuCe;cvY<(rS6mr%ZLz^*e7*z-Pt^rID6zzs-``oFZ3 z*w}y8{)dVSk~&p8P`z9$Mp7n`g-+F}7osf9RjqsfK-{%4Q@{wn#BUS@EDJSqY z?te14)VbwnrS#M}@NWqI7o<{mQ0`gDm|6*WSx^C`n#3b>&O%Jmb=cQI;wXqsFeH?^ z8H^|52QMw6BD5D z<6vj%^xXiITdvhaSuRK_7^(usP6MPWbu2WZN~OdCN}W0AydcekH#g2P4ImiYJQ&;p z^1K$F*Pey+1!)$+jL9@$hw@p!KWlA}kvozB6+{3K2>_`OY%m%ci2k1j0rt1XL?gh> zN~Mlhmyii-pr_x-J%$_b)C?DDLq=+WG~s2WH5ySRMJrM$jBD98gg7)u)to*9aaem1 zYME^!rq4klwc@PAYR*Y2Mppp^sWC>gs0x;F73ZX^d;&~pg20}WEDRE#mI9t$|3#@Y z-z=gkbFiIGfcqZGzlZoD#253UptYXV81p%)2l9S~yq_Vy3Gq#c#r&*u@OM$V1{v2N z9)NftU)4JD2FQ+P|M6FUFG2wvz(^&0FXL8>t{77e6I~EhOApwe*wBb`qU_PNPc(kg zh;)R|uQhG$kE%V>$Z&=ak$C^9*^PM0FD{h%s{`nHouV8lx&Z5LxKQ?W2fWcbDwxyb zGJIHFLeR!CC{=hdVKk>Ga{?#<`50oPVJhP67n-&};{nfGfMMZ9`QN6JWrwsd5wPH5 zvthDef?~6OUvSkWlbb_khVgo9XiFlWVZn7sydz~;aXk_@3tJQ#Ze-c!!%`(Anh&ki zLMzokVYS)SC4rm5ImJmE+f2Z?vPv;vSZt-mNP1Bs?Jm$Q%WFV|5)-=9SUzCV#g%Hzh*Wq_p@eCjE zR0?nH6ft zVJuwfK^qcT-(hQVX}9%Z3l^6QCBVD7z47oL5BV}}{92?M-X)<~i0hP)0Z%L_kFwU9!n;-0c9^_T zQhvFNN9o1RK-2R;<7>oFG^Gb;M_Es`;WRuY!#G#c9H;wgBF?x`RO#3QmSUtUq@{Hs$J0omgd~W6X@Zh`PE3&TJU#Rw?l~79a2i zJYV?70Hx95+dxgaCj%abe*sUEH+cz9#D))CQPxTkg@sp?p(snd6$Xx|zVmB8>{}km zbW`Hdz!%W{9@i`>3x&CHSiJRPE50YhSS)Fg3-pN zb_pFQg#j=0G5qnOG9Ks8f~WDmc}1PY2~Nb7OH9~l>v`(~mXX&m-p1&m2sz{lNP!7 zxtHTn8ZEX8p6KcMZ^IKUwh)>V>->E#B-Won;$O}LZXz91&Xk#?JQdD+OYe0CJpAdO zp*L7RkHnb5AB3eA@Vplw73T{rF-f>c_%5ap=LvDK851IgAAOXN{=m>RGh?Lpq_zY+ zvBMlMJ8o#Dk07yHGACkQ<-m3H5n7xkJRYmVcZ64Br-p9}Fg+ZfYIVCPal3FiHiIe; z2waLG?iEEz|yFZ!rN-42LST$PDZt-t}g>uFvsK$(*Vl2JeM2Ro^pMxxv-r-bn zl=!b9lz!NOb@aM#T>;OhzKjhAVA?+S$zfe)IgHlQ6G%KS^o=&hO!8}C*+4geVEwTH z&+9_rm~8x>ux89ms#Ps~G$srGL+BebZOpM@+(28XhN`WK;JTW{%XU-ZKZNP(G5C=1 zpn7iQ=3!Yw_iv|p`>+9;9pyXVA_s`9Le-pT4S2pJ^DjmZw*IU#20Z6a6AEIRsS3;` zKG)$|Ra{2o>%+e^kvHdfz-*gQI2f0J-w;~kG%-&N z<9v2vXjU&Q92pti7Ng*fOTrC8Wc=hM$*{x>jTmGAN(>)H+)YbCE1`d%OVxZ1@J$#m zjwfTHMCo*@0f{S5Bb}m|;&C0;sA0eT+=ureom_)Cx%jaU>F_?ehJy4NpKvJt>Ey*; zMhA=sU$qs9h2D`t7PKlrX%ZB*qDaiDQZn`rd?RBRsQShF<{CMj0BXx_{g{j#uTA8g>7H z@C^PAL5*Yo2f`-oPnAyIyyQc69VCh{JCMQj_^$g4SZ7nFv;o$fXw+h3UVP^<< z_60t7A?*m{KZbvCU2OTaKWYo`P@zab+F$!so7etrCyZrtzp9o4s*d%c28JJ@oLP;e zB?WB!H@qt?>#T<@C#+X3ue)Xe24)P#mN9&LBWVpN1dW;-;4+_NZ-kInz~2GUXD zH(s7~Hw-vOnk7|`0F`P->eNDt`xvO{<^oPMO8XNB7238las=CcnLaT8NXxuAwPy~walb|oVniXE;+=Nu%v#3BdQc8wf+!d&p@~iAx&uH z#^6_lFS&8pa>C7>!Pp|aubn*Ba+ok5jF{qM#3Tp_zVHgQRoxO+kzh@*u4_S@LR>i% zWKK98JAVF$sEzQYWNCVu<$Tmk{PF~=T)ZIRy|Aocy6^Reld6q!@ve`?n>2g#4>}&m*HDd9j4_T0jfBoqFe*?FR3YtS^q(LiHLRsom$~P=LmpY#Dd!F|GV!~Ba65Gp_3=(2GwlEr-1G|nNSg$&BO5zT$yqLH<9NU4urP7#1iVvNIaWu_ z9(Q8L*f0t<@`m))3>H5R2q76oi?Db$(6cffMtQ~mFV|M-0aYIyeWTEOWa+QoBU#X} z=hXnxl2lZ13-EhVPZu{bA$-e@*eorDSJar364+CkF&1Y36Vuddrt3GnL1)}JM^bqbOC zQQ6P;do}$#SiEh;gUXky0VORt0=5GN-PjtHN1|$NCe+d)`+D300=3@ zp5{79-5z^?W$%nJtqb+cn2Sg0D4{SbXOg^pixF`k=%_=9h*Qwhij<^Y-Vmv0-n65( zTmIz+EYcWvz?sw*@Vw9lve=QVd8N;(?`-_CQJ$gggd@v~-5Ew_Bi6mjhk0qw6w^m= zRHyYu$gVZrSx=T+qNc*EZM5X6i^SFp{)UUbvwIzIEO`pOP?XKbUyxX~y+52tDbO#y zaan&MO|K_Xi@=Q@UCNd^B&MLSQ72M#JETUWPf~1#oIB)op&AiyDq4WI;jmZK6Uj*AkrK*kk=+@2<4**Rz)i-Qux z3+^@r&sVOxl{8=7T(L>Uhw+OQVHbse8&Z?3!2MjUjlO?Ta#WFaQ=_lnJqK5q>lT`O zKQ@O7DLDoi%z-LYIBiH4wi*g-vI;rqZd7^@+Vv)p0WlZp;e~@^S0mP<(#gtWmdPrj zR(&bQ9eAqONpr)Vr_Yeijo~yhiX4)a%PUmNqE>DHABa_FM%o}S1jpj|= zK;dYU9S1x=26U?uVp}4+Kv+VeR_7-`oAhN^3$$3U z*~sy_UWz94xJG;oy8lanFaR)Jtz-ghNi#bD$>ssH?o)_KIzi#<&~6Ih#+2P{nuF&q z&UA&3eBok@b3XHQ4FJzt3@Dl6-!7?GUlKNh3#i{>v&6YSLHY8f^ zxKyOS-}+Pm2Wc?`JSPH-wrb<@enm{x`Vmg*qmPg_3MS%Ko75b!N&%$xP)q10gU~Wz z%HpFRR&9Deeog;#F(|w0&motu)*dw}zE?Z*p6XW69aWpmqLHrpvu0CVML9mdpf7QE zQ&ZpJ$dInlo?X3&j(ud`~?BKbQP z|MnY()WOjT59BPetqd6We&9fl4fn#X8;O7w1`^#K$S+4+_6-q~Y)nD!3>~bOPaqZW zjPv(c)s3`O!*^TjOZ>X5`?D)i8nDwLm13gu>U!N1N}sIMz<&<16PYB458;UcPm;f0 zddeVopF_c^6KBxe>O1=ICP{LRZ29Nl_CahU}AbG zsGMTcVO4=n6Qyeh{L5igr5m-n9lC+)DxJvCy3LeMw>IFJG-QO`Kv5d-_~398O9Gyw zaA*^%aD;=55CJ?b;9wwP84(tuXEOZ%7m~|7^S}sUlIdY# zdI-b&JK32w(foNiz6e6DFgVVAc>XZF2N1HR|17-~;yr+_k@QmrcxjlG1X)73dB8YVx4G)s7|{|b zb1?2vuy_KVa^IAmlhT;#lTw^bby7;;BE8T1_ei7L*{0D=AG*UL$96{EX4wT&mWbMt zCL#7a2-y%OOdg59g*d8UB*Z~H8A9{KkuVY9xQ)Dm>7X(xXR;i1j5(p(NYtUa^}3DS ziqRc=qz#62ei!U6ixvpSC&pH!2Yv?#cs?0Ix;LbU3@|k{w3tF;eWrubhdGe`q7!AD zceeMVnD%}nI{2iq*NiMrj_Sdpjh5>_?L6CemW~u+Ch2VC9nTIoy8ig&+fUwgk-@y( zfimB8lJ+S57$=%w8>l)4^^iP$`rU_)wfD872zh0%9nEO77y#eZ94wIWL3a54;TK#; zZyTsMhM`vJF`8fA&&24~i>|R7s};68&m2RUwt)@DM%s>swx>;Tjx;@`^Z&i!Z~W(7 zi_hQ*w38QA^0Di`c2N^_&aaz7&j|iWTKtKinXIwpK-)RT`mcA%Z3EfIX7$Qx+d#%K z+l1+N#~!QNNK~Gbe)<4+Ok4iLvmgS1TGn4>?!_@go10vr-4SC{Hkt=EuhVU|xw@f^ z&|}|T*KDkWR^`Y34bSwkhk6mT8TbIh_=i6D=(={}Y$)}7KzbaoeK69c_`&Z);~zxn zwt<@;Xm$je6y+htlt$A4wN|_N$LpZ6U+Z=KzR&r@K)?e52)T0G@hj5trfwYAQ=*SL$wc5I2`%X4a3NwoD*&(AK zps6oU2m@P-xZnNeTVp*aN^QWRAMpMt zU)b?xlwV6>|Uh^->@c1(@jUugrfi9{sW*_Ah?j&@itx`0G zrg&{T-T38z=dSn7zED`}*Svp$HBM;@_(%FT)6YTrncxxf%zC`{ZRsHu94o_#I@+hK zCEMj1fFYaZtcpYv5?9p(JY7S-iPkT5DsYF&8f96`a=8m!XdFMYUr`9AqRQTqxP=nU z!DJOsy|j&0i#Rd`)DTn4$G{d|CQ*jf8%?l;MB1W{adt@gnnh<`flih~XWJkq=@^m0 zGSK(@-MboCH$}|q^=grdq#cwlvz)Y`7TL&9$LipFb9%~2wzLO_S)Ddm`e#<*#)`i? zRj%2*O$QtFI}&M>DmHeJG?01{8AV)u(e?_DM1W z8PpDl+gxNdBTae{t_yf-BvOX!34Vx@j6eiDcLv{cT~?ru5u9AR&JvE<2Im1e2gsR# zRCY7~=fV}~iyF{FDz8ZA4jyq^WVoSI@mR;|^2*+_g!7WB0M1)0)-IMpswuDXcCLxq zt!{(kfle`w0Sc#u0teObuy_0IM9tV5Gq;;>?!C8t6P0sNxO`-2#srMHC# zk+aD63he8@qc!|LXwBUCGVrc5O4sxkM<3k?OtBg;60xSArmPYiGU;_)`tplD3K2J%J1cr>3$qEe7q>EyEg-m6ZYSmopfy&$Ogv$ki_yg zEJStz_P>qLLv^!WaNWzt*g1mZ6s{vxz;z-|F{2AG^!2>B2aA*j>A#t3%C zPHFW<+X|TO)$569^83ihtG!e%HJ_Kl3Une`2h;}$2m{ItD_95?;q9fyaehzTU~Q@2 z^Fr`{$Kdn#2Rz#Y&sS6q46H?cEzBfY5-@MF__d#`r=CFCFdr40 znD@|%xRs2}y+Hm>?NaKpcF7QxXs}D1#x8|v6h1l{=k1oJ6)N_pnCvM0D9&!GTH zr@KaE=lr&ZXV`TQ&pd3gUA2Na}LGVKlfswa>OoR?d z2c8Savst8x8Mwe`yNz{K%Rzvp4=*pv1358={IkLTu;9Nc_#YemSHsQ~DS<{R0CWLx zss#bCF2^nyUw%%?UvLi2t!%I>CoWK1xjdA95{?1bg*dasg_$MQ60@XE6ilKs4a}4Q zF10KXpoHh9$J@qK#Fp+`Mo4XuW#Ov$a*b#!)C_FI5DGP70Ed{7X3?@y<@=V^X!lwC zo*(=mx(`0V5o8W|sy`$K-q8106b2#W10_OlAePYhHBdTi1Fnux6p<%;h+IGdY>qt; zLWYjRju)1JHXlb?Wf|Iy8n&451!8>1yK%!#6MYFa;5;PUc7X{#4+}!IF%c&UFBm6) zpGT|lNp*GeJhhsy95@72m&9L-r|%s4^N?rCurQ-A|K7bVft#v|$)I+Y@iQ9nJ1|v) zxE`fnYy(3*NAzlpIL(LB!@%&xh)cXE9j2bU4a$1IBz#z?PI={YbqP^?5q&>v4FgT+ zD9My4>!YIKuo!jpM1NrlE|>z`+C+!KJw}!$M#_$vCUg>wSazWKjy*E>JX!pI3dsAA zYU`?@My>U*^<7iOg&(bgMVMh8J9A>7%F2SNAJat=b1$iw3hE`PH4OwH1D^%YGXfvF zqPcHfiTpoYG0o&Se?3675ulCM40+^3U_k(jBQe~9QqtTJdJnOwst%M4d0r3>7QHD$ z)-Q}mm{}Z$BZWT}C*h02w&D!@xp1s_YSf3)qcEsjt4^8}uoENkg5WDoNVx%~gYd3b zB;G)T@@)`<*51!pSC|OQ--L<$blYd3El1*dDTBxRh(YBKgECM9AaMuSER}#*wt3i7 z3kW3(js<1au8-K(f@Z7*`-dhA+M@^oPXrr}+kjS9ox4$-hs1j&#=Q}plkBsQI0@2U zK>C|mtv?qSkvRSov7KZYhCNF`MS4!?=O{rk{WP~|buKP@)EBKLNyT50je zHo%F7EEB9{4YVyA2N6wVzrQ3@l@SrRV&t@RRPb?M`Uc_yk=DpKf~BSJFZ%B-c_(MfVO0q zwlaFrA-ROG(sbLFQp7$3Vd^}@nv$a=Je890bfg~yJ3Gy*ns+yb6tSR%#)dl3JtHm0 z$5$(RR1%&+OSl4oHqRK33t+-|$eW7vKIdH*&ByaNFKPqI@H$oT)g`KCs)*q$lIu*Y zBSyk0NWuvy!{dyOA5wUBfvru|DwLPqw=5NwY5S_`l9Xmx5AV?8Qb5mpZB#ws@|H@B zk4TXrGxb(;OUR6n`$H?QNLluiFewQ9iby zNVGGQPcd21bK0F9sdt>Vxebwh&LR;rR0AO6C?$|V{LA^SyBLI@wVfeuE~IDx&3o9p z!y7wbx3REk%GuNIm5~p7Yu!Y2#yLd;_M$JFkakN?kw`H`BExjLibR&_fPWQp-gWX0 zvb9_|?S48k69%?Eavc0W5~*>f4%k=N-e@Ws;8wJ|PP;QBBb`06g@84xL)UwC1E@>% zZ?};Vr|=J(io{yxeSjJt*#%I@y>tt7yZ#Nxc{Eb#JS;11gJG^9O_CPT`oBVn6-q4s zDM9N=iG9TmD5;L5+ESt4H*7)RTGzYomGHhVUOMfrf+;vs6Cz%r=YrJmWzE<8{))vC z)6fEVVcYid1Pi5nY+E6m-GLlfi$iw4{)f}7CNd0=ijQ(DbA>f>Q@(7{ zTS+%Rxz09Smbe30uvFlEiKYbM;~6owEJwVXi5%a(yEv zGd)UoV2UA#F};<*5a>#t25-VST`;hxzHlS@-99D7fTtmWW%lkfO>Se4R*DApf?AMd z_H~Kdi)mPeiCx!#vu|++rrT)e_+XRtYhM+II`>OyhKYKvQx2(A5F%7SBb8zfizn%= zgyF9*DRhxow!6NBRF~~jI8P*!7G%3g!}TSyeK?nX?IU>89QLX!^-aVkLf{~v_CNsI zSEchg8Od#=eVwSX(Jw%PR3xa>Tc=&7CV_%ZIWnj(iuG1aSL^_Km`q`8Td`)ProMzs z6Vsg&9O5N;cE?w46q2nOnPh|Jv|AaO_Wj5c1H%q+8}K0)-bW~^ytuYa=`Ns%fU>8} zpn0Uo2GZ4FZCkVylUQH!xvK}%Y(1o*K_uQ~6+Iq$kdLcVNry1s^0g4u94 zr-U^$^#zGDXcdtiK#a_c;&3NlbmBUm{ySNh6u;4@kl*e6)%9VVK_=l^6M?{cka)_TA>xpt;uP5U z?6*(ai*BnZ*z)>q%3cbjD%zPLMk%35Z#>L7*nsT}py`pKXelns0BVxg?3n}Y<(Z-? zgftKji_s{)Z;uCgU+y?#vfn;u_r=qF4C`w;+$UEOoYwbz%^#KlmO?9gdmi6^ak;Fa zLnoWxX6$dzfe?k7j7_^;Cv5P}N&j!}EXtLq-3ubgTNcC4zlQE=Qf8KPD)q&kSAM3& z`_qcxH>#*;(m|Qh&4gY82Or#lG(WmvLtA#mp_R>Rvp2Oj-EpOgqnQw0ig#-eTe2Xw zD1t32%fY^f9}%w18e=1z#m=GgKa~NJ;{XHL0cb8$>ArVe1#3y!Kzmu`0JE+mIE!f- zLK!1R8IbKytnN!!5pQzo_^e!yOdoxsZWP_)$SaO`P^rk>I9RUNa2ja$VRc)! zrWXc7da{x2qQ2xCS5$<(B1C=3m%oqr-ujaJelqZpL2r=k8Q~ zfn5ffVhh>I0O6B!-L407e{}_JezIGrox}Yx%Bku7VXe$y(2#T3=lOXErJadGS_8l6 z@p~ViW*PBXIC;w$>b|A&Qs0p?`WM&nTkX%h{)>6_$y@w0!TihQ1pmSH`Y%Sv`z#2% zw8L1&>LSxH_xdmQ3UPC%*bEhP-)FS&3wp+IOA-3|FPYDry!Ckymg#P~#XN&2+96-z zma$i)1K<#M;P~vDs!&GsNo&APu$@PB-3i3O+YJ6$yD!h-7xSpT4Bj3z6>dY=LgH5e z9(5sFq+=!gH6wm5ZRU6K*Ih9qeq#E?)>Y=H=j{Lc)Aa%-^A8pzB*$2KVq9zS>G0mn!F{jIHtZ zuc|2OUv?|VvKye+9RboKv|&)SnpgEVg1K!_*fT#XWXWKUizwk23<_V(zi07ua84so zYM}N$muXdQ zh8S@ec&ASkiVpC26_!4bf`1jBeIS9tgTlTCa&7B?qsJehv=tnf-huO1bmNI~35PP- zcbwp?&*>~6qz0|P%KHiLpSOY1ldfm`@-|?-%t?%*tv^?T;iD0fbir(#D4zZf5Tq#Y=ex+ixB%OgrvoYT?*j}1RI27 z5XzPy_QC(7;{P`C|Cjbb#}o`w22%_E&ztE6B7)PxvYyI;r>g@V+f~0Tx&5|OLxB20 zECM&K8f!9>j&9$ox$-j->ClL%Sj1?SgYqumC)FwXii^=aTzWV7-w*!}m5Q#!G*B%} z1pG*hMqVdB67c-&&&nQf{^Y`Gr0q|GZJ(>58)(o7(ZG*?RD*SuHW7tV93a=gh;IQE zgi8y63X&xd{LcjQ5hK1K!PFQIn>3xk@1>f_rUQPov;fm$yth1NLrlwbnE#mS!rRd_ zrI8;&0&bf*=)XBy=scw*@pE`nrm(~1sw41S;zP|394HrGJB7w^Nc%CIf>U#@Nmsfb8_ z8WbYnE*b#FL0@MwiWH2m(?yV%9_(yf4N9B98+*tSTksa_fv_r0LO2EC8=&fMVo>Vu z6pyl}I3G`(?2!NEg|c$%CoQ}97@p;55l1X$KY~L?;n*TRX5KO&+_NasmOBF&IxxuC zTu#8AmdM*U_ZcIT+1)f-(iyh&ju|)LWG0eXIBNQ)6DIhG{I3Dez%Y4D6@BqKaiCoi zkk_4cA)V}qOaPx9aG?W{%T7jr4$^RS$S$j=#kqms$)jU9@i%B&z;h-D-V_9XKM4LF zfNxe9#UpkWXz@)uE$;kJ)lQI#q(X~-LGko~x(|SyV+c8q5cBlmkA50ivdP0@?6Rs>z9# z8#>dhQCl-Dl(-yDV_A2)g|iZcmfxc}UC^2e>d|XJp-Z6M9*8#t_j6_jXT@S_K=^S9 zr<(%RXmY?Bh?Y-T!CBN+KNy>^Hr%bi92~35g|wv_+jA|Xa&kp=^T=>&kAr`>H=#@p z11kp~(}EM~GV-oPUc(7myagMHnaDH1t5gYA@BG;jO%G;1p>64KyYA zJ*~r!fX*%*?#C?i8h92sy=oZ#TP>9XKjh11g8T|`C(vvgc^mR38(|<1K@2Ln;G4W5 z{IFC*^-BWtP%e%TCOYn;D?2G9QQ~?bba@g^5i*wR@f2bHa*g6XZz-T4O?Y;B93C(Hb$K3+ z6~10RG1Uf0zw4BNVrUkWzXw+);=B7c(4Yw4d4lBJ7`)*UUVC)3a8K122^$6v!pjpa zF&v*I$j!0jwuCX*aMFt0h)R_GorLPLx=2=quyjQnB}u}D730~{gHx@C`;@fs!HUu< zzXx_-a4BKjS>SI7H*$h$HTWC)!8fshXWWVMD6k57;K{&~)a}3sOftaS3?NMbwBJ00 zGzN$phjbv4R}OTqrOH54SBS-=wmrhal_|JYcnbdCKe2bEjIzBOIJ`mMNVKqt=rG*J zITRRiQmbwy`c$NeH(>E9G)>B}`0oIQ6bGqG!BiHcE(REPGQt|doM7?Ww(90Bpln~V zigBw!lZwTvfDZT}`6bYoR+Hz)!7mc{AKLFGc2WLgV zBM$^Gu+#)@f|Dz8Y;B~iz-SR;Jjb?f1^R?;gdbKF;u=Bsh%R*RN8mW8v0DS4J;Llq zG*tMou>O%H(bYkB;02Ad8(AycIP8h{36E53seAmwi`7Od&M!Es3z%WgVXqMOcpY`` zknq~$YBg}wm0PXhyq(vqtgsq2uUf3o?o|MOJPU6Wh993vz3CTbtWBrt{KB8tj-~ed zgxA*QCWk+Q*gNZht9b%AA3**no&~M$Djw;Ocy&m)wRSu{CM2z^S<*E0_aImNi2sBO z+*oDDU8EXO)kgAB8ysL8jS?+k^J+V#4YTTM|5f{pbM6NDRGA*#{>DzkWcsVZDOKec zfL~2@(0aWC1JBWB&$1$M;gFEH-eh|m)c-C}bc;0^*18Qy?DySup$wz=qWy;^BVc!S z;Fik{&(GOGMnxUptbz2F|E&>adH|}-bAn2$`n>ByQ1%Kp*T-kpo6G?95U1euz*3x&mUH{; z_0kG%-{a4_G#L|}it%}*6|T-C7@kP9opK6EO7T4{k16t51< z{Q~7-zm>BPTY-OVa8TS2fLRXx5&j=SE8sW|tud}Cv!1Q}+D=;&R;l4O16k_~4=&}k zNM|Sh>|56UZ8JP=2|A*0v?)t@ug4YGBQ1p{=Q{RCiy^LbGVVPg7o|P3vRgpYBGp0# z!1MEuSoPag)-l`FMJES=?TWwp0?un|YG@L`1P=4B)x7wZCS}u3liI0$F&c8^PJmNk zunpiT#Pl+{kx>1k-oKj?I%knRV$e3?lzBMth3oI8YnQISppvL|oV#rGq$VuM+vA#W z-VfUvnn*J{gPnZq(r-^L8eap0gMl7*=y7+C6 zfTjj+4a%b94*db8t%3W6NOajRf~QuD<)pOSAlUavD-6QpBHS!RVi!CufRY0s4Jkvk<;U1GhgWtcg=`Lttjmar_(7B4Badeqq6y@f02sYS%af zOM1L;@==v)vHy1`IlHt}1@@Tnk7iPT@Cl0^P0o5C=%%Ij-+~LQH=V>f8|)I=D)ViX z7SH+-To@C<&a>4Drw{RC6<5cy8NoY9$S;IF8gKh~SOm8_a#xOAG=Q59Ay`1V5z5%{ z8)Z18YWpckZm{SJ+AKOGT$FZIuQ~CZ#2g1^7eT%40KaYR-w6CRLP?sFlD7TDrbD|T zy}O2@oAwk_4%BeM6yLdQ*P&g?rs$@ZO^oxm;IX+YXI<*0Nt> z4CJ2ah-&1mU56f-)U{v3%SKOOmh^=BG=qDwB{W`o35>0tw_Q)#R~O)CtQ1EbdgRUN2$j=8e~ zQkJ@^D%0Jbs;v@TcXcasXYsnj%cCmJ-H6C%?ilB8k!Ec^E6o50(Rrq+d{{Xa=ME88 z$?qu-j9hd>sY4#i@CU9XMI5+4%=F3lBfuD(1AgUu2)2{(XK3Dbe4912T%~zMdeFc? zbu1c&te{9a3SQ;GN?-x?dfp#Oho^gn$#peSuev#mXVUesc#xQwPN$AVqh_YVLWl1a zfMPd}zqJJCIjgDMdei7?>3fu3*=wXb+bCUqBCTt0s;cIy<@fZ^I)KscS9Cf)h3Q9!Tl+>VTJ1iwD0;H`~sZm@$tMaoc#l!mHX@U+7l_M2o~1@Km~ zp*7-Y6w>n`lni5Ux;`n9WH52ekQ{< z=-CbiZ6w|pCXfSZeelFvV>)zL-ct* z1D>tA^#HI~NL&C!hEjc=4~6e)o`EZob2sZSBRsjeMBfy!TEa^|yFtm2_;=WM>EmK+ z80Q1`2%4YOi0e?Q%yPt94@f#9+}Nyv8@jPz7hKvM4aE8uT;HI^t1shsh?cUQTucRX zUcJ=_TMCvD{&AWE>EQaWVMefJ#R-Kw3uFTL zjL4uYneO6X^tb%~c6}$QbLbO^mRaDHt}cZ6AB63A$TQIkcV207SNRW?s%5(6Z%9RT z=WfV#VY;p0Q$f0ob)Yop)(Daq(V##7xfEOYy=z7)(N;OmcKL{Vv{H0E5mQVv?2JL>1JvT`Sti*F)fwB{!IrU4Zo-SWq&+ z7;$6)hY6?%vM9XAY7hhi9w(F*Kp6v=1pQDDKZm#Dyu(oQtS=qPWV{b<$C0{wp>7D& zg*!{o;lZ{?tO7s^0Qo_%6(Tr%(HNjS+k~2}F-iM_D_LbkV$mr)H34j?1-UWk^Pu20U^xEyT);(#^utbaEt|$fNS8d@ zTggqCH6n$oTh9q)+vnPfeJN!)|4)_(>!(tfJ-H|m4=#A`wa!uFjyP*h z%OO+j_i@&YmN(*K%5J*Ud?+uvYOPe!NGhT{18AqztLh==Ms&|!>uaV%eVBTqk75q? zF?g@#7pJU@(3ipco@L}400_7@aaxTrczZe=^x)>keO8o)@7ZV3Sz{U-K;}c2$u{Zp zOdp2ng3=mmNYOrv*;;IA2V-!bOIWhwUi_}GcSlBocMz<5;DbAb2U9#%XWG%$9*;O< z5fZNmmv`hu%>q^m`qRIH}QW)mye$S6k#yNuK;+!k>dQ9bB3qs;?kc<~&Cia8$6cmC5&C8Urft_SfPP zOOwh8|5WHk_@)mnBbJfRK?29Ty1W!t%4Im*<(fg8CvB({1~AFHM_Qsnx|EE=E226J z;Ekh)?TwIULD`==u0E!>=>D|Y((aPOv<`Yghsd@ZA{XJGmj4nY?&+pTgudE0)d=y8 z9po-25;fqQ&4NWj)y#tCwI>y66=hY+BDq7$Bv0O;LKn$p=$4U%=kXl>C@@EXWV;Ac z&+x@+ZUfu+o(VY%T5joA5vLy;E7-8I3mQ3sGruZUTrbU0r7ypj> z=&Vd@xuwLa5V2ya*=!-zH+#wdliri2-HvzMER_QkRr|L#8>i{bwp2Y%OhJ8U)w9x5o^(cL;2X2`RDL(Ww6r7Pm(lg*0v@jLS+W;J@n z4;OKnWO+B-YvXY}oJ_wlcs|b*Nr>3fUdf=GT!EIca8RD;j^a)U6 z5&HLNk}ChFe5ACxWR9t-&kPq(CKx2~{FB*~V(;LW~1M6RWey2%!31x%-pYYvZQf!0vt?|pC zJIuYtqwF3Bz}ik>9$aedTo#o%? zi(rhswDDEfXKqe$!l?BshGz8AVVqYnfW7kmMDrlQSQ&zJqi+x#smV~3K6P*itS>FQ$k@vo5BR7(2m2!MLDLufTl@nT<~o)(o`5rM8RTKF!lQ+OxQ!`hz}Dkv>aeN|CI z!giQt&s~LYbRN(|q1+eIzwlMZCoNwu)*cE+Y5xC&6i|2bmakB?DIH$|OKjWgNE-T7)8F;0O5Q)v?sxCooM5(K4 zR&vT2lIQgy*p;dhIB)^Zmpt`D37q741$Zm+d=9>d23%n96KtT><&b!2P!87(p04h; zE-)kUCHQn-8+=p*oXf>GTi|m&ze!T9kpJc&0{9*9KT`e__=QK>;OZCo>K*y6-^f?* z=D@vS^3gFBd?gOSSL2S%(GIBK8AOZ!d?imiU=QZN(81@Od_j$TMGRSpWD42~%SZ?6 z)8s@x1ey&};vf8Pi3H+E(`oYYE*sqE2(K=QOyAR1IRJ)pz=JtCLQnW-Wv2!-dgQD| z;)K&kRD&b+T_?P~8=AWVu;R;SwkTxI|2}_thSVnkzSIR8Z-QB*LQ8ZNVspHe;k6Z? z^oPo$!%}J&SU)l)J*{`VUa^ur!$uE2-zWfpWL>v$d)cKOCn$T7sTxxQ$XfEq|tYpc*db z)Y_)yR^-9=>g)yd9a{{2XVcsUO0Y;Ci*GzMwA7ak|BHN>yX(0CAA8Aq?5^jZ!xM%bg9oXd6?2fL7Yd# zUJz`DhJBuQhb6Ez*5>1}AA`yT8PNjNBYe=1YHdce-Gd2trXJIsVJ?mRZnW_i%5PJ|Vz3W*G>x4WbE!HrlZ1Y{u@?p{% z((YTv{#Hi)20Q;huoQgT1}e`KX1_X$zcxf?D}j$hD6B0N3|~kyS4uO)nPnAm@OB-* zYZkN;tEA7>PSiy34j3$Y@Eso~(gZx0K&1D0#!A9_uV%(k{9bE~N!f|-pr{&??2@ds z#`-dRkW(%E`l=4!6k_(Lf$zK%!)VvgKO=zvmiUZ6F`%iDtYYdxCrk2I>Xy zZI({}N*09r6x{#)a0B|K{ZC+Y0rg(?* zk)7bXfOYAq?fsikh=%desn|!;drY*OqQRR*c>LgKtP^Svo|@Ad2aYA+`%Yr|w^)u5 zItb4ScqTD?1O@GfIOMl-B|H=O(BGcJev89{@rm7s;<3${31&|{Vv8ZpAn6SFL|{7H zsfG{*>0^+W1aTUKrN4zYvq6bB9SR%%Ys^;F+UJ10&j-$p$reI%dIP5}I3o$fgj69!LVo$jI- zl*VF|h7d~o^gYBf@Lc-`>Yi`ibR>b-^*ii3bH5`m!S+x&-i_-~7V3M`fg6y))VJ3$ zr+jW1G}>QPsTY;BMP#AzFnI5-w1_4;?Cx{FqcY4!fUAN$CdecF_gS!6tVQJ+Q|p&l z$`dLr<@J@+EtHqA)LedkNdj*c56-bC*b?~Nc(5aZSHb@T=;dBC*fAAiiztW6CR-t6 zzsVfT#|(DdQx?kCLOc;-vq({)wh6%}3{OxKq~uz4x&)gM%IQP}Wfp0Ql%>Q1N}c6% z8A`LuY3PJ$uB9K%rR@are$yIwSrcs=V~yvv{oRFy{f^o3w&1fCo^#`Ek-S!f@1kRN zqzywJQ)FR3ip1o5zbQ8o8qkTRISDrENL5J!zl)xJ>(Rrw9#46|jf$vw()e9S4RI2L z3}1F=DzA{aa}i$()}5^Qr9N^G_T zLS%WAHIfgrMB5^R2@CiIwtBwaHdkUGoyk7WpSQ8CsEzc7twys6U{Cxp+=Ea6XTx(R zgbNV5Ap|f|U4>Z4mTMNoSYyi*`N$f&-|@`4Mw}bzh^l#}@kArilll8=)0V!-nhzQo zjqy_?T921C;>kDMDC-ZWrQfkeULI}3`W`pRaXa+gNa7dn%BrhW~ z(y=DYhO~?|-f^aBGgKJx9wHg8$Um7bw<5p-)WpLO=STl{)sQ-7!Acl?19eYo4xJg! z8Thc4Brem2YmwL|W%9TViPMCCE3_I?djGATp4N*d%NNpzxumWtz#*w)0@NX>*<ok3hchT`ZwO+SL5Oa4=<%WD9K!{?vxT=pqJZm3(gPP}rHo76O%~)LR#{e)RVGY}iL?n^_$^NPmT#CizCs12RIE9b~aHnNCEUHd0 z;*Qp7Gq8Tz%pE$$QzbW4ZEi+d4M&U8kYF68woe(JSf=6bv(aLoKi`Vq=ehj*lWdgU zP=&=f-^FVP)8efGMxSrX=dq#qqLFtXS`77NS=I1`v1v-*vLi9ne}GRZ?cx{Nu=wO) zB6PFQmjM4s@Li@$cpB+atqC?7YDHqZBp0KGldNHlNSrXmp9l{M(J+`0{IDs2#X|#F ztntglZi&%{l#(Jzep#^SWJw;34@+2_DBy@_`7yxZ}M<}zS7PWqS>8Kfd{1EfTsf4Gr69~{tj=W(-xIevlf zzn}kL1u}S?xxp_pg%(xvnEeuy(iJReA0T~by(+$d+9pRKHs_kRg5e^#AFd(2@YvE= z`y~mz1)=&3cV0rXkfu{YDm<|OR#}~SRF{fxhv6G1O(>UfD1&nanqGj(zDf*3Q@U|Z zG=IDer{k#x(`-p!i+eXmw0Mxx==xDYra;qgw(p=ulK+?Ox0_y4LY%s!Xk~w ztgT!eYQgq~GVbxU2NwUbneh}+NZbtYZjq8|vADz+@P0iU2eXY9KObOpx@QC4ABRgh zn)K#nJP{i|a!2zKWeZWX4e7#o036Z1XVx_JRw|h;O8heL4K%;UJxkIdoEOH^p1^&l z_=p~wE|&D@iW{{ZfkkP58~#3o&<No|5(qgzmPOYml(&81riF-k+ zG11~VKbJJ~WHv`lDB$G1TQC-P4am8Qo-H9LqsWPRLqgy8upvh|=H7M*?K1)R?S6)9 zEGp#igjw+RivNM4bH#}+q$!t}CE+Ld)BHoWkzSc@;`j$8;1DvLPFj4&kB!f-kQcpS zjy;Vh%qaG_R*7DQ+2rC>D2dW(u~Rq` zJ$+OnywT!WG7H6nLh9&LcH4=oP$#S#ZnW7@2}>;C{V+h1R}Ldh0W3B$EMzpK<~T0i zD(AwvWIo_E3r9y6;#}d@=*;oqLr*6lN~X((g%@PC0UX% zr*h(2`XDVnEX<72<33?^%+yhD2AFOQm&SYClz2dBiOIxEh08Iy@gG6E1)(U-2%(@^ z#^E$ApobDAAtyHZ-dTZJEsW;@8TnEkC}@GrCGX2?kpx=t#31aE;@<~FcR@2C(W46H zniR-rQBNSf$`f9Q)#4Mv`>{DO2LiT61FzvOFI&OuA4mEFOMzb$dShpY{Cil_@<1si zo)L=U4ES|nb(}u`gWuld0p@SgH#uGx%te#YR-TCu&*>2#iR{y-Y5W4cIkRLy{;oTjVISGd9A3oB2)IjT1l_}tLo*;9GZKkYPlL)DM21ec;yv9h0X+lT* zcsxyzB}~U%LUBT-vSsK-(^lxXh9i?3B_QqxHMO2|#h z!AZiRq?Pzt;fJK$RFhA}l{O-eO_BXf2B)5w3;6opf7tAG*%-<3Xwn+K&$GHNV)|JXGePBnqluvb{0JbCd3KVi(sKBR`}nR897h~XY8 zPtDkRZY1XqLpR*l zTmI;a-0sjJ{U3d*%};-_31HjYr>YqP(|0_K!6M)GKEe?>beE)>BY5{CjifdWH+C&0 z27JqGYxo1Uqx@ytYwlTq3EKd}ebWdv&fARZp~4qODtr+tM4nlchMUigp76spN>7PD z`>1-lVUM}rH8TC6&}K@&4N$7)=}$AM2U4if__-f z0PY3haB4m^&nNsEV+0N$MpK51ghiS-JWhC4ldB!?^SRrB#gJJkyQ+Dvl&4|H*LFTtk*r^?hA355rJ&Exn!fO4b^hY2o+sufS zenwmjVUd57Rn4ng!l8H~zorFg6yiUGAM~mC@4^jzTJ*ZEtovL-AZ`IN}Be|+}Qe}LCT11fh!sB0(g=K3%Glk3W6~UBf?VElOqyj(lv5pKCz~BW8dYnw7@_>b8KI9}a$Wc# zOB<6n-2JD3cadMSD&T#@Z(GGS2E6kG+AtYgg?kNiv0vC_NYtMh+W#jan~wrNVQS2wm^l?bgA{$+^CIXjH>Av2RW*y9r?H$IkR%;&kCQV1|1Uk~O36TxPCTnuoM z4jA4YLS*){krR$ab4&5)ir?msV`9#JOh*ZOvva1hWwb{{VSP9+nDmw~o7k%5^xRJ{ zr%)JcLQ-EKiDgaQ&9#!cJ^KENo*8ki^9@Yg*$-%yAj`?UM^?Vsgft_PXm=|LA!YIh zNg3<<(DmQ0GxyLs%SOV?b;)r@!24xe!2430@KnwNr7x(5H+(W`(%Cb<~Lw(9@7&c|Fvm&Em>Ph`V|&kqb*-uB(~;q*WC22-D`kBnW)GS*m0a) z&A0cBB0@?V3vJUI7WWm>^jade010p)y+ikZQX&N~uag_~A_aIp72K&vUJJb6hQ2dU z2it5CHArrim#aau@FGBur}$j7X2`pA5NX&}6=F@MQ8ZEkPb5zQQA7?h{kQ)s+w5RA z)TR>3jLGWn1N!BOEd{LsZ&zTzoyifhX&>$n?iRwU#wZ;Tu4FC1M`J zjY+nCK%|OH2nYlUsX1b~0ywqDTEaGt7q;e2rW#v?_Po)Bv9A2}T?)FRawE}4RsLDK zQEe^9r|0!1?QUx7J)mUI$CP8eir;Rc0pM@l$=nTh{)<^$F0e`QMFH;C!To+$gGOW+3xFmh)Kx2SE53LZBLN2e>KNI4Y+iw+cAPepz=!SSd zz9-;~7?OF`(Xv~wJ)`h^iS$JzExm~KXxIhok|ycI8PtNRfY(2`V!dLVUYtR%SbZLJ zMuhQ4+R>#6wh9qPEwF{@qd^S@+M;Q5q|wv#{lk@Jh)p{Ewh>J&L+dwDdb|GVfcGcA z36?xt3fwsCo?=PBn+q5t*do0%MxZn`JdcLZ56@)Ca<282pj*42VYpQyhsj=dY>@HT z5P8G30q;kHd!&1FAOFj$zEd==ixq9kE%3faT5lv@wm=ME0QIP__t0}IdZIzeYMQIx zBy%#JnBcTC`HQ*_Y}_Lyb?=el+Q)8Oyz!TfGkO$b3wvno9x1lg+!LWw`d*O2nv}jx z!!4e0Wk#p+CKI|q$`q?7B6jvYi2WPH@85~7lMuV}PIv|4qYy$MJ)iu&31N?9Ap-h+S`#u!?eV-}(t!HQSSi-kR$?Y-Sv}mX0hEtuVdQZ`z z!aMiq?E&wq!T*`^0q;YD@4KIP_Pu9Cw`PM1V0*)fvR-qM`l)fTE;QcWUvYS(mg%?4 z50iT8P?&s1o6QJgQ>6hCr3|vky5X&EG|t{%a2P|GiHB)!NgorfUwgOS>HSY1Mp^c< z{#A!ZDvyH7?{ke*JtYWWguJ3>Gy30EXAHaCkDtWjX_rYkrTEiJG@6 zM>kpX%G} zN5Xtq`bYez;c7y_`;GrqSmc!MNg$Meg{S8?yeHWoJ3_p*z01RWvE zE#Pe&>~ddHppFrMN4rM@r)CHK#uPeuL?RTFY;f~s&)qDalkiU1re_dRSCr1hF8z=<5* zWxl!A1;E29q86-;-%ulu>bNA$_C4E+0^l5RgS7=UOf4nQ62m~&tz?Oc zFwBz_w%N7e3N%AeS!V&Dc%REnc9++EZehi=c>5aP!Nh=fhi~$WHAU}9tfT9S&bsi< z1hw~fe4GkY1h4`u$B$PMXR=zECkBDI<9lTw#)u4|U0L?tjdOb_z0A2{0}iqlE7rDL zS+RlAN$vxT{g&)w71Xf*c0Z->4}dvSK@-;S3#q^0v?NWk%mW(n1w0T^RRw!i``l<- z?{5=e*i;b6W*L-TV0iBiaY1v~jBcBjqk(qRmB@g*M*7RP3=rs^(F}U|VGQb=fVWPt z-kXVc3D4Y{lbkk;w4}?tgfv%eLS7T2@+SJn9O#yG2^o%C^=|S(% zke1VN&wz+fBn9;G|aFQo3=XxkSO%G2cizr}=!2(>2J9LD&;d;v+FnL+GzSb(M1^PyH%qoeq&3@yb&kisSW7)aaqUtz zj__k9DevK>s%4C4ootU?T5l>6Rm@XW-#6jhP0}N#rJ|itWNwm5O;4>`)rTQvzf|6S z*@bjTV@>If2bZ?;|i0V>*3t)p!z*6>ndVvT@Y zpvf8zcyA6oqaj!v^nUOuY9sdRun$=j4k7g85HtvC0y3GpA(j;&HXNuS3*oMi3!hA2 zs+?^?5hJs$8)h9@W8Dx4X(cq4fj~&CsvsO~Is*EMG9;k-O=f(CSlO|F>$jQdbEqEY zq1`v#U~SLCyM?5}B&-%D7mmlPh2@3Msw0ak`u9Jr=Bk>%Pe9saj=r`3&tMVv3sT{P z2OC-f*HzX@ph1>#GaB*xNc?aB%)S|C+mL2NU&e@k^P`M#uxl~mCq9$`^MU9!MKnOe z?C87Tb!)gDH!-zRAVP<=FybFVwK-0KRI*+wYV*-I&8c|G6kxmVaVk7#Nq3aydv_A|gFCtz?+SR|2oQ-Mw9cSJ=0K}QY>I*F#1!im zmKSw|)eyU>YG28qw?!x`en$%~5uh@`A_i7J233_PkEJ%tKLG20BG`KbMtoct#UV(DIHt|BA#Ji5R*SV&ET!8Gfmm z!eH$*Avsp(E%B#FOc{WSSv$7N69u1c~=6i>GJ{a&SAux%xr5x zGuDBrLz@lt;Q&n7iAc|QjA&Wqm)DB(k!X?_&j$3R4`;2X^f>MllU6OH^!F(A7k`603LM`6~=oAIiA2&?%jNz7Z zhoR58&}?YI`rm9=m|m*HKL{12aYeVFH5m{jVz=mP#Z&d0RIT9Ru{_|FJ|l3C;N z?vjVGk#=6@asFi+QTtpRBK3++$sM>Z94yTU|E&bE7a^>805pnEhHtLujIYAoD9i7v zDlw--N_Z+I;pxaQ0Pm!$yBkA`!Z1*+CC z4!#*smY^vcokkVm$uy^G7R(AKR9Qhw*ov~fF2Rgks#fwg;1(V#yU(t98?o)nt4dOv zVJW>2MnXW_hiz0HF{3;xF@BJ%3qxn>%{q#pyy}9NaKm;xVn<;p9Kl;t4|`S)NYRxjSbb^#~tU6d!{R`ohLj7 z<-N|)5NniEohLkc<$caW9wXh=6k@38RD%OmR2$`2Oez%}EajKqqv$^2$x&uH?I%1& zWsj>=#4ObS`1^no2pDHwhdjj~8LjIK^=Lv%`_a5bzHL5I4cjIkd&09!InZPhw>fZb zX}_cN+a{#j-d!qEY^lhw=iQ|u%l;ewRqR>!@mt7#;>-!pbIKe5YppU1{-0E)xib14 ze5$X;E|vCc_|M%ZJXuPWi!`th5K1}qJ(r*T1ne^JwGoI@xW~+;Vh#Hdkh!Tr<7sv4cXOg04jf{YN#2l+XJb5Fx9c@ZYo*_4MVDf-|B|`S1GBs3;<%} zBU-n~eaN#6`d)MHgr^b)fRTm4TT>AYrPf&0ZK>Qly^7G#UWF`9!imdU?2|Ym zc73~PV$pXT)zEsSLd*$0<*pD7q3!PDP#tz^CV$%m4M8)P-KUx^N}3~BSZu}h>KsKpRvqAQ;p-HrE_rhMLncm30i z8y2Pf$Bo8baH~a?Qr(90-EM*hMyM@e8t_yd?0B~UA1U1bA0GsF;jSi*=??V-rWm1& zy{<&hlWe5GLmUk*g%6)6Ak}lU5b?pnqUfnI;e*~#8rQEk3+8EU|MVbQR!@p&w;ARLa%sc(C%oTCXj+$4#DUOHOzK(`Bv?l1K#%(1JRsqQ#x7zvkAwgIG0$ zBnYTI5P&LG8ZI|8rHzcZUR2RLNem^>cs+mbMQS4GFDi>q^K-FCBSWC;5&$^D@(yUtSBFoZF z*5trd3Zo1l8w*!Ml?G82CO>a7Tj70iZy`?gZTBa_I%k}zEwg$sn7B_l09ZCuZw7ik zd0<~J%Yx)9kvu<0j01_y4g;Y3cyTIVz;UzDQFK#9`J2LeC`tvoJ%bn-N>UPF;E`SY z&=GOSTofh6XB)Fj;_HsA{`T@LQFSK^3wn?b9SI@^#o$r1juC6%?c<_ z1ax30Al<6cUmTe<@YW9U2(zZcO~y1`OD4|~{$b8I3d`orEaV zm5_>}V9uW4oW+K&_j*}$y!abnwq-?xCT6;DgP|yyTlQNCHx(L1i)0>3rsqeu&C{+6 zmj8t`O(y__yy#2-!Y=dRV7fu8(L&ve)NMK19stN_hwOxy)Rp|x4Rbv|;*f@$pMus__#em8}A zepmUZe;0`?)8jt!d;9Zm-Y8me?04?@;P;C~BE$U0{pO9r=a2pVk6_+MJIrOQUYU+H zZ{E0X#jYEw=QY18Aoc6#J;Kl&Lu8(n?){n;ZlLFlzbnGtykQU~&rKZlHmKj;J~I2d zDvS|t3ybGQk9zsy9Bv_p>dK(M-wV}qE=?m7TAp~HR1Avou%Lqs6084wN%p1G-5FGN0|tvD{B4Dmb| z!oXw-PBTTS=56L^4!hI|s@9}+Al_x)c1dm+7>k2b!l0O2hP}Iq5HKM`PunzrZfSFq zRAg*W$j=UYw+i+L; z%nt3Bx{Tz_^&B=mhn;E$tQM`e);$NTl`utDY`zL~98t3dvF^(4_WeFY4(syS+g9wdkqC-L%@O%;Y8 zihVp{fDtc%HV90R;uVPz4}o~bh{@nSM}!ha{GugjXG0XrKsW*?3Bt>fUe!FBn@9)=AB1S`ic7$+$D)U zPy^nQ%qz!uM%*9~5`TnKHvUsWRY!?BwQVp}07 z79zG1LL-FD5J=|4M-V#}@=?%GJ_u+aUuLAx-K z5!XwMR#B@s81Pbo?3{krZ*Ed`KL}1p{IZ&90MAL926p+gYOF`;l;%ai2MiAkSq@0f zj5r-UuT&?4-w^{o%$=b1K44DiWExN!80YC1?cgKJ2!K`-hJ7Qk1ysoOiR+@P3U5Zy zlvZ&Njr~YU0s;HfFbCRM3?L;*r(s$%Vzz{hCh@^)X2Mx_9sspxnDqU*>KIU5nZ!R= z8{(lc)pj$wSyc^M4LiE|RP`lE(>R|yWFGDM21@LLZh#l|;_9>(b5L280>=;1MOv0# z^r1P%MbN|2v)u%>;Ccn7*~(!UU(m(0-z=$?)zN#YdJGg1=l$e{?Gm^$TD$;S5L&zx z0LjKsYc`2;0IxHMvxPyN8LCnGcy3%b%9-q1oixd*2z@oJd^Z1i%N{OFurEkU%AEnb zdn17Bc0uR0DiD!z?(-%lv#V*2(6%7Pt~jXpTfmz>OrTTIy;q3$YHdJKd&*6g!I!Y2 z3f=`#6rPVm_Enc|zqy zm!g3RreB40Bp!EA4Qgm9IUKL0I$H)P(b}`WPZt(?+W~b!vz!uN6-t&Q<3eHC5(8c+>{_DL+I*#ekP_c7 zJM}M>a#2l*P4(uKwl&akOeb3?ah7mqNj||E5e_^gboH*I z#Q@%Zlza*E36E8F<9cEG(s*1V%wL+9X+=4y{9Z2myb01*4v?)^eBrR7&r&CyDL%XSz1~-Q0BH-L=F5XfYlQgHpdL2<5j+A6g;<>4wpMs$St`CHG{gVD zj&>}QQTFcx2i6(DW(Ad_18|P!%fRg>Vg#ycC8|NBO#nY>nM8m}0_z}>Fg$4x7X1P8 zlnqa}1B@pHVJ%@2u=qz?Rr6-hqCc{n@u)%niN&n}!iUJufkv~6ybA$fdcf)CzzPkg z73TAEjjCqL@@POm<%Dw~X5d}G%W(^jvYCtDKSF2I&IAZJ-{TGijk`hvitF?IJ$Q}~ zx%_$jlCX1manjF2L~4*b3%PwTm!`mW0H)4B&|9Ng5SJ%Kf}d)&X;m42s^&WfSn8Im zg|H_Ju}PTuq<&QGXXFTygAaJOeZL<3 z@5K2;C~asG%m+cH*1fc|DGHtqF8xc15X)VVQ-yUPKTSsB3Mr=sr~3+nK=q3tZZg zizZgD5))+rqS4T(=j7$zXiYE_9m6AMYDQ)$IHAdIxD8JswxD?n&n^cC$F2X{!BMDv zQZA_0j%I%gI-M*D2-#~B*t5eTII+!c6Sl0$q6UYBBWqH|TpuQoW(0nR6MNTP7GPJ% z?4J)D#iijbfU;kJk8WQfh%vFk(lsi(EO6IF%OO3gA`HF==Y+N%Ax_qgF_eJrczct1 zNxZ$CQdKS4P3c!#B)QRMC}^|kv2a$};ULo>%h@S0HX{$Ex6#Bwd+UgU_EzH7tvx2` z+Fx$kzeDNUF&Ndf2adulw(r=#BLoIxmziR6xwnyBTqB`D){=MU~Ga1z2%Dj}z%MshL0?IUN_1# zi7z=8`CjsvV0oEfc{$+AR)>MFlOE6{fPC~XH_qJPf;S^JtaEir`;4y@Q$RakD_-qF z*{fWn+|NUht|CvVK#4zbS7%lROCZCd|6M{^{2&yW>oV|3Rlxga3s0>|$a<~V;+iKt zHeR7I0M~w8Vl?%RI!UgnUtQzYW=?b|#^sYbG<%ALBde0^El#AVEBOSHlI~Qkc14JE zM5n|XYovMI$Z*h!H8&tV{7yOxF%P8mH7BL{8Bni5Jp4a~mIV*_5W?{Cku)7Sb|M2t zeaKrnP$5zwjJ^V-ETV$7+?=QRK~mMqg&(f5_7gu`3vB=|j3I_AXn_-H3VGuMTfrUu zj^*Zz46ur(n}NEf4~+7tA{ftW;JWv4)n`|g=*w&R2fw_Q{@{o3Ox{WS##I_s^qVay z0X><@1?4dD(LutJ4SUA~6v3ly+1#L)8G6?}i+cc`x_k<5 zA8=oLfD`%@!rKsx&0CLb<-^KV+E=89jSQ5Ay>E~Q4afUHf1!-sCj(ok&s#j00k8iV zBuCUp1y#-A9Ft*y)sDm%EuEZ-VrFIl79s|aet%Ltx7kd2C~9<<3DJ7WSXtHHq^Xj3 z(|Sf@tqRezRokn+sj6xXnfa?bWacjry4}A&0%}JICs7jh)FrZF5Rm@1m;q?)&tRVu zA-)9xl~$F+9-aMc0}lHL)C#Ir7IxDN!MiTm{@#Fs;~U>u=Kzn3Q~nYu9aXj9dk?I8 z-7Gs_0MNhhUnRz((C&vJWzf6dFM^AHv)O&-3ER6>NF%kb6628HO<1NuZ+)u-i+k%j ze6QlPjUV)Ghy9AUDEPd+#}A{bF_nDhd}ER7J|t>)O1ox%ZSZ@jQYf zWq*H8k28d>=Tg}$LiohMkU%}3fstT%KGQzv{S#Q3!S+5xhH1jUudoqqz#w!kG1 zdXoo7xMYGGBtCK+_z>McxY)I^es)*T{1rLt@ zoD{_8HMmTO+%O4igt83}Q=S1~|AtN2Bc%W3Z?YioFMR%&RBRD`{>!5{Q<%O{OTFV0 zmTcUB8-+_7CxssL$?N#WL2r{JXzb?XTFDL5LB^0{p)t%au(>hZUyqCe-5nDDEZFT@ zIG*yBJ(Cg#gzxPfo-RZ?wA9G~;U0$xj}o4BjKzNy-gG2lESz-A#J>n3)tT{QhCbvg z`44Q-jrA|$yn65`EQIry;5Hyws~0Ce3OYW&mj@oOs&yZ1DoA_)rW#7~dmj`2QT;rA zL$GYp!*D#Ysl;$1z}rTZetnISf%5@qyXYfgYq-Ym{e76`W;NnklqRzsYHv*x-GBkb)Ftbx_le!Bb^|c{Y z<0>&+*5{_iot4ye`&o@|gVNPV&t`n(2U-!**6eNIy6_BJNjW^vz2 z>OwdU4t*H3doK;ZNmrVjR({-8xmdsCZK=rdC?dXY{X6ZTWNIR zCHIUp#xLJvobU?_04pQASs3hQ_j0{%5y%H2q{$rK4X*KiCMBwiK7{uY2hMv2nUs(& zFxI7=e^Cd{dSTjcg%VJ*o3P2`|zz}o_)K)MC+SAfom)IyFj5pRWApb|Y4 zM9P5|asB}qq<{E{SDcLV!%;X=wgJk9LfL@#F=*|rwkLT3ate^MDOd}UKfZxlUI4!v zf7h{raHF;5GW%keJPeNeyd~`1l86Q2{VjT&F8r`1k#Y?QJzHie4z`k&vqC7`Iz4jw z5a`D=7gBnAR)$w6`VoR9K z3MZDL_@+hy+{R-zd{``fuU`fLJM33_mYZLTflS;;+@ z5BvwU9S1LIll0U9c$x9lKhz|kopB+oY8jsJCtC#nl@#tsX~}?DsT|7gHbQx%-^DLf=(6jeVGrd*cMVS$jXXt^XTrpIz^Cda8$wj~F8)>XfnH3%-AglX^)h&u?S@NM zMkdcR--oslNdy5WDHc|n;M`$Va|Gz9t&R13I)}#KDfKozAKlmhwr6y)s+E9rWl#^t z1nc=~KD4ObX5l$oJ6L3UVdoKMZJUN?2|KrCCNe%EV&l5W+<{(}sx@zGYfnHLQxOuc z39fCqqp!j(B7y5u$mx5F9Gq-+aY?+8qK>sIz#=x_{p&!135<_kTzjMuAC$blK@4J; z`s@A(jKm*7T*q8oIpNFB!}cw=YX`ia`b_}B4+DFoM^s3knt5Pp z6nKpJy?-C9X@qY!l=HRo0qGF{p%Or7cgtaf2fT0jufQ@7mHz?%wETK-icdEykqN@B zZLkafvwkYs5XRoow!obpiBWcf08Y=8c3&- z)3%TUky3@%($hYrdyTpF@U~zaSa~ck0fz$-9 z_|i0p{oak>#s-zV{IJ9%$$LY?v?9h`fa28&=M`3d2666SACf{HT?!Wb3La=xKSxwd#ZZ^un+9qqKe#`CYOVv*FiTB_S>^TWhj+OT7RR1` zrV3(p*x=s?WL(T;8Kd|Jlh)ET~MM4D8`fSY1~P-8I*(=yfiJg({57r z^#N@VTWjH@Dax4M|M=m_9BIhw^$bmhltMR3TPS#UTB!CGVcJWjvtKy@mm}HKaBweh z9h9k0*ZObvQT}KYW}~bY3({C2g-oHU<|00Vqj)$_Wc@9UExqigiWTJ=HK3g??!_>d z&-;uv(D4WzFU`mI3*%qTNuM;N0Iy6H>@_H?-5?!Cku?PL$bfNlX zE9D*#etbEJ>KqWRzdVQf7$m;hS$M0ktM(%xpwo91hpgU(*g^;^gq^z*WsSk7k9Mt$ zTnQIe_`JD56IG3PuislJ7o4E8i(wT0?L?Us~ak2RY ze(Mq9S{KWs@pFY3VLZ+fiUlwkiTTnc_tfRc;Bqd6{~w+Bkm+XlY+}1c8K=8iVLQrq z{75!c^qo86*t5-wkMR58tF{8YGVFZ_wl;YenYXx(I7N@JcRugG1Hw(=q0FVg60^-R zxI_lD<6v;>@Qtjpu9K*3=2oJ9Ax8@R-XdZ3o=GuXEgyN<@Riq?A5msV7cwMt!F@nN z>z;VLMELg}EuJk5>`4TMEasKWl-mEvD`rR+C8ql#%uG113uF4lZeiXlrS=^hIghg0 zvCSOEm7HtxZMtc0`~p;ZX+9+GGX2eD>cQcAOcgzGrTXws{nG7J-wVU6KlXD=54Ont z5uUx~kaK>u+!HW5#Q5sHX4B2sYU;kJMGF(&ZaV6hMAom$FY2L-kUwJh-QtjQ)8Y}B z-5sK=`rTsFP0C(P6-+BK^~g2)M;XHy5`uzeVcHgsnI_yM)*~c z0B{lON7BAx#T_81)BB3!(am#U{dl{VWlTNcrZ)F>=nu+4VxwSvHPwFHu_a+~FO9JV z@RW1V34qOb#|`+QH9q?G-%Qv?i3F%~CZmN8ho%UAqzHd3X%6ti0)7}D)qe*^(;VVX z2f@)c#|Vz90Y^dbg55xV_D(kdN7L4v-flOqK1UTyF8VG3FvP8Mf9=tP(>{5>&KKU7 zWYPG-z1S!3tLPbhzt$J-NwrKRAPl7Xwg3q61cbs6KkM68O!?$D5#(ggEmnsBhDuLw zE9TC<@1a7pMQ`+)O4shg-JAJ%38^9O~!xUly-wee*KlNfo z@z-1#mvAP|`Do+O-U#Z6UaU~~!Uu1fW`N&~*94dvi^hx$;yBPehq>k4wJU0F=!&KI zx6{XasfgvU=i`D)Zk9XkwsAY%)m)4Faqbznkt=t9=%KXb+4zWJaO9Z!31b1AK zeYeg(l5!h#7k5)ckSGqFz;?K)id06f@KR>%X{+c5OE+M_k`iGc{IH@EBzB($RFg#8 z4&vqs=(`7+xdr*envN*7kY9My`5NaRJVtJK>mlspQpzM?+#5gGRpL;J0{TSADcyHt2xOl^`A* z4~21p-k&*=0X=rBVXSb8Veik1lw)z-k~&mDFSjO zlH;1@xfW=bYNoElmTWtBzT+o)yg}}V~07}ejdAQN<{d$O0 z`OHwHH5(>;K2*AD2y3HC{odI_lr|FLnM5!J(UXSzTMiFNU|g)3fX9B}u7UBL1?L*( zIj#yHH>B7fhaF)Z1RBl`%(Ku|jc7NKna~L{m2h2Dip(l24R2$$SWAfv6>np-x4osU zB%N?$MDKx1Z+oZ1N+9n@hqZJm+kD%5&kz;7_zvzBfbVKj*PXnX|IJImg)~rDE6jc^ zhWm7o&Itj-JVN1ZX<+F>+PPA?G2SAx#zO}`0-mv;m3XxH-TMIGStc|OgOLxe*l`8V zQG?ul+xz!`@ZoD&@%8*Bb7&{r^cc0tEI%hJ-^Ev(cYw`QCH(Q49*&Pjzn+dy36oz> zopcT)Kqe>)z6-}#uENa(1)$N1VtgPg!f`?{dCY^0Q@(~=vS6;S0vVtxJ1e~W`ZI7l zi0qBk*d{#t#(Gd0c;5H{e=4-S`A!;BCbNd}RDbu9Xt;lZTrxQ94hOt5$S2Ft1++fz zg_FXLec50aY}vQHw4ix3pgon6@$>mz<^<=tC%1t+0@h`uwfAj8p<2dIO~8JNdM&6N zn=9#N$(@P}#-#y<{gr^G@rH$nw@4@Kc{R5<`G$(N0MFITx|p;rmty^Wk|R#EbJ0`{2rDD-o~_ zBp>v4K3W;q)oo}q&hSI@Be+zm*+V- z=brPP<-X@V=e*mwhuzdSZtCbo3fqNl%IHX`NGZLTbUGy_K`+wOZcAM|(jy%bUmJ?A zNcjJij44CnvwkGT4kB^34~Z)W+xshDZtq|9a;4Z~I49Rn)Qgz<6ykI8uHVwTCjJhC z#8X2^R6xDYhERLaXq3h}FiK+}AcWGsd3djGX{9pE88jxE0j?^I zI$BdgCa95~dF#$2xDijw^`LfSrWVK(cObplj4CNwl}ce;$F?KHp}Crtj9G}o`twlB zDq{K!#Ay|u%B=2;tZ^`g3Mfd6HCshZsEDgLBWLFmU_t`~_>630kob%olx_yj%U#e2 zsvc>m3*f$k^6wx%5Apf@XlSh`E!KKQ?t#2(karE@pCSGkVi95y;vXUY5#oXTq%-iR zX&ZS1HKnVNC z=1u+4b*Gvb&h!xy?>;f72~YjSgR*{g0sXF4l>-GAV8e9}%DL)-H(E`Fa(XFNr;!DQ^e_dmwBmALnqX?;a(-W0 zH6?engw2lNjrQ=?BtFxI>yda%&a~qOByJF%Qt7yn1)2|wk`QA)v{DDH)Br8j<E0>+h9ib2z2J1s`hi;`$>fniBrBPx`c@NE{qn?PvGVE&RTMQ1M1buuh1 z2wd_!99vF%ZC3i$GOI;q5(R+PR3N>kESyWQA@QgW=|`2(91;)tpcVaDIcbJLbXcuo zkM$EsixUjwrI&ulwmH8?J+LRR=ttBO!JxEDYQ(+|A-2V7!0)Z#89pdg3ZvEI@ibwE zIyqwG?Xq*u$r&?*zZu4;-`C+%B<2s+AKRjSh|+7q5X(VeTd;V@k6{Rmj5)RiiAW~@ z4!>Y3-Dq{k*WezM<#*SV5S-vrEG|BY+SL&hkTT4dj^(jPon*u@ZPRCA!}QtP^^CVh zX{_1Uf^-~=>9wF>j?g;X!;{N6{w^CW{?ngVf#0?Bd3Pt-D1)&Ei)!Dc>j=|g_aI}) zv*p>bvG|h7?nJaG4rWzoA&0SXrTZL6Wc>&1DW%=^hiq89e<%^&$LmXg{{+Za=o6km z`qYX98x5@@u|rmhuMQ_wgf}5^(w+W9NT|fW_!B}I&L9?F9mL`@euemw%ox>R)*puG8V@R(UGyrgZmJxjuf&Y6LOQ|5Ib=*V!uiv$VX{GX=zYVVZQy0Wtk4` zVqi2EWR9nfk~P%22eAXflaZ;4+);>Sgx!(j@dLu?NCTyg60SzxrBp|e86fi`m`5q; z?SUwvY}6|JzR)@<6@M*U7?m0Iww%E$kJhwt{7-fyJ|#p)EuZ)5Ad_-uH{^@75{X^# z6w&=c(_DTkp8?bHzK=;!Kq+hyP!fCbz9y1>dr;RiiJudKI1l+ZE*@Hmj9yo6C}*bd zRaEl0y)u*19jf`>V(9qviZ^1&=a{-NEJ;fQna%;b>|P&WX04XvgVzYNmOftUF5g z)s8ylMNt#of0L0p*!+|2uh1fa$Bnm}Uz1JTLZ0Tvt)XC-|HGOy*A-K*Y%_?}4m#G# zc#Ehj8u$i0V80#7BKgqnK_=JQVyAy5HrglCx2S7e^%6PuuaGVdi34k36uiABCm& zCIlfZI>xbu-_5Idls1|#)|p#}u&K`Ss~dB&2LpA` z;&oZ}oPoDyc%)}rer%>Ibi5X*@sOVbdV5JGWttYPj)5nSurDS#^J0ME>tW>`^D9!A zi$F`_=|Bcw)5dty&~ckm{KCiaD4iDD1W(M&{CD7q7F!9;iS>a#4-y+rA@R?rfNQrs}dD~_7l=z~bCk*!IX*SK&!eUKJs2utD&_?ECaZd&B# zAk)L~X?CxN61NE7#${6FK|zyhihl)GbwLpIL63s3~Yvla>}!F?3k(M z(%a3HxFhg9`6jEYztL^xkMltb(m9%r~Sx) z_b7D~q)+*Uoe9sREcP)5;4Jv+O-L;CjSRA&O$E}!O~2$3dd6vK1XEX>m=i$_F*YC% zn0if{P^BCr>`I)4R|?-J=B8%&6ntqD^4e6{PiFAi$+|RpqG}DjvAnqoeq4ncd4=SS5}|Bim15>r}o9Q1yX;lgCEg7)BYtxUYJq@(W-g zUJ}M9Pj>VSEBMW=DBI=Y_%N>q!82ugc`UwDvy1oCggzj)5K{@NeC5qPF>Bq05- z{hAF=e7Ft9vY}s7#{rGU`B5Xoj}TH-6KP2W$G~;pa@%VA0oyVA726x0D!{<3!MHMp z?`R^eK`WLmBh74qW{|gv;`q4yZ?7W*C4S>Wd&0_gS#aZkd!$)X1qo28Zlq2fq*(s6 zke4zob+SLreiIgJB=A<|rhqgMOj{AxWLS5|Lc0Ufu<&Ba*vL10J*}G35sKL@G^Hd* zZuJp#!lH(OxrFYNJX|hBrRL&Sgu>La_$fZb*=)ZPhL%sXU-vNZs+@2jHCLze`8>yg z(@<1U4o%BEd6I^KiOlvPILOEZ9T#q;E{e)#=9RG<^n;uLu<=OccWi{|8 zn}+g$zhJYyZU$J&H8AB)q0snLbkVU`eiBQy5=Av#*f&CZ>o zEZ=BG90)era3aza^t2&0sh2lI>RH!st?O2PwHAvs#+`6PwFjja+d=kf$ev&Ny!O_* zubPyZ`Yt%ZeAt_5b~jH2TZPLPFGA#WgK(_JV&owP@5*N|yE-Irt!)KkB z*@A9WMCW;#S)kyGLDEkbvEmH0j>SP4;sv*xL#HiQ(?(jaX{lJR;3N3Os)+N#-%M%A zc3_3B)WzJrC?&c`zrM-e@12V)tn~}6y{E0=LR79v0aKs}7v3|a2y09Q4n>6$lrkD4 zNase2$beLfjPSmpp=%Lq(-;)xu}c&c(JQ`E;!Zrx=cc(~>6ufcb8{q(%p!*r<;n`p zlIRs%{tIHosgX7aOhF61g5e{1Ym;?-HxM{l@5DjrhoE6aVr*+cTTuEoIOxgb$$tOs z@IdIy6P8Yh8B^0@UC;3UQcmxr*WXpP7%yIs%;a|pRjFfyp7GdLYGu4Q7rv^inh-$5rBE(EXo-gdKp{Y6JW`l4o}U zj;#Y|^=A;1bfU`Nsb3$)jV-&~JQvSfU>HCkW7k{fRSiq$e1`Qg<&4X zq^5p-C-gwUxr6mv&7>#N>t~P`l;(%{q>l()06DXSqydR!Nw5|0C$=cor&d0O`xXMT zZQXh7^Sb#d`9;V5w+Hz3u~s6sS$oe|@r1E=v+dU2qSbwKiq|vi6(X%zhH=h;g{(UU zUV>d9R87pPq`ni|aN6HJb7anpO-Z&}9u4X5w>~w%P1;OB=~$4_SFc;zuZpc+Gs0GV z{4vr;!#vz*ms>`yPyuB<*c!gxB)mIu>f%EmRj+?PVO9V0u_&kdPhpp?)E%;@zSFw% zp6*uBoz?5DqM5G#lWu){ML9mZpf71>b93K;sIZG;%CX_BoX>7E)3BWL3%>9q^L?JY zEm?dnFi`PDLFpc0s>v|sa98#EMap;2fA|}Qw4u=oeC{I0@}PF$(l)KH4M~L8$^aS zY@iH=CxX(HAv5d+s?wn3hoem_2}+0H$R?h~N-2o8kX&L>f^> zNYpAitw6%DghZ1E2`u8Q10#e;A>8lpWM^4V^JkU#JP5qP#Jm}f=%Eok9BfNc zXHfP4W(%$B7&wMRnlqZk4Ni1x=aZ{M9+Ok>(P5Heyfze+{xG}?5VETOQ+gA`y8vAy z>8DNb(l9HDio{6kfO(!_L-lj9qAg0{V!Wea@dTxE|J0u2^4OZ=a=b%xTu$Vod@lrc z$zwX$<}uA5c_X66bw%A|*#&a8h}t8kAodFg$q-WS7>U~;#swom4e@vgZ%rNv=>W&A z<5f&2l|{Kzl&Ev;F~d5d_B5<9tm{^d>D(o+HD&PIVRKouK-fDut|BA&J3vtSWC$7F zlpi#~)YQ^qDvga0M2+DE{ ztUWT)b_}#VW2$?k>8V}+=Z3!tob@a|g(uQ(UeqYZt@+wRO*FW_ZVo>s+?b-rp9s-+ z=p4DwcJ7h>s~44yft({%y-M0Kka@&0apvuDN2=Em1t(>kIlvv!mw*2p2mqjj4OClu zaV*i=rc~&+#+ubl)`1PH4I3PuZfGO?$hTK@>nfpD<&l5EGkxU2UIc9hKfo~lp$|U3 zs$Vw;N~I4-j{}YmM!FO~_?>71gDAr>@bd?{t-)qhd6+r1$udAaq2KVsRZz`8;q&~y z&-uk*P=Wx2T)Fw^W%+1xw;X5gmbDyM6Y_u{R~yW6W`lUW+Az>#Fbq7mnh@*PavX?p zhn(qjR42gN9o?{fr{`eJ$olfeW&#;gi?U-bZY#&S?X$^lmBIhMTT$Y1-!(heMA_%A2y4pZ>q~Ts zu+EKTUxs$D#1*uosR5Lx4q(vt`hHL@?0lvo`4NQ}rEc{qqvn367!YHcZ=s2x`>1Wc zWrlb!#LkJu?$7$eMx&fU*JZh*HffyFuYUd?a{l9JqFH>j_RsS4eJ4SMW)_#${zEoB z{wz$RNNZrAi)zg|hj^7Y869k|6wTqOKF2mM-Vu~;``+pchqeBr@6WKtDSZL|NdE@< zc}PDSIzpaZgLl6pKd6CYWjM(|`_*-1yIch@WV5WQNU|VtMQu>JIP{yG{c@KIcWUg> zw#6(rX@Lig=V$k;3Og+omAxhL3uT&v$ts|FX$Pwnaa1bkB&L;*g)O{Hrc5i>Szrl? zw9Odn?v(R&i%z`)oh*gUHbYF(u_A*Np!@lYZzV8ps@Rolv?3KnyC_3eIcY&FvQgo# zm7(|MjFg*fY4;7Y27RdXPpry|Rey17Jac%50XFD&Wzr~DM&5ZJtV+@ioEN^YJR|h) zawl=fA0{gLP}oHnP}r?kpPAIUM^>1~pteHX?jfrg=`xCNeNd{ENf~Y+_#p~20uhvM z4IcJfQlZWfocwr|CH%4j&I57|kTU^koM-^fh0F4nwV;z!UzX48JLt73aATM1vCfs{ zmAz$&XJt(RoVRwYUo3~!P(Jm|Nfv6SwjGWKI@LTDD4Z4wTvX#jzAZPCbmMwy>U*i%&|6W&7n1Ss;ExZK$`ah7gz{y9h4^eHKCjW<)}`&v7(h~ zB>7}e1z_IF2hC23!|x1%;6|c}WW7o3VipU}yBA&^LH)VV@WTCn_mBqvXYiA&1zQ4j z)9h0cv_&6S4z^F=Q+?0Ng`u*8i9zZ4!Kqv7ir$e~=Z9Ch^116MQKU4m@f`hNgb5~Q zPGmfIHGVd$Q+P)s7{jxJuMCbhAtT$}A}5-RO)J-7Jz<+xu6gC^%5{`p_8edwx6ZvE zUJm=;RKq|Jj(HVL7$VpMr;_y!=kRL6o1C))6EM#@&@u0v?c`7Y-=ki*b2_Ka2;h(r zmaU!_#ngwA^sBL zFT*PboHk%*fXRu2kPjgVf;J;4^@2UIOJ2Fou?(hr$zyGoG|jzTdn| zbTF!{jdH2^(Y34kF_avT%WJNn$h`87&+8;z2^u-a$Iluj(Sx&=4vk%xDSL|f6uh?h+`KRBo z0vT~Po*}snD?;4Hl6x!enWbNG7B;*Q5elUbNuT-;tc)WJTHb+bB)%sb?2|aF*g+d? zS3qD#^9Vb41uTBAf!v241Y>RinFs@r4m=l-XRAmPb8ms!aT6P=mxB08A6QzJ2V!C_ z`Da7_5utxg=szy>uZ5i}N(OyY5anDzNwA3SbTCQ=xwNt*fD-;RGr=*oBCd4L5<+T=YztQ;lALuhES*zgE-8Jbc>dZF5k1HR=>v zzJMBW9ujVPz|@|H1;J)c!V$uA=83pQc;Eb#wx(siR?Alo><6k#=6_6}Z|(onkTi8z zm|mDaeRpf{XHCT&po3QMvzqX`Fja%N0cD(T2ZKCEv}%kv!;dl|zzD{O_xn%=Og(oK z6!!sHI9#YredT0L2~m3y-9KxO06pkv*^;E_qhjE&7=7s2mBLh9FcrA9$u5<5tRh{E zQXH{N>>~QGoM6i>XVj##WbywosO&?UO)G|)^!5Yx_bi#`ey|HRVY+qP?8(7uI~(!~ zD3Y1!q+%Kh8R@%0mi<}LSQ}=()pQ=&p~yL#5Hmz zkM|Jc${z+5panqUR^{ffkT5Un8Iq;tmO@I;AKrKexEi3pd z_6AD~h&HU!1g)$M(kZHoK`BXiuEc`Dm6`G~coM9X*@CF7aM zI0!a(n%A`KYzix4K?jXZ^`Lo1dX7)1QTJ$MJd2ib1p-~3IRO{Ig!7O$4H^CJ+a8)v z;Bj8`T9oN?YZ7WoG%ZvS!&ju#TUb}Dj8l<}6H%t*j!76&N!!8h21bZG%kEkd_an!Um&_NLKS@ zX4)yst#j7m{<94wUQb69O6veGCK3>=`3~ViS+WDH!s9N2(2{#D?ih_#%F0_N=axUSrfuZYnZd1(KTu+a65GE^&>B+WT(%WTYNDw2H0bwDM+msi^PYD(yzfgF zPI{|h3J%tWiI?elAT@kd`!)Ys#bTLhYz4fq?Ynt`g;GAQy%5gsU@ol1At&GP{Ymd1 zq8tP3kA(5ic~O*3?NzCxGTDQfqAEP2JxX`#XDS?tll`yBX`p&mQ#i}w+OM*ncf^TI zR0JRusVhZJ9VFOLN=;PHxx_Ikd7f4h%WtNU1`7ASp1>vSGvo5d3w?kc*# zQ`wDYu2zaU>Q6kCqEX%MiD=@ce${NWlWu28J6C^s%e~ghN{Rusy4{ceTQR^T1Mp+3pmhdZ?K>nMupfe&kxGdcAR(B1F!Gk z8KJ&}0oSrDJ2Kt|ETr=PI~EL}G;ZaY9*(N16pbR|!Nm*CusFtDe;^dkDb zJ~hRF2O)uFcJHy=(as*K6iw_otspC$tCO}A)36GYF8&CdeXBP((?Po@gqoyZ|7&r$ z`!zY;G}*{?DIt{xLWBlrq*Baf@f4$-F#HWAg&qWV!o_pv0>f?_9WxS>R` z2T!73{}|phm%ZYNdke7<5Ht`_M=%KOYclxU%#?Q0zCqMD=ocYDDiTy0?K3V>Q$Rtd z9vRe^#YVgCV%z|Fh)iKzd$Df0uAziX6Vsg=8sY_IPUl~}C@e=eGRY?0Nv}F8{kxGT z28JExHR1gpyoXR!d2wC4+FL*o0cBUaN%u&R1Ej0Ly7m}3HmRZH3r`QI+3=LlJ*0aI z2=KJWs5|Syx$k+y!oF&Dd%lKMg4swfr-n5&?M0b0=~YpkK#a_+;z&1NbnGgg`8!#c z6u;T0Qr_uj>>&e+2Z9A1!NhAWJo73n+htLVV}PrsU;|kZwbp&?7PqR}O_mxg zGxgW}1)0$-1~~wBfrThDQ`D%H7tNM3cv{j|h*M$U@vwN6E`mAQUDb=h0{w}TJsf7x z!{I!6kV*WpnLyxONIc=p6meKlaVl(l&YQ=bMK?7RYvcQ$u4-}0o1W0){Qs&7*WTZ$02D1t32+r=Knj|hLS8tWjO#kQfdKa~NJ;{gNM z1!ykQ7{2pd0b@zoKu1~S0JFL?G>hpvLK!1R8IbKytl=w95pVGr_`mY^!T&v;gaKzI zb^|NhL*;chKjbOAsiYEmsi>I)i;na|8)Vxf+nc&i2?rV+s*dj8HxGh-J?wxZ>zp*C zapNhc`F+Ki-yQ5@(B9$`z|Sg+W}U)~c||GwnxFRaGoVBCkkU&jjrO?q1-iAN1^pxG zmQLuUqb|D=K&7Je;!wF!$LXNmhqUcEx?UIz>B&L1i-wYKJk=?q-pk-wQe@$d21lqL*P6gzP0w3_ z-+Fpbopqd_7J^cLXPWe8u|mei)qO1eGqB4bQ*0z#86fuBjd>AcKo7w zmb;;XZa)tVo9RYAdg$nllJMn4cp5wP7;LsbyAOB-ah_Iv4R%uw!d@YIek#@rx$||i z4WMfkFM`1Z?3&=zQlx3wYKi4(SJGNM31!P}ZGxta%$XBrYYcB`4M;)4mFKGsw2e5% z$QzsGB2%MEc|IWB6!y&@s~Z|-Qm$RR>CwR2I5tRJeeMSPNaRIQi^wit3K!<*;zL6C zJ-XPxK*_+xZ($wW$?NzUJMm(gc~9!NT3`Q)ilY7{H$ptS33}ZcBt1eKCQX}lMSm06 z+XjVA_hg6NKiK0TTKENn!pVE?Ts#vz)d-Xp$i2^FSuv^UXlQ&?C)Nd}q7$L_%*1Xa zE;)rm@##}FB}6jX7;-;AVi0`H3RTMt)+~l>pA|s zwb-a|6QgL`wHgpzPMji&mCt}T*0e;=GJs%^>{@D%s@P+RzYtZ?Xs5lXn!bhd_E@6N zGGh23BmPqkI;1CqjQG9Gh;M8TuerY0ykt^^b*9XI7#0@M$35jb_#+EbVebn`~-R6 zOS6()2b^kY0j9+~y*zepZ0k&z|Ja(sn=v${QyxU)-$j7k0;&XQvUhHvU2+;t=sunp54vMM z`By^ly8t5N-w^MFAe{6IA&5;Oh>cF=yK#Vm#Gry_bc%Wf(5Nt+$txX@c$riH1^B8^ zg-4;nN*AY}Q8qSRc`zWI2tb8{idR6*PAUNWQz3Y?`o61VC1! zJaeG_10d&ELe3+^JahQtpGKB!%COk9Iw{gk$X$7m(v6f)9A3tS*ptej^g923mOerxEVv8=x)|P#0lF9(Ydi8G;zj zl8UHVD1&X+!a(=?BFi`%Eq>sOs6b6xa-vNNpKaA??O8TTTneYLqC3OJ*@;FgAn8sP zw8epb^hco3SS)G1!r+zVwn;KRt_$v1;?~yF8)*B`Rt#X^qlG(Il;YMTSTfQ3scfD3tX$&$$ZgXGE_^&Pi@64wa+CCNBd zh+k^NQ-$KCI@MjiQb0kv@YvFLJVAJ2X&#OfPA#3B<^ZJMb}K+LR0ZXS;r>KIci&nX zG~wHhk(}#;*FC~ZkB$+ts=rKJJGc*Co~Vi8_$)zQjwM$o%%O%OmrWW~iE{oaqx$TN zB&$N0y)2%RWx>8|0()|Bn*BhZnigJPR$3j9VD|-|62_Yi?uKwZCzRHLyI}xa6AO68 zo1}~evycQ&CZ42j21j600Osc)(iK4aEkj6Wg1BkO05W;yK=%_=8K~+Cv6$SxNhn*M zira)0@c;g?Ez1>@*J zNL>h}vLSUo$aqr_))D3ei{G}_v}^=z`~52zuNG9PSgZ~jfFDv`0EKA{d43$+B7q;$ z9azcnIw8_NZ-RA2EF8U*E39aT1vn^RRyTs)gSiyGmNwF^1PD0S>j{H=6$GK)J_XMc zzOX-wUlyz@il_cCOoUyftB~Id)DjP8MNm=(L$_IKgFl0hEAeY>qV2$F5odH;_NZ!fomRH!#x>s#>X!i;L zKc0=(3BNo(n|doCOn)MSst*W%cw!v&nqPS7iAgELD-iqBYT#;~MC=`a{LwrMYTXq) zG9dBFknpc3Cg3ANCB6er}R+#Y9xyo}rP_zNCg=47{OLLO;_tG5W;lSz&f zF2psIv_MhPZ;fl+j7T$GvfWfCFEE4V)rGlVpgiKYau#Ac@UM+7iu)cg%b|zi|3S12 zj^prJ^QtoYr*&UDX?x-dE!=G&Yn|c2qr46ooWz}d;}ailfTxWiKlF7Dbt&(YJi%S^ z1JL9=*DiT6#FcKwyDRLxysIjw6;v&99aI23zwn6NxJ6?hyG2`cd=S{Kgex!Ny!PhC zW&v#AF#mepOMh-wH*d3O-TIeeAXn)II1L8l0G>*0FJqbr)j#U{izTtEitG`CjuEHK z1Hmsnf3f^{;p&STnd-okmaLr8jAdm2Vd!VoaSlRclFyB>4VOuTNb#m_qh{pE5+`% zOmH4MRcarMQ7duRSjGrRK&#Z{{u>21(ywx=y9G0SFKpv zae1jpaPE?qnS{qhxI&7=i}17nO0EOJZ;}^+y|KU?lvaKuy!pp_>G%CD!tft;a2F(X zRlJ590y~3&pNa*-oHJ{w|yw4c~>#zLXF2P30+IJ@87O&j%nUu zVch#y!tF~3zw?p$k`YQ+Efam)7HH)2*4JdlM6Q*N=tkb&zWa@^Nm(^gYL zM9i0urs-91Mk)>>-JrDCUnx>7W2h8q@bScI>&*q+x3b2m6u!OAzWeRs{tjhS_L}Lg zcFNF@L>oGqt82I#<()mWf#E7@)CRU@Tg{g>HEoL7mpp`lQ_Q|V4ia<=Mym$X-3DU5 zgPIUvtOg2QQx%%nc)b2V^GE0 zo8DUM1c!>$p%OVA)wJRn2iCr3QCuv5w^9tP633vhp8KF=ND2rupH9AKpiPD&Z}VC_ zLv_|>ACf$<8i{j(PkN~J2&x%ZZSPuWD$?AA#1!8cuLkTKBxguE=l==ToLqTH&e&VW zkL8m=sR)B`-FioYd}(Yg_t0jY_C5(SI(=jM*0gE;guMd++nl$($Xsy64GzfQYfq5O0 zp8BtgT}WI6R%(z3#P0$Mz8WmbjN7mUOsjc@+5))I3#uTHe^eKTr2B`EoyoZ6+Mdzx zGFwmv+`cp{w;5{tJaxdE5RKKTKv*fg1t%LLz~_Yqhp}Lu)rLfHCkh#%S#Z0!^CLlg zmc#D|(d+I2zO`)KeN?4S*uQQAzAmIc_dg24j+Y9jpG(Ch!uQWTfQ`b;^*Rdsg{AA) z;TGZY`a8l7`;-m#rXfi)C~yu-@(tMogrH!^Wzo^h4<2G3fBtABCU{YL_G~0VSee`W%?Hnzp^bVHjsa?Y8?J9q6SSA`yF^XdL9VHSL9fAXhCKx<2m?98g$!^R*fh1L3?TLlYnoPx z5em2wI^iArluNUqpD=K{`0|*_n+-w%65kqBq|g^R82ydFzdZkxwYl`MBwH2urE3d; z00v<{9+D>e;07#BZZ7}9R=vcq^i8>_{>*iyA;Pc;yedeyaW0e&-I_rZBRcdKzL4Vz zzw^vWWBkfBru@q=5v<|}{D&(Jdy2vLUW5&VY@Nw)H#-RA&!oh3)9>Nk1u*DILrjXg zo9KcrZqbVl@?8-47|C^J`9;8b53DE!V2rr3fXf6_1Ys23VcX8R=x|^ABX$8G1%Uh@)C!RtzHACo(q`fD zO|i+Zg_g3$jKrc7cv>P@O%K$Hmx#Ck+67_XCPRvDXs<=ped#)7skYB;nr8$5j_W8- z*}yjWC1XJNVN;cg`WV!f;={t!%`>Cl8pa0Dzrr0kC0t@1lwK3IY|ef7y&y7xXYNzr zC7*sPbbVQDiJgtO*jd!LEIU2kU{7o{*s5(}Ta3NANsu)i(d)Js%NOR@K_TDq>2;)= z+KRb(wlPl`ZK+Qs@YSG-54X*;r935j=GlY)Lha=4+X+GUycNGFEPvjCHw!;KKN%=A z@rCM$S>SID*Ho4bO6s7n^@WTv^8^36@L2sqMlMbN#yC{r932BnEGDYCR(m{ymEZwRaECgWd(x9aYjQ3z!GOY`0)$`MgP zE)4o56uJ`($3H&_P|+!Wzm43{rZExHWob(rxhbz4g}n0m91V)pehc(?5rx1x-Ym&te7Hu6CL1l*fAqt+a{ zN*xJ$aBI^ZJ4(lQ?y(u{u}zI2^Px**oAgUFhhes$wALP0w8v((7u!0(8r|aHsNMi>K->TiZJl5N9qz;$`96t+~-vz-k14o?4M}y}v{S>iL~Q z)V6qs5^k*wN;d{gX2N~r`n^r~pe+4y7=yB2mbAmkO;)?nw$Z-QrhHnK@`nk34$^dJ zWrC=_jF_48To-|(f_1GLNCHU`_U3&8TkSvaLjAVOJSj0 zg2P>@8+1tNL!~f)DZX9u{TgIQ%{;Iyx~l-*IA++{1bH@;^O@_)V@8|dk1K5*9wkic zpcFntcI7ao2>-P5mk@2wv_v8F*FDqB5MS6zu5uz#2j1B%SR^zpENEVP(vV(NR=p&O z+rLDX@&;9gC@#~mgseMBI{I;Nt_t1SMwohrFV=Ev*`~u5cH;Q+s0}(paIzz<^{LUlK=|pUg?O1T^W~iM*~2RE+0eilif8b2jG~wNTX@M|p=X0RaY2BHrdgcV%;+K{P*LUg?|8N57%{NC!gHi8<*z$sX z^HE}L8)HWk?-A04i8x!hN0@Ve==MJxF_TVA0|(x}yB5R$H!l31`DVl%4qQ}FhO4`6 zFv67Q{DvH<=qt~t<4?7y-pB9WBQq<}D*?EN%cLl~;bI$)8{lC2jluIvQ)M9_+?!bg zyfE9MfX~T*jvHL3FZ+mJqa-bai_w!elXXP)c)zqzcy8An6EC;E?`0z%yUzR#WvaW8 zF`*lYkI9#0rUy4q~1(X90fWjAlPIU}AHzh2A?lAW{k8*lk0C)E#57ip{7a2avGK)K%`}!g< z47db_8o=YY2w(~NRsPs$b1yC&<)_6u3kyTWnD|mrXY0T)^|jN=t6{hRDXRRM=%QX+ zG|G}6;C!k9>{Iq9 zSqBNm$`GWR{Da_0O@^ZOYePd|{i9$AluvmxJTwf}8@$sg);a3{6`P$0y%f8oXk;*h zqIzU7g~&fD@DdEhLBqX1oE&?CFx-xUURAyu=O|^H-cA~WV*{trda2r`*)bJ^>>^d8^OYq@Ca+K(h6PQ ze%-?Or~$x*15gj$7fd|+x+Mp?uP$m#+yb*K-B$U>L$ZDf%jb??rrpX998j@+kQ$SGBx+wW9dlv#os;yR0u_6fQX6;rU)r-0Xr4&h2sW z&w8k7ONu6WOuX7dh{R#>fY!C0D0MY0YEC^%mfjeGU8y>e10UdgS!x(cFhd@a>-8B&jyYe`^o{ z{8soMDSsLq!=oH<_ltbaj(o6hm)#+U{^`G(+=ZwKe<2Q=^ulEuG2f2SXC zhH_x&Fc9*oH1g3fWFwL(XfJFd9cWLI6L~*qHb_Ze@INIoNF&WB$@jV(aG@izrX(t3 zS9|3E7|sC?)|633!al3JbfD2AXEhQho%~{M9K^ zp9J`97ihc*W|0QnZ>SJk66_4GulS@tTp1IQTDQRdu_gH#qw9@=EgxGHZp=lbEBq*L zfj#+|!kaX`$HKWRH!;L15R>O5S7GRxZC{kWG$oub62|T+b^zs6p<6F&Try}UNT&rj zgYH5)TncO_xLqWMGiW3ahw>c%mB+S(btwRD<&YE3WP&kpiG=6JPO)vIp6fcAw6UM9 z)070@IPK9B^whw0l)4%Dv#kR)a5JaQF=J9i9(8rN0knR=jGlxKSF({c?C5oY>jRZ^ISOv{EF7fwsl~vC^*x zE95A5x)`K%;G&^+{{q%aWf!3{G_Kfs*iz7*&8xX8S&9UWqpkHp*k?W&CQZIE99f|$ z&xRF|0L?ZGV_i(CU%F$M(nUj@N2FemYlnvY(tE=)*c$8d@wn5VazSRa0QCs3H>NnA zfKz4@1O`5(vA{}*gcBX+1xv_mb^$$8DT)e3X+%4#!|+iXhKjc_y4%v4Hd3bPK|RDC zgiCKrD`B0GXQanErj%{DEiD};ts(uMCG2ly)Nio&{2P{nFWo@p*+Su~qxm0)=o~fh zkqAY!r-9)M>E_Alrg*EOA|BqZ6L`&nHe!|Zdkzyd5xfHiiynN{$BlGB=>kafk~B^h zUVSwyp5k}gYc1+7d<#X_S`-%)rM31Q@TEND{F55N^@$7@ewhj8n)$MOBb!>>P$ z)x!6$e~V8DN8We~?soU+6cuhcB8P%cW5&W~Eh1)+&jtnn^$hYUGW0>f;jeAN+P&F$ zj_}srZMkvf1uY!h@||N>*mqkJT<%A#!shVKTYql&|ZoLZx&(6 zzA@M!tlf8F?)&lJSOU)PB&L6hl^CHN@T`Jo62mu8(2Ed<{Z_7qX96Go+jGQkabzey zwqbt)cAU-vv!@ZUlOc{L=}h<{UOhJYdc2INITJQ~96-@+?7pv0Si*clL7Ak2oa z5CSxdilJ<`39*gv{0aoPfWfYU=VZ8mea~adA46d0CUE382_Yfz&0&UEzK?0&(qL`X zf_%%YKjluyojk$x@TAGPlPBjc&0C(2gp9Y-a)S@Tt3Nc-4XLjBE&bRMXx@(4C>sp5 zdZhfT<%lg5o_l+2dD)|gePJaG6c76#&e;M^E*Aw;J& za7qGXdMT7P1j>Q<;#rgLEi*HGT*1Hr!XTl`P+GNEU$q$MvAazS9F>j0RYnaE`Taol z?8&anqghY9{a?>GdE;`~$p@D6Og^_<2-v@WxZIu5WU}T8W#G{{zANN;Cj!&EJxl)c!DiCIWIE!?kUq{vEc!DeZEb&2!>1cvz=yf^_mR@IWf_+{Y-i_-}2I|@C#PulC+(Vq@ zWwT46)85Joqoii75)Yk6z;kDXRWh>?f24bz6%lp{TqTq-LmBd)G_jj)1!ZYd>z0_y z5-QAPbrsAll$)@0M%jfW38F1OGWN%Dt$+Js)DLq=d%qvO&RK zvn5oH>u=914Hs)5&V|?_F-*8UCzQgFf|ej>oXucJuxCR(gQQ|C63fuKjFiu4GyLwf z()1EK2=hE^FPazOu#ceydpj+Fhq<&Mr0?K_fd=5c>@SU5dWKiO-@xfipCHM0ytDyN{?&sres@`W zooke3F?MY1@}O*w%Lva5Jpbe|eNtHrfRvCrWm1x|lun>?O@tlkIa|E*Oyg!~Fz7o( z3;av@@eHL60T!So5#~5A=07`ywlN!4|A=2v=cK0aS&>4f7}1<0q}y=~l6vHH5!WJV z3i-QAucNj1-}={+M#*gbTt1vb+o}W{(l#bQ8-(XSa*VQ-OF`49QcY8$$ig03n8bSX zjf?Z@Q2}hf9hQJQ&K6gyof&U0mz+8Ai}m)si|66kGS+LivbUC6EwEh)lo}2I4=;_- zCD@U)(vJ-4QdWl~(QkyEP;W|;L^GB4?$-_usZ}Uks{snbL zawzr1FvKr_5Yyx|;zP>?P6+zukX>OhWJA~pJRMS_RAIJ65dztj8aMm{JzIjL{Jtz` zBMrjNW9P#jVdl3%6D|mR6P8v7Fu=pfSjRUZ3CZ+-a-gypmtbl63Dg=E$snWy)aZEu zOPUj$w6kT}Ol+JsYo~$pRw^?qH#Z@@PGBW@far#49a9D;mgVL6-jNfQi>i-vPCo?X~L91A|zB&W`9EH#ik&Z z4)tNFI-rm`WzHB@LaQVN6rrkZLDJQ$@JX^)or15BW_7x{O->V(M=M)&!W9uo>xoyr zY~CAvT=J9-crUR^Bwc`~$c`5p<_eRAG?B?b8?V^Eg%)Y~pLX1Cd|ftaU~kkLqzVR0 zEFQDAVsW??JL*e?N7o)${L^O6TgV`3Gr+q=PO8Du5`WP5)nFW~Hdgwqk24sa4*Gr= zED=~bnwRlJZ2G_xBSw`jLNRt^h!6pA#CD%q)7V|1<~kVZi{RJL{T|P3*?@3vgvfe> zcb^iYx>&YIHlnK@)Or;5oZ~I{I}D)>!UP*d4@w`=S}oKHDgmX&3I&4JP-$YNs{ym{ zf?RE8rSkzHY1YXsftipmD7&{{EbZ!33gul}!cbbF3w4Kuzvtz{jtSiKHW}?R1NdzL zPG~4B5b%WA@bpUH-oo=miEgATles04C&bg@{q~_znQ!9w`(!xu(_AiAdOLtk&#q7w zzF`@88cuG0#em1qusYo>kI9)DHg< z=(NX3E=7;R^GP7uI>XhEP1Tm)-B>4kFsv6A_!Zgn1q_`Nkb!UdrIEGi1ud-4_X9du zfps#?(==)I96a@q=VC^s-yGzG8rX}+0*Ykr0<13S{9u|;*}{2K(MNWrG!<&1(X4ci zoQjz-ED@eq=`3A^(m|pgk;3mhaShspeRJ0cOJ)UZv7qm8kY=wOM7n&~Y;;=aY{*S< zLcC2WL<*zCpwB`Mj3~f4kC&=EB*|7(L_J&MRC;Yr@g=l;f84oOlvx0PtoD=pxgSzH> zOBm@4nHZOeUnh&>jCt=5J`Z~brM0^?I!5}fAEg~|VI#Zddr#1JDv-WzA57DkfD-m) zmdh-b97EE-$=~9vF|!8^uxX&>V5t6>pzn1uOq-35ld0NSj605O*Jj~sa!q3n`dlaI8seK68`dR4?w-D(XQ!w$F;Xh| zGJZVHBDdma;0`h|Azj@(@N45%7`RTLiy@1wOi09^l5Gk47&3q-@Dn4lx?t-lD7>4q zNK3*f{4wcBm^ADz*kq;#Y(RQO8cR|VQ%stZsU{??K7ov?CPu(DSg!?2JG~#+WusD$ zbxLVcKQiJvrJjLwPCxlm;xoyQ`8gwS5kkclB+c>f*H%-Gj@$m&`h8$>?O-bO03u4ryU|W?z@eV}<+6 zQqr~_JuRc7Dxl^aGQW>IzeebHcLbktdPvrUzyAx+CCB_PT<; zUk6ayukNd!$-;cteisQ&p6Iwdpb)k;qb!$8Cxm-77?v*V-Jox8@b4aE7%KVwz^|Sg z&A;~y-{CYMhxN z`k6YmevhTsJ+%Cw(q@L>dZ<0l~sp3u8p~HZw zGB*tRt_D+=k7zJ%c;CXh2YtVjIVo{bANV_)H6?V>GSa&z$n1)^=#pO=8L8G!(GU9> zz`aQRnv%!N_mi`+Cj2H*=t^-RDc8l}apW;wj()t~?>P!AhQh`;G)?p5Tnz`{Oz|V5 z@o74LM@h48(XeOySjPgXQUk`;61_gI=;|N_T3TvR!J8%is~#o955q3{2~MdJnDZ_B z5&tfP(-4Lq0BI1oK-PZBtC`2%LdJ*?Z(B{C(~re7kG-uwiSbOb*f?qQOeo4XaZ*Kq zlNLjGBrwdT6}8QgP(4vx(~NW~>F=b)n1cUCE*axSPVU2dVH3fmPa7OY%QPq@Yaa`L`XXV|X`5+!z~_P!D8HpS z9r5Ii3>}%Dkvw*H@FRJyDM6`h|45!~N>noK^dy@TL^@4Nj1;B*-4$hwS#pE4Wawij z40ir0=zAofTNU&@7_hJ68-l+1q$guCwvp`2c{o6-G82vM1N;9(#qD7rjnMMvL*@Sk z<+Tkh*JMg7No!_o_Sr#X44aiCz!{%7x#8g?Q=TZiD2D+P@>PExFcEx~*UbSZSqam- zf#9sChfg>bBP_)u%C9UK$Hkugkc}qWva+Z0rL0%OU}L06%tmX3U24$_M&VzurceZL zMsiOuiRaCoO*OK%E#{u`u9!)>W z>%-T7v(D1R8mt>BGuNTS?LprctwG;Qt>nS%drMx>4sQ6SL78qi2Pc*vdvnb020Z$( z5b0O+#9Q8gvw2Kcl=7Fx!L@X6B^g&(4Gs1@ZK2eXBV6~ew|1`q24$iuo51r|(SD@kTQrC_n}@MT13Zy32}BVki0t3|uVV8;#Zaq; zOg4?ueit+@Pi)R_3HmyMeV%lIl1;~8Z|Jlj&zqtRRJc+!10SWsQW#J?ZG#rhDJ;4B zfzr1GZ&Wss%Ew1K*bNtyQSITd^Ey=F?P2#QbQ8ovPynP#n9H+csY#w-A3Bj>KtN6? zI_PkeHdPsDGrV@oY5Cd|=Jqv%RpLN9KvAZFsn#OiE;T7O>dIH*?ggxbtSBST^;Pw~ z$rB1c3f%4$HpW;%1mTs|t}m>3oR(b5iBqcF(X+Be(w~zt9(OxA=AzVsQ-AQJirAE7 z?*&9^=z@Sip^%%RmaBkMd$>7b<9PB^?qsH+g&fTtQ83b-x4uKgwpVPVDyE7*>o;m` zW%%^`?xfv~jok;-{Ds&uY}AN5%q#%>jc1hbt0!+;hL8hnQhZ_1_ZSJwGmiZ5T*bzP z%JqaE0DRd-45G>=v$2a|BkZfBm2fZyecg9h9?JiQ7DCYXZjjj+QyQ+Di|5TZ z_99Rv)L7@u9`MEcjT@uN82us~QL=aT{#yl4QvHUrBF1jm$chY{wAipc)I4kd>JGMe zz!u%Lbl3BA=NmM@sty%vPZ2v*5y z1(i$;1>szuvJC0|=$1|_4--p|H`)P3lVu|-oL1tqLEi-um@wV(O8=1R2$s69JtzZ> zW|nh;q1n1|NzW$MO6%$=Ijq>Y3Z5(eyhwHHtX^P3XEBhJPhG=6HiJHa^(l@K^JWgI zQ-eNspi|T~u%ce*5NnGEjoIawNPg z0u9@M!n=-D+%9yzIVj~v%FcH`oWKW&`Zr5an%#p?ISBWo;OQ3kdD1v#Qo?cX%m z?2S~Xom1cB!WYWv(&~wbFSrZwFF?HaPCRuI;-9+{wnBUWLf-_$=h45Hq2L}_)0QN0 zYK4o*VBI4nry99Zju|&lC8u$%aYKh{Wcwa@oheP&O>*vvFaOKnA9+FFE@0K)k{>n= zDKnH(iV}~@aWUhDxzM;XZj|nJf7gRzzUwhZzWMabE^Fi#c~o0$Co4HvW#*}Kr@BwE z;pCOOjEgn{vc4e#Y&jBNZE{ev`?Z(L3^p5e`PW zNUdFwF)?X|5$e$M;UDX&vk#>?dVl`Vuw4s~@-`NT-H29eFS7>|=nPL!p& zu)YlI*UyR((}W=^0^+X!ny71F#JS7E8`6cEV!a}~eRb*AA<*FC!&;^XEpmAe^9VrFMV0S=b?AFvU5y)GJX zqJ(FKf1Yh2@UW`rg=^zCR4b#~FUvDOTh&uEyl%rq&|xx?I%-u93%bxsWbTU6dmQd*OZL~nLJ?KmKJ44l0 z@>E3_;Z2Iz?A~w{x?z}%vj9-M-|eBN%j5xSk>8{zS2twIu+ID4A8aXmu=SW5Rl#<(xL0_r-lrHPZ zeqV4vFBpWUKtw2%gU0x>@?NJMXlU-|a%WDA{c{=R>T>_zV#-8>+mh@L+8gaiw#>=2}xS=-c1-GW`EF z^#5AlOXYA-244azM(>jdv|V?D4rtQAj#5To1z?Dx$|ZB8MYbm*y~RFga6bC^TIMN6 zXp^&WQ~+~HxeqMWEaSZE6nh-iLl^mQZeUn^beq!CK9t=7A z<+8S)-N=wM);!wXcuG!Pd`dRqq`b|tZun+7a=0o02GiVK^7H~#2CY#AsRMG-g;8t5jf_UKO#WjZBwz;R|i(}6~pmyg|3m^f?crZpXw{|lN?WMV={6apzA@7(e+S`O)`T*v{L4(DGskM+S(`*G zk~<6Rhe2H?DKe)xQcFjdgacz4%uNM}lM#(JgXFLndST=AZm<}nAQNM)GO+e!TVx5f zphiI{&}0n;eK-4_(orn-`#$&twNm?Z#9Dx1DbK>ASvdu#un!QdSr z*9s=wSKl1Gp|MQ@4YER**?`|e(&0X^>ZYA-MY@)punFn{GMPd8a8+_)}2XjWk=9bH@zg0r8L}*65;RAv~beII7C2rGaPfD@-3B6i<5513gKrkUq*wZ!z)eD%C|u_Sq1IK4YDGa zdCRpkv&Xf_lG%)nSL~RKFHz&~$&8Y?!duXr0tgbdTlBQxsm4v37VzL$9`wndQn-f+ z`sEaNqXw~wb^R>jyr1n~>wkx@0Pw)n*ElG=PFGl?L5Ek7F8pVZ?o6FC|SK>~T z5pY))Tat&%cq${~87Q+4p6O6`H-r~P2wDN>5zt73y10@R!a8GQ90|7j2$be^&riVl znwAIw-esZ;qA4Ab$`spIu^_jmg+BFph){aBL-Q8m+m=@r zr!>J6C6be80?NBoohQ86>U5Xm zgx93*a+gS$XX*ie?=ysgan^mvTLhBPx^v-PU3f_^n*WG@yPr10w<^b;@GevLHJYXE zPMlNH>n!=E5gB%LmPia=B60i$Pl?3y{{#OT{;cQtE#x?H=7jedbvA&tR-FO=kE>JN zX}wM{#b51^OL}$UXPy(@47J8hJ6Hq=Wn9LtpP&91>@x4RQizjc=O zDrc6~Y=+L)9e{UFs3YJVa%futRPj#J&@x)L2Xe(wu5;BNxo91947pBms|Utksb*T! z0EnTNXx%2yA@4F6d-eGf-U^tI530hY%j`T5K+aX27yfEnAan0i9PzDn0tI-sFrsxb zun@r7ANZ~;IlQR^eTsxWmre=uEAg{8Hs_02b!2qYB-UYAoH zz~_fCIK$%7N{rg#)`FNF*$NCeC~0)zF;b+u5DRYasOWEP4Jmpemc$?=qG>2Wf$=@_WN6^jBo>PsNWZh9r7Ta*0 zwu@CKxMKwVJuWYz5bup|fb|n^N>6tsdO3Aw2PsOwa1vUeIAA((eSJ~tg$OTJ;rh#o zYJYVP%4EsMj@Hbs?llS{&ZDp+SoQBVJd+etc+B!q>+J+IMk|G>6Ww{jh)%q>B>A&O zyz3txT>nV&zddN|MUPg}sI{#)&*PzZ;7Cm|SC6L};KaKP_(&H1|M;M|i*z>%TxYm9 zIK>2Y9JR$pkrtyB?iX0_5`5qS1*uM8N!0s`3S*`!$ot*lEUsH`A(m;a|L`JKQAew1 zwVI4)9(+7$dl9$WAf{em_Xe$OEuMVba;{Y^P|#Ga^+^i%IOqmb&|b&&CyT<}ugjx# z6EhOdDIk^V0NFgaM?9wZ%VP z#dQ?uxkcMsqYjz$a|^@0IJ~+wT8>Gg6r;BI@1aS;Zancz4+VgMT5X<8z1xFx-uH$( zBED&KdCm)X>@XlSu(hVXDCC$xeuoNx-J zBEJP7{vClt*yo%prFnK21{3!wCjiTb z8!bT3C-?2^=6R5OWm@KYnR6nk$(af0K3Mt&MyDG9(+c>}Rv$z@$9dSZv#D5GpO;Sdj z@H*zJ>G%XVELO1>8pAS5&xK_cpSygGm1d6-;1?$dlV}GKUM{Qy#BJC3;&%i zoQ-Xby`D5_WJEY9WrlFYy5cCVm~k$OsTCfkK5^asnc;4xo*rvfF+o)A#xPAmhi_f~ zS66I+@ouWq+UPfUQ zN3_n@uM5@xiFVB<0EN8dN&v#H@ZwN@re3Fqwja^9X6w5EAd>@%Q({tE{0|ST^}MJ< zI$^GV^UX*6n`NUI4WdwO@t1!RGdw=c=%QzvN0*9??A?%_l_x&OzFiCvt{-PVFO z*Xwy8_jk&q&7Z4tj0Arw4qHbRN(>j4VAB0V`>G}EA{u=%9vMu+!qwAOPqz;#$$*!N z_}%l-Z{`T^ZyG=IKZO#{b$O2d*7odQe=S_`(Qm@Dq4$>xC64>I=dZsOJp0jae-D*? zsNGV^8`Yz+?ytYzy<*p|nrC&tsUY{OXT9XtxtYUrZEW{fEcq2ZYx+$U@z-B7N&39R zVQ+!@?X9D8ZfGJn={A`&FJ{=wm*xtK1XNoJp_o4iTbAzbyu-f17&UZML< z3DEp~1%-y|Kz_FW=x;*AvO+wSpL`4`?G5(jL6ErPJ>p;BAy6u)dFfmrApoU4YG!OcAQz2kN zn31*X0NwKDM!C>buTq{J^lc@p?v2xT4{*uXF5L8JsCd*zU54&~UWQ$uwWtVXC-2^y zgC8g7@72fHAgA}j_ntywil7%NMd~&-?7oySW`ECeTVc=Q-$J5+33?qBq&-3#CQXZV zc~3*ocS9y~@5>7Bl{-Na4En%(tNOkv3&w%d8!e@UwcYKpEYEE?8iJ2$$NE9vId}^r zO~-B|Wt_yJc>Br9Vk(}^4EZ@A>FbmEP3l>kkg+aW8c>J1KUb;RkyJ`X-JgP+$@KdZ znI4%eygzqZWmDKp1^D9_)-f5h!SMm(I-IF+Q{T*%Yn34Xyn2#qn!W@ETGJFg(+Cno zvWq%#E2fg)?jQMRR39f@1Z@zQAf>A^CmjOujFU!z`y3TYIO+4|kev-NJO|+@Tn>mV zLq<*02w|>l)aV=NKb~x%|9KoZ{3vaS>++fph{k3{$AO<>uJM3f(?Y}tlECp(v-!oN zX!MDDRKjJMKTr+clH4mFiJY`SrX>ETpl&b;e!)konnrg;A9lnwj4>wt=dH zQ6`cyHz6H(DF+ob3ScX4f<(?qclRmk^;0#O*UsVn0FZ=Q3+5yK0SK)S{{BEHI6{ee z3x-~JA^urI6&`}-;Xdqu~;_9gg&XGqt%X^;zweawu zBDw9RuZot@hst=X#AGfF-Tbxc@-?Ut5jA`S;`CLZqK*&J+75=j?BVp!mfVK_=Sq6u ze?y7nNg55>g^8TBUgq?w8r8v|j|paF_qwlmXw$tQI3ekaDy|+pCs`KQWNQ8O<_!)j>4&133u<>{EjRXlF5ilq8>qWz9)hGB%l|`>MDJXFa(9)Sf{) z_GhYML2+f4{#=zA51natSkTSND$r^;(9I{RF3Y-x1;QcA2=~`eV;2kqys#Hnr8Zka z%Bp0zT`*c=6{8CeTVmZ5Jv=+dLs1K^S74g07=-x+T}<1};wnWgyO*iMKoN27zdUeU z0$0XL7eNccN|%Em*<{vO%#sqoI~T&)q7cq9tI+82!njV9J=wiFX_8A7{%UI39PzW} zJwgOowJfs<$ii5M>Y(Z`LEq>>3Y~`SzDm7U zYl5npQy#hvzJMK-_737dg7k3+-;IC}0|DOC-R6R4)%zfGM2r%a>KGFA{RG;Pwwqr& zfnASa>Q4eYPpQ1*R@F11{A-Ypq~lJeUJE@fa|9O%sv4@E_+>!t`9GU#2{m=#|Ju~4 zP*Vh&s#BSzmz{hjy1COyn|L_E1~qfjxQUNvuB^9%|8pz zHdlGCtCE#|AKWaI_nwAS*WegiebEf}7+bAnn)|Z6=O`^v)D;o2Kma38``}Q8{~4TL zG^6+B4`HRo(3Lv0P8SYbx-zsEXAMXVYm$b!=}J}|Wb{M%WdjtDcL#=r4tBbM64}Je zFd&U!iIUz0-(OZbH2A#bXV+=qE28uM+j8~*sF%o!53dAoe7^gk=M-Neh=Cy6)H6{U z-%8Qw@((N3*BWo;&@B+<0rY)s|dD3q>#!5-x?PCR719-0WvB@zV(X*BdnE>fta8c9? zqG0SjzQ!tIF|$mI0c>p zz5xIk2k{?(e@%uxtY_l;i0R>6Jb_d^JT>70>^@FNxvQje=h`y=Ie z0U2$#;^)Y6`)BxHBy;f``~i6mMCR|wH;We!d!motMPn}NmNU|;WYUsRxPaWZBoi+p zRZH}GyT1ewQtbcfMdM2)LUdzdW1S_rbqx$0v!kqxG@G1Sl85giz9kb4Z^Go=b}K+| znhkY+fC~=^9o_3#DTsF*qi-Vox}%jzn@{X-UO^?`)8|5Odxv@Cy9lPFf4; zufdxzU*Nn+%HhI*?=yHZfv#)7_sN|y$x!CwAkybU%Rl!cy$RyW{YE(Whwun66kusa z>r%3HSqi>P-iH5w9{X~cf^mEoJg_bkY*x@XIso@*z6joKq(-317OEOV`ULQkR>%~n zB(M%58AD2kuoMW=R2HOe2RUyt!g|UiVCnbP%BIbrMSpNP=hcG#6H8lzln+s!2aRSW zeI`L*dcf)CzzUt9C#B*%lcveKJO{2dCH*)+r3R&|K-dRsX$l+%VCoEpyfvyw=klcC;HO$; zUR5fds{Ymqmb&Fy5?EdUcPXboZX8zgDZPT^6obAUpUPyoE}sADPdhG21Z z)bEEALf2K0cLQ%00=_)|9{C~QK$f}o$ctv9?8R=*yC>|dyvL5l&2&8}B7NRAjo1i& z(b~d~`f_!Ly4mobU&MJ-D6MZKmV+Qu8(w;`F&fgDZsSXd5G&nKQiBa3KTSr`3OTlc z4q~wXP*L)^5}4|F{W%U$S_FOLf#81Qx$+_$Qf)YA$%^boMpm>XG~&FUw$?Y&?uI(} z!E>mn`&@$XPjG1)RXDL~m6WIe5KWm4MnPHjwcZR<(LOkIr)FrCf)kqJS5M*-h|h1@ zBJ#_@!Ex*Vc5o!l$CbO+j^M9^d`^}GNz&Q`{_LOxK5TPZ$=Wp;O#dL+w=(ZK4Gj=4oca6rO2>#)r<&+=NQ2t(mYeHL( zQXgyQ7>1xb&faucQfF_MTv-Yxdn@(o)_)`$+FowlzffsdlD-a~%wplq^qo_}}e{>NuDo_@%3@BW=1^^K{-xzUY(vFzW1 zFTN$G9>qCdc{uM**q(WTJ@S3J9HB(OQ?@_~8+^{MWQ{X-^++HAy6ELK#VGA{*Y}=E z@Dr!lC;LW@42Qb-cH@BWhM)ZDsU*iEt(7eW4Q(qdJ2&qfqFmS&^xfN9S)31>?!o2e zn_+o-!ONn{8GX@wQx!_T<7~KP0fy@fC)gBY_FA%B4Y#Ts^IfYXt>W3vRlT$AxR6cv zonzB)fmQ-bj6xH)|4}r0C0GoQbj5kE{P2tz`+;iWJfL4sR)ft8USDwTk>{JhHV#Z7 z%q$oH^UXouKU>JFtM3O-*1wV8SL^XRWcZWunl0ekkBmCuEqNgbIjm1CH_G8wlrH~GwR z#DBR0@t>`P+jl_SVg+7E5S9aYpl0%ujVs6D56K5Bs~o@d{VgQKEgwAQ0W+B5sE1ag za;I9@Epu&i*1x)bW*5$KuXllu!fu(Z5xVf0nsvk1nY+Tqos-wi9xmBAwg06-hkG6< z!(ZxEPE`Qk^}Unoeb{fUQ|2%OXm%l8 zZSlvDm2{_RtvgC$qt3~qsal@ji82qmu*4kNK5>8( z@|)p8no8L)!JdCdy<@#OGYyQQqb)#ONB0f$YN9yrYv8%}K;@^`)aZ-r#{0gwKKj1H zkfzTxe&ZU8%6l!=vrove}5*($?~eC3YHuPZBC!e;&A37hp3gig|3qCTs&+Yi>dnRrgc_pHB5je;W+fm$2J#W+a$+*(%`0 z^Q?9xbwX3r>db=!$G=aK&S!PFl;91MFx)QK@BriOBfB?j!d?>l++P%w^-m)W&!u21 zaXY2CwWbVcdxPkn0;~IVd=KD>Rn-2@W?- zc>d@xP~9Qv&t#QD54TfxIno)ak9^_~@C?E_^~}jWGRA4f!^mUKvG{rNvNI85^1gEx z{)zNC)8oes92P6Y_w6wab=z=m9XJ#g!1YV;8X!}v7AHOgD!zbE1QxKeWgi?WNV*r6 z8cGfL9wvXQdKSMy@-`V^Iv&_moOvQB+J}{Vb)8Xw?*S;g*rQTQq%Pq5ZIBgaH{cqS zs<0mvYXM7dk#9EX9o51JAw^iw5#5ZW{UBR`lkO$_9#tZKO7EkB39eQ&0inSPG=2*3 zvQzDoItw88wE<1TDk)OY<6*{~mHC>yOEaOD58y8A(PLrWED$bedx~WCf(~HcHF()` zUe@MxHze6-3*X4v0=NwhW9WDIF89GjSC(E@e$-yE*tp~^xzPE=b)_-VxCI<6{@Q>> zPXpJpAur``!)5pbGK7rH$XkPk{oM+ta0c*X~~KS?Tx%Hj@JIL@%laea%n}q+5W01?Ze; zGxRDG^;Vb-D$zqBtQ^>e^A5l){XIav;uJyvuENo}^-wn)>IQueLw9esJ}wd{NuXq7 zs1+)Id=0I<0Dd=tj*t2xO}6Hr`E4D_2)OR^CV6g4A|_<-79$=_TDBxI?g4UP%WT!b z7P@s-kesbEhR+xP{g{s4epAAw)IQ%NQnfYbvAIEH1P9!w;fCkvTcP{MQd0~_%`r2X zG3;1_7$GJ$N7!v}V<}o}Y#`t^9=qXik$nC>@r;bxPF+W%r#EBWJp0I}jrNqM6NC!T zgJ;_3*^{4^J@drizftRP@B;dR#6NGviR7W@9XN$tdVV49Ij!Z*)M|r?M0cRZqk(kk_jpnEp?gieDS|H874y8@&b?@EshWms%-nn+s^Dkl%EGm;qO( zsE{xF;#z3#Dv3drEk{Ytwt0@r{*+QY;ZOD`@k=?fq{Z#S z#hm5?mJt_+i|Nh3B*c{701bP%AbF}qws0sFRhAA5<6gg}lb#6Cox8+WEeEWrll)l}%Bgqqa5FiK7KH22ZK88^xH0daymC zOO-7Yq^tc#xF%R9R*B(-b#|*L*xSG&+YLt#F>jxSXOri)rzdiLDq`c>$-;qdo~f~H zZ*5CJI&&eCu9MHU=Zv@p9|;NGm_l#gTb1Bsvr9-4NtAY^Lj@MGKHu|w`DQRa`f$zB z27FNV`TH@5VY2V7{_F+@6yMwon0s-BUAbQNecDeyH~>CBRL!(GPdu=cntt+J=Vi`> z^vNZ#d3gY)vrT(hUe}gbR?z+PYGk|-h{8zv0mOAI#FbIT>;jzMN{7DB_esDEAbj7q zM}AO)j49~{mPUieSitwU{^|yJXGhszx$c!81Q03!gf@>7X1LGyX5cF9^Kj+w@Xso5 zgqHXWiyE0BT-grC@IUIN(i36q9c>HW#Fwdcyp1n~FNqiy+GXD-veM>I8PvK2aKYit zKHtVqgL74A1bje5u@h825K~GXB@`vc%2=&wSd(}W{C+B1`h07Gw>*q39L7R#@-xSe zgZ`7AsZ~Hb)q=j6UWk;-1HQ2*qniW1ul?Fi=8ikuAy68BWLKcWk;EFF#gE-*Z2ySf9$jcANT#~XoJVGyF+yN+Fop3>A6K7KA4*q^Q+}WYx z!LQ)nR$c^^SmFDYC(oFR-tG=p%sPG0GUs%50wbUdyUTr@vA$-HZ1`6E*Gc zj}Yq<9CHgJ?74PcG=nc(rM(31IddkeBucP;3yg2TXZ0(+Ja?%f0*sd(a7nn%9^KF( zN1D#Sw?+;YWftbyC!9antx$Niw`S*wHdvoSDyAZ6E8t57HB$mjD8Oop5S4@zA`JTF?Awq}y`QpucG zPQdq$>{__E7rX(=)F*2KH+z^s42rNbHmeosY>-2jP-Ro07$qpiIf*&fM=riRm-!GxzM9#1E2*ma00`*#T}5GwcOgCp!XonA zu0+L~q15ZURt{eYAFS~Ea)2gk8t~qLuYe@(eh$A#_U=wstpoSHfX_z0*{x4pdK?+d zH)Dq*>5=17(+lF(qtvx-q=?4PBMLGeXOM|x&U_^0$(KD-m!nL#YZ3ha;KGN@HzVgz z+cio%-O&QaQJ(V$da9ytJy9P$-K6>ezX!f*E6^*0zWd>5Q+CjGi)*P<^bmjN_x(?h z{6y|gpA9@Q-=u(#$bfbn3~ufIpO4Tp)N@2iPNEYvz6x-4KftQb5d7b+K zrH6H(%!Cdkts)=niN{OG-}mV89CCe6B5-7iSJIPf{##Z`lP}3!=OtK~a9+3ehIi4%&?H~Kf-v^0DUD!o)cl6IN@Vm5c-$UWxruDB9o2i-BSw}CA`&mEFepKK$BP4#TKGK z)ZjZsVdtmCBQU!=B}LUcMdq7~ql(F&R%q^0n&0Y<;?S5;4QI{B_~mtE&4EoVy}&dF z|4o5H8MEErCIT4u001%`b1X2}uaArhB;~;ku>w92*|WofQ+m-!akSkzgrh3JQ3$-yFi?QMGYr7dv^A%9I4rBrGx?JXzfAxP3F|yx zd3BMjU)gK$NA@IHb^b^n_A7hJyGGoj_eXkDtWzlneJTDe075(kp&%^4`?nV{e&tOB zCHeDlD?!v_YhI|~b+mX!blRJmoP7WuC)cCUSCNjKf1$ zM=G4)^wz5ijN_W7FdaWr_T}{heW^&)8R2-!?oZUoz6`jO$Cer4A_Q=Jtxoui82z*u zd~!gCq}o0u__aJ!*&)uiB55mp<*o_72m+qvQhhUg3E_@NbPV3t_aP|ngnyb3da_mE z3LZ(X-~u(JS8(UTUD`1C+#dZ<8eeLFug@8JHK7lM{rA&p6j=JbGy1KwKfZIuHvzyP zI*jy#Vj^^mBKXD?J$GvZLpirWdGSY%1R}+u6W9S?s-lh2FLbHX_OzDwf~6aw7 zr2Mez9Ej|G9q1;hwjJcn6EJo!baM;JN!2Ges}%14KDWWQH=s2L7(Tra0#bt>G}=40gC&X2s>WM)2i;0o3&m6a8y8g0l(s7HzjdhWu6#-SM(}7zjNs7FI~;l! zPpax-9EyG?9Ih1c;CKinRVVotTGDkLt6#e9HA{gTrP8MUXIU%_IjJV#d%8e3#NY{_rU62f5J zy$?0!H$Tu2@O?Evn|yj;xGf77d>%BqdI0OAO9H+*1B`w+#IvYm3bH2)-)}iGAcJwS zdIBE%xu+WDcQ)K>nD4ws-l$J@%!LzSDFhbo4$QZ*Hl5@!)0J=zRx0JXm}G@bQ4-n8 z>#?4ZI40iC>2LeWT4+Ay#;D>0m)!Ohz)qmg$bj{13EyN=`A^kjgv?<=Iu*Jgwj{wh@-$FfF0-l`! z@N6@hkHN?XpV)DS?oor_ecSi9AbIVzjQBcnlO_Bde7rGwlSO%6QMOC0vg`z#sfJvB z&4@oI?CYc9Ya8jWr%XBz5+E0n1>b>dEZ5-61o@!SiRSzuE5da`FnP>}52t(ur4*r3 zUk1}aS9X>-UVjR{4sz@D)!0rRdt*K541Rp$d;AGG^4GUhxl)BKTx5DXm&CyLC+If> z2R)I1cMka#X@;QQ@4I-CY}l6tcER`d?I_7_8UbieVHDy5ahD~*b^h_~;EsR|X{l{J zn^3r(3osLKfMH$>X~*WthS^G&DvfjNfMI_nsB8GuO2u1bARFF1KG&@Uml5zzr!jjc zR$_#j;8_LFH0I&C0pjpG`C;%(%SYUKj=U2O3&qEt-=BaTI0J4xLwE{47P0`s-ZaEt z9}9gzJRQPbcvlMX90)Jo3GOVoEuD?{^$=behxlzYh5*f?=OE9WgZO9R{ZkN1A#HLNFe!N_HRsgB;3ETJC>x<~@1%1UBmT$75P#+o zXne^~{)@}t!!+decjC(4TMf#$JoRzJXF_NP<-7;NbqL#@LVU`fhHCBr zdlc;<_^3KD41J)wnjnzYULPO7{6|Nh_ie0iS9 z%$a%Ta^87o=Dp21;-)@!Q^zh**e-NZMn_UvQt_q4Pm`kJ^&(B}w$!#FJ<=iZ&4IYG z`2SzY$Py$z=SO06KN4s9khr41wYU7$*4~w`mWy46^K#vIy@;tZ5TBQK{+8Z3{&yH8 zo*F=+0_vR^K&=I_D1~)kl)^wj2&J5S53x^_Zaj8QM!AMQr@`9i%=rw`_A)HsdSpbs zpE^lw?mg{XT6SL6rs(^sm+Hj`$|ADRsW#=joCtYcOD&=qo)iD`+~-_6{0w!(YJex@ z1m3~@R|c0-UV27OOSvEZO~L=X6zUF|a7H$#ltEr5R6r>f@z9(z5R-Hr_P3Kb65{({ zNGN3oA~|7c7EuXZgr&hS(=2^v3v?Gu*D?O~9DrofUW3$mhuoJ^E*{Ibh!lYLrMRIJ z3!w1RU}xI29RM`0RIiJ)otHH*R27V!21rOlBbpRS%%ij!{qFPfJa}{S97`X9!Oerg z%_5kvSo)msJnQ#oJv_tfkmm)^T9?IP5edKo$OtwN1r0|9Q2el$IwLl*K8q%B1sGOoz$rQ%5Y%4+>nxkn-n}Im2zW}wY zBBswmoKkj1W_4#}je{|iK|xBi*(z#+MO@igIWw046B;1EXJs3M#AoGzbbIK6+yRZC z%Hf7O0PY7U{{i9)5MRiRgx0!JqOE7;F37t9c{d=w1@SG2MTkX+uR(kb;=bI(v+$>B z8GZxgM6)0J*HAY?0UW?cBe)dYl96SjN?~I2B5UbB=Tqw%aCW3Ks`jad&l-?{5cajk z&ApMeryCf~^f40eKRLSrPyWS&GXCWP`dyD?f1Sq7z;1b5~rVXt!66tdQk9%chpSxgqp z7|c>k*6*vVy6B#!keOk;(H`2I$fw(I9TM-z>2|yeiB92Zm5v);tGTc~30>wwE49!{ zHIP+pR&`O}mT*#a!ofBXFs`Ir444+%X)%Iclt_E?3>7)`C|_nmw^{sd0--H|sT^G{ zIS`Zqf2S8%}U={X0^ynf&kE(GNjj(gmUpVB!1*W`Vl2Ghs5`N(2D+? zoH)%OI;>W)%la9l#c>Am{!9PDwm5%8U9df{=o;z@13X+-BlbfG(M?VR{-BCy_<&R{ z#Hz>QDZ(`M=&<3p%gj12r%e-H88cG-p$-=#F}Hv7@h$2{D7_{Gu^a@p35)OhF${r` zF~>F`5y|BLdB2cZylJ{St{Qit48Oa&sJh5}S8c=M!c&NYNz<`B7U@%r7~2xKHFX9y zOr5!1&v>hq#_CN?NXNl=-VO*;!?X_f;KUM+zt2XC-}`gQ@cVW?=l(<+WiVD_QSG~Y z6Jc8H>}L!)wj4V)7G5^loro62{){p$pHh-^On$7KTdLquTA@48_!6vum0~EG+=a6u?I&AtDxREfo-6B)(LFUI zPJ2iCf6i+?cf#92SqRJ$q9z`RX=50W}()4oI${1w2jOxn`qJDFXms8Yt6K{+RrD>Je|o?xp};@XEVm) z3;jyIyn8c?(h6LthYdO8W!d9AGp$WVdy8TC3;hg#te}L)xwGJDoPSPb!ddg&`e7?*i z!-9W}7LEQI9`ELOwHK>t5&35nxI8PxMW`MAL(w@;f-o348qW|CqO8-m4`5TRyRg z<9bvDSqzbc$7+uEyC5P>EZ9d6D>9q5)|u%@zKd_@u?fo zCM>51qAkV;Vd({=BLPx8e+Y4Tun2!&y>iniKCVp3hw-EB0jWSZ6P=H91Vv2x_z{Co zJV9u@Z{V7hG1EI!ngdeIAjd0?nOf*WNUWBviI~^8a2-8Ls%z0GzAh;Q`T;*92JfYJyOs18L3LT=H64;m@%;yjN(B&5GR; zur(O%9DjBB3cKM^WH_)4i4O_>*xBlqA+C8|F(oz&^G6!-CZT4eA?LNB7h&n3w05_K zqr`s~wDCs=aXoFL>MJ*^g3D?auh>C}e;-urAlVFvZ8ZgKSlo&2d zk54wqr&3HvTz(1}R816*>#$A>`|sy|yaySSI?O4>RzEV}JxUz~>1Mz1O8m1)i+zj% zxDmc`GZOQC!$ZkyQGxJr+b?-`L}_URvy`8Zg(+cW!jpJ~a5*76InAfwiyM&FrpkOO zjn_`h26Q$0k6I+R4dyOR$Vwa)y3hX(Je%Q}70MGw8S4K1EcG+|0;p|PP-EHq$FAXc zO)hD{A#6#UJb9^~@N(pQ(gJmoEh?6uRhpcp;(_HoHiGYz*}crgm0~O!-bM18C-bvl z0zMK36Guh-I*8JKabNdL<`=+HyDS(+Pjqw*D)<+gQKrkq@gZIfh7rPg4@i3gUwDvy z81nCfzj!V*|Eo806L3+XNI?33^=dY*{>wHP%f?8c0hj*xYaW zmfP0Y57>^|uiD=B%!2ow(H~R7@NEsGHE6}MWw@Cw&T{v)C=7u4uFOX6d(_mPC*h0I9 zq(RtK@>){tcRYbxQ9zjqc56c<4Ek+fSF@&=&?Y7BKD8ruWVEXIS|cTH^$|3~vV{S= zgzuAbaH$ZQoQ+=>rX`oeP4XemX8WBSw0wg7riX#nIN|N&Y@N>M^Bf|aNEzkOG|iPK zXc(BjOdo<{i%i@h!JE8z_6i^7XxO77px$yHZ1&MreEHq5>JQ<>eOac=_;p&`JA`3d zEwQKoX0GqLM+tE`tf!ygz$%96U%wx*Z$tPRf?9Z!8-<-h6E_wY9KXz+#<)P(t-mL- z-~i!L7;&_p5fdQ92|wzisfq!@w+LYdcHHcbQ7hqE$x4)(lzik&{MvZCQgq9BH>@Hc zg{ec~WeN6#2Bp|33l;;9pBA={8|x>Ru@L)hC=vodg5+rjAu}whQ_=en@&p(2W_7 zUlwMMF;LUS9{=N*FbX#7m(o@+So|U&+)XQRVDU_#Yk3-s>dMeRJe%bQG(B**#iAn~ zP1D&GJ7pUhl->#;JxN9KWM+q?lv8<4pRZ7sWbm&;?vRw|V|Z;dNe@bI1Sw;F25^l{ zG5n4{oUf{H+@(Ay&oM=}pO9y1wkRXo$+7it-~{Bw>y%28ZAws5!R*8U;xsMM;)sZU zxkebGm)`OSJJUJAm(Inap{_p!qzXT`G9WGS+g7p-0cnviK4UVTDO6?5#e+giM#AKM zgZuvwZ8wPFbhM4YcLw1*0AAbBaziG2=4lzI1{EXojRIM7IS}j_l!|33ysXE3y0}QAuBU`lCpG@ z8F3&CX+wz^l-JdQ)TCa{0I6r)u(h^R`PDj*J}_>Fqp39@z1#}&+Rn^*#V=~_tpBP( znXd1Elgo#_>1KBWHoU=y`Dkgf zV-0XBIVz)I%Hkd8WtMI04JXnL^h>X==*_3;wM6=XU1B3LI62rSHm&}P6PnsY_K9Mb z%;e=a7(|M0gVeC}O5m-KbBDY?v_s^kvSwg%I4qXKMyzen!Wl9sbqv8a46;;p6SV#! zv@U!R8&N>7zod+851nyAX7f5#VeJ=WW`Tk$1Pwx}h!tm{7cBP65HGmf7(9Nt>K4*V zbyL{}1@JP9Rbdx|uT3eGeMk^Z@iT9gPtLe4|BV zKpI9yc<10~wTQK842sg|3Po9D)mKW~j;HwCG&d-%KTY~EhttR`a!66CEYnm(R&Dt& zh!v-y4Iy&eXzfn{Lsdd^UQ0mwF3|5u=gH>(-C!R%-h?INqGGF?tQ#2qpUSE2^oILN z7URVWMl-p>kJ)33b4uwA3o+GWjn>+os)6=x3w~)N*xWXY+u+0jNeFNoj3rnP^p>~L z%<+b9iY7F-QhX9h{}do6JIp|f&=xz=F?wb@Ak5l_)_e{zNhhfM?fMNN+^CYfjdSqa z1%^HZ(s!M8?yNzn-DlVkRZ8g=V~*cFYq+MflGN01XooH+IDfEytC@5~y8RsT0@A!7 z7xXciY#>^e5H6sJ5I&m;e`1qjLvs0(xMv|S&(Ibm}r~Hp+w#=EaDbaSvqam&T)`JGPL7OQc9S<=2 z%JoZoRne7ehZ&+zK0*3OK=`k%a?^+^6%fUe=Fkl$;hpi5sly)&UE^a4weFl}I#qOg z4hau`Pkz zQp9E56hWcJqVPSd*qxw5lSvJu8IVHXT(yCz0nN|=vFszG%twd@M$R5CK zzI8nV$BRgFMzgrliSF!pYNg0ya=<+?NK%Z~h62)~gF68sD|^q-!rya8IuaBK;nqI$ zT*Jo7=c7eigu=ymV__)-q*DLnt`qX8>JxID=7gNUMfhGC+9{80V;e^{e(Vj47}F7P zn`IZsnIdXcPeSY&2yqY+?ir4oAs+lKDDn_%fUs}kaL@r9x1LuqA?;KKDX+tBF<=sv+qt#{t>{fHI9L5DX z+z$s|_8_C9uk0v>TE$0cerYcgZCERM#;mVaIqp1n6lFO2)*T&gI||yKHrYMg^yH5J zbHm>bo%1X{jmOh&UeqYZto_DAjW@WzX$(CrbWhUb&xG)MbdGFjJNszw^-D@eU)IrC z-AdZgmwwbSe)`=pM=RG8Jtk$G-p3u)m;U%XaP^>e9jdf;<7lF%O)ArGjW(+rtbH5T z7&baQozO<;(eJM7)|W%8%A@~;XZq-pZUk)xKEg2mfsa19u3tYJN~MoTkA04hhPxC$ z`kiKm`cayr@771Ut${{WX^1(w!O};q)^GgjIw<2;`#isIV}3CZkRSlrmcMZ9ihQiG zQ;sor%32QW2RT5GYYgTXvq8LBY3S=R82X-HLpF?WVl*a$QH-W6>yJ6=VDEpkMkcM==u1Kc{Y2Q@xWpKYrsG=PWyFf$g z0ABhn-%rYg?a!8teq13&sGGgYh&ewf`oyTlJ7_!-|5Vd>#|-gah@ImL-Jkb{#GGK))V{vn%IJqOb$(i#}(q8fA7VP54O zjSjVzi{{W|pJSUBzZQ`0`rhdYg_V8H_a|7{ls=Dtymur0BBY-So)FKi#k=2=muTSB z7)&(KeswL`99IGi*&1h+C0dYJRTGdd4g4kmzuKX~?HYTeZ86JDSl~fp`I)_{{B}!O zd3RCVLYd}Zvht{I+QDi?9FYv_gDIt>V8bqvDbtGe7Fa?eZ8Ju@+vQx{qSLQKCrhET z7a%6-XpzARcR>29Zw2sLs^}GKwIUTkyC_3ODQQ6~vJs)K6~XuBjFg*fU=I$m27R#f zkF3gzReyDBJhOR+0k-4!Wzr~DLf&~FtV+@ioDROPJj3+wawl@gA0jGxP{<`1P{^G( zo}JLVM^>1~pteHX>LIHc>Cy^tT|lalNg3Wn@I$m&1R@~a=|AGRtU~R>IJtJ6B`mH3 zc7L+#lM?`GoTv{@fh+QtHK0CJUy;x5JLI(~aD9jB$@Uec<=rI-=VVPDoUV4PUo3}I zQ$F?W2^MOHwiONoI@vr5D4Z7ZTvYudzAd*Cbz{0|<-=vzPt69qg&iAg*=2GF;1^}w zAH?u1qa!?soJIcEVTb%3t>OPhYsUK5fT^5Oyt212>hOACTD5?Y5i5IX8jIC9zk5U^ zu&>&TwTIWL*93F&lq1^d`m$!Kp5&83<$*yf7gR1uCciTX zg6oNzko6|Ai&-qZ=w5hz81?6a!wdEQkB2n)=l;)xl~dvzf9^k&5RhK%pS-2E;60gj z{^dGXI%hp4ij)R6nPVRf^QXj!iHwJ?$IWDQ3U4fs_jCQP_s5!$k?m}f6HLa273;B{ zFhDETzJ7hhdP*;Q4ls^8=RXWBg{^L~p)UaEw~8j54s3Um$|>RATEZu7-Bobc8F^su7&sz#D^gM65=mI%ln)*U|E2XiGh#{ArXQ$Eg*G+-LOMm z;aI;6CV9nLA}RbnM)H!cmdZ`%syUL%QYZ%4s9->c$x>+EX*R?5-@ME4e38yOFf13VSXwmF=xrL zxaAJUyG{Y8x4A&nFi%upXv7mX$q$*Ai4I1Uu}LmAKe29QFNTr>a%uHdH!>uSHK$%` zY?D(e+GJB?qRA<9I;R|_Q~BvAoU=oomaj6B8XFiq6ne>6BB{?9rWs`q4_#YPh*98A#g8y3BuOeikS^~NNIL(3pn2Tc; zj4M4W=Po!4r&Si%i4zxS?OYB@I{}+N>^+=S=EAJ9<{_)BO%yDmI~6RB0WPH^(as60 zrYAT?mBkeAsUVcL$hNR5zEmeV@^yXdF@$`b7{DP`q+3)GTe_#BM!&~4B>gx90(SpX z9Kq#)wEAOW<_{{p)aC(oP&hh9Q$|ccHWktzdWO zh#rg)r}$A?7+9$oagh(D!OU~FL76@z({^O+{Xz0@e7A?_sVLAzg*G#yAbgrXN<~G% z5fOX%_?7%*oHrSGw23a2ca$Pkj8Gi4jPD@otE@oN9cRRZb7UL%LqOSsG@Gji8ua!9 z_75!S=YO&bHX+YCX6D2|rJW7h{|jVhDyf(Px*@qG6@(lUp9#-10v~ HlP{NFv% zP2>=NJ3w>toaqMB4=>eTiQ8kE;CQ#>J5LOkY<1d8z z!YO4R%TK@y{91LwqJq5|iRa~8RaI5X;>l=@kH29V=|{{%0L_-9$cU$yVDM1lOnDoxPJ9|Lrf>QX>T6rL$E;B~^AMWZZxp=AY(ome2` z7CgnUQPYBTs45^0d_u+*&g-fOHckv;6YaWc$2nJRL?80gAZ=%iqD%G&a#5ONWietO zgJ774SW8l*jHggCo{o(DV1TE2P1BBskOCIe&)8H4N@t|!`1opdmqx}jXc?CwP|}&> zaUKu|4|!9N(eJ+Nq4{_o=R~eU={~n6zPd=$L=`Z6SyG*abw$fK8Ob;SrAzLp_yLvl z3Yg9`EyARd`yA{+#I{vc7bQ2r0(zeo7Xx~Zv{JhWF9@XLCz55zOrzb}95N&1{?PI( za;EbHj0zi!HX?t`lbI=}EqBga3wzJ)D)M^TBEVD*-c2MR*d$1-YJzP*AIe7pYG|4M zz1{Lxk0~5H8gp5;)d?Wp6TTOT|JroQn;OBoa1JFH?Lj;Bq;L3LMX5guGTyrLG1Ya-YlxWc`oL?VI~&!;@{TUW{jHRr%_|U{ z4CPndqv|^4&5AGroWm5+<1P>}L)8P84pRad#6R30cnd*xTHO)iuhvWCY@A)t=PdZD5$QK|6^Im5ATmscr$A(xcKFvY=R7CwAV>50 zQ{HDIGN8k?5o6*1@d%werO&zSprf&%k6YH}IpxiWh;Vl)76Lk{c0>2ob)Z`@zSl}d zoXkIBDG+O!4*_ai#3g`2-iJ3qw`&hV&Jz)8_W?z5D-3g4ut{hUt^G5U*rCMs?-I23 zAe1OM7RyY1 zGvI}7-OUp$6!S5y`M?AOvccD6z{&6W@s#(`2uI(Bqai%BR}i67dsXU)boNlXs0vMM zjnJLGMTH_U$N#3B0%mVDg)=O!{VMB)7>CG2gaJ~Kx?JSc(PCJH)kV6BX=Mzw;j|^} zl1}wr53N#PI0;@p9B^Q}icWelE4%M2Kw}9c<1*SyfHlRFb`_E48JMnBrO_ZotSSp@ zt>bs`@Aj~2bq}l5!V;)zp30+4vv_jjeFYbJs@`$-dbyaT{>)P@8r7|yum*1OSB*wH z>E>t8na0a9w-*bxGQ20zlHiW!+4q^8&;qFUZXJJ95QSK1b)(s91){jtQS+!1*a`1S_AQD zY>cRmNOVu(L20qOIO)?y{Mr|AQqtZ)UMCC^u^pbDl*O$$=embrgAwYA81PKXfV1r` z;3S#<-*I99-EcF{bg8|8$)+IwjCKM;pv!p&4PJ(GF2Ts2`O=H%4|>!T10IM3nAyF@ za!)IJxLh=`=e2^YaIQ(*Qb@z1OuTdr+8Z$_nUI6X`+$qP(msN zBoYl!Ou3lN;z>q3ksfvx<$Fl1*s-gK)K=_KIo!t+NfU}4q~TpfiamG&{njV&rrGRO z5Bm;mA`lo7w*>;wfhLX5PETqj9T>ok?q!HcJwRoI(LU`mH3@Wk>fu3sS!lHDF2(er zN63W6v=-`?>vk29X<|CFgG0QibY!)E?L{G3y5TuD=}vjo5ve~6KQS=w5U&aE_uxH* zz)A~iTh-n?iikTqTTQyh3qVxsuWgNzqZ4-(ec|Z>4IQ5JHxKEa0&@J+W7M7V;Oq~) zAt7Hix;@{(n!#+ims7)vn)0&Dne+}-L_5$XGovuv%@-WMj;H@l4y$-s1k=Y=Qm~y=MXYllzr(Gpbd!Y#i%$Iwe^F*Mi$T1A zJz*hAPZu?6LuWiF50nnqX^ZprS*Jgq?qOJee~&9`K{*OwrmKIsL|ZG!$aPA^#AFdMWyVs%R)E@R??Rm z)fq({YGYx?l^e8pe`*2zVhai;Irb^kUMBP+c=_OVr2EMO`&-2omtHZi)!EqAc*m0> zj$}d%$-d1&bSZ+^q6oIAOc#6PaSv6Wu%$jzO(E*^TIzlYNXB|-T&#d7qPXTZ782GRG2jPFd zC%(^Fj@`gDcTqW=jgNTpZ!4+zZYpAW-=d?vKpSKyAp4)XM+qk$9LJr%?R5>BYfvqmI)-!;ffNvvl1s7}6ElKXw&;>#0l{@j)6t$G7SB z53s97fvmEt=&RocJat#meHA~O_=upFNY+i+8r_GUN#vD$1fSSyfP;yw) zK5cs53Y^;0{pySp{FES+`Ulg5gM|ti8`t!(^ete_L44Unb~o(0XM)%B;Dmp9gmrVc z$0FUj?jKhxOeP&Uqy5sY0hD?=4(Uz&qE%B@O|uRAIGp&^9P0g5p9|(+Ca3$4p0|H7L*Czlun)JJOISlhD(2q)WvZZ_JK13>qkH~F3%{V} zOuwo^-~J`zxf8#B5rkzr8-HbJHdiH4y5A$a%?FFJ#Zt z%}fO~u6PM7H(=BR7ncG}(^g9~PrDM=;Rz^Hc5CA`Eo8c!Fi|6U3ph$)8MuL5wSl&A z!6|5z3rzJYX#1oY=4rQ|LxWT2LGuS{D4qAZK_Y;XBXB}lEUC;LC ztiwiyo7hcTZd8M;bMiFN-h2)WwWcX@h5@9B(XOTTh_XGFxQh{G^>*5eD(O2YXOAWF z93zJIGvfDhz#%;qV8kC~Mtlc^F-D9BR-XtgjCiJ514d(t4FoWI4DKLknvfxM#yr`; z=^MyDzPEt<=P<@Tx3Vl@T~6}>yP=ul7;$I+1j7Lv)NXaffO`iFh$`!_U9zK$0gzZo z9#P~UDSP!8N_D7s(C2R)T}{8nNC;gN-i zJ^J8(LJfI#Kt}Q+#C{J!u^6$15Wax$7=%AV$bJa1)Bm@M|J}&{D}5C@reKf?m|AeB z-bmLIl@cvfbd~o#TOE)bSBDfyZMWqb0@Mq_6u5ZR*prwvbopy@3LOy{gBaaX zP!R@(NOg+7;$d`;6yFX0_rm{@V$qYB3f$d9z>m!6ly%BO0qMq2W>%m3XAe##ZGRqY z`)mzePlMix24?+}8f++ch$xie0J$bcd>5!7TwVZFkR*e8;dC$`G2%fPrp9!@qU!+e zFU3lB9dNCs1(+7|)Y9m6(aqCg{-dk&Z%5ITPI(B8{ZQ6|cz$STtOupGc^2^Le5e

      m2{o1k-{;|)lxAJfR-0sxx21}-BDLU%CDu*w#L_c71j*pl6%~+7 zLqH{<`Dwdtt$}zq-h*M4VaJ4jcsgaIA&P)gpmqVD(EzX!#yX2xq+om<9)i5IU}s}% zQ0jQz+(njH-n$^H!m2nyZs$Pw7O48$Xq56h#iOjr?p2BRxRif-xun$oS@U)tqydf= z@rcFjCvf1XT${uvt(*FUj71TS2{VAd17nZF;|A>MiIk2fJZEMyIvZ!p2GgeQQDghu z%tSH^hb`ZBzyu#s{y8A^4U*T?&=;-~FWQF!%DOWiWKbMZ2;jT}9(N#*ImzhHLK-d> zITgETackWL4|8-w5<2EmU2_(qjkJmh477TAcbbiC0MlP`IxQ zR(Jv`tZ;GqX(gjlm4}9;Q$tYUkm7Yv>yruq|8x)@t$FY|**Nb5__>{*HzsAx>L5d! z0ncTw@;+BJExLy`fp+j5q`n=>D621=?oKb;Wtr-}A|E_PAPT!3p`qXtF8+0BxI**L zg2L&2bsqsaM-y@$Cg$mbpZq+$WRnKPhBb-dZbI(LLzHf~eEi@tF36db2c(x;$SO;q z6O3wiHjm()w}4+UEp8ur(Q?&w4j7}Tod2{OgXjfR^dVP&X6OHQ;2p);*Itv$m=iA&)$R&=J>I6F~+ z4M~Pmc`YnxVXpy&PK9>6AYK>T&zTvV9g8Ue;oL)n(1C6p*(V5Q)Ins;1VLf*B&XF5)czrsdh zCE^XRD|AwHXVlCp-Uvfq;iKw7PskhkPJ(U0L{q|$)H?V$==IV-cUa*w@hot8)iC@+ z&E-O#}HKIYP)Fh`jD`G2^YTD|D&hOj#9LMhx5YwOYXr~_;E?Jnm>hF=RwOQ z!r+p6xO}nuk#c;GaPtu>UMytUKE)@5f7xc^Z9;xU89pq$Tu~8zupbUkkcQl08PUooH{Rd{k~93CgUv@{3D2&b1$OmP6x@46MBHJSzGN8oxz zd}q%(8uabkj+305{Wm?}94cf~ewnbYe;>R%QAES(S%kbCOYTpYgYAYdn=qmrWqmKB zy39)?t4x@=ERK?8!Mm5kS-6}ZyG>46T}Sz1`yE8`#M)sC7|BR$KvSL zwL;1AWZWWD!T*QHw=7psjt>F{))^a+0UAdK;D*osz_4Rlbqi6#B3--*i&vp(QjW!c z1~8;JNL>u3G9h&#z<84o))C$Wi{G_YH*Ery{zFxaR}1P_ELH{#zz!)df|9kGJg)-( zNMMI_2Uc*rP6)Tp9cQhIhLe|ag%rGI0R{?q)lHxTVJ?TRqm8sH9s74d}v{T4`Tt`I=3dJiMS`b^{A$!9gj} zFD$CoQ}+%D8>-Dz+>p>#oyQDH@A!m)>N@H^@St6#)dE9ZzS$nmJ9*vmGP_y#hRqJ` zUIpM)nRvbM%c_~wJ43?M)oE1Sknrg0G1S}OTE2Qh(w!>AUS0!C%~OcI2aq4jv!DvD z;*kM~R|kZDt{w+`b@-Z^hZ+a|8f1zeA3E*{fc>t=+bAx`W z`kd!uPy`DCY#fulGnFXi?)cgf4RJ*!^w=+Y;;RpW9)I(VhPd3# zcz1?ekay0?Y6c~XTnlzw!0Jnn+l^Z^_EB531t{8r4?Afd2z=@JtL56o z>o03$str%5STU&)%gVO6Mx68G3-yhpnQg&NzVjHjBo&OSfx*E*kGTvyRr;l_7}jU% z!26zyKu>wFjvuNr-&W`B2EUS9&Zr;Ew^hOPA!oxK3*7Pho0B-H@3z>+xf<@&I2O59 zidx0C}!E_Kl9cR)*nMM@DBxBpR;x)SatBGKc#04`tAwiEJFli=JbFEa_N zM7Vs4#7pqB07`BGd2f~%f(bLv9FSIgEFAp91N2dUlQ8%P9bEQEUKyw12H?V(f#VO# zi-4c?4hh98$5D7dShvz842_K!4nCpLEFSvZx6Ua)tO1iv(i0ifqkf_EiKNU2g8p8{ zpn%4i_y)U#wo3e)<;Amp0?)@pFa>S4vsJ>lmqrR*D`Hq<@IDe65(ZYpJ8le$ z;H^jQ%8^S5a0?;?3&=3+V!Rb5nz$Idc0^97XTjVPRRPUR~q+kkMM0Dh-%zfNV!n`aZ7wh#rFN%)s0b&uUQ!P{uOXx z)4}g}ysl`N64uB>)3yZ~`CIdwGGijQP=^&E?{44!_@u@i4_oH#-+rQhj15nSYW$OB z|7Pk3&_L4%HskESc^L0@G$5S^+MUlWgkuZeyBShge^^%9zL7Q6+hm5^`s1Ri>WWa> zo38IX`3-F=qAc4tZI5b9XxwALF5v!JVP|f8GKCqC90B3RlZlQ8TdP~Di-ai5P z3Qk1DA*Ab<9`Top6w4UOMH)OqvD$ij0r#D(aVmxHZnE!xcQa(`fb_{A!{;@_4K;if4El@wpo6#`r{iBDB|Y?dD} zu?CIK4%D>FRNgmo4N%qI$`_eCTOnnutE{x#?W)`?({)!jGj|rRIj}Uc?Ci}Exy&8& z+)eVVjc4Q;;8!}&GKCK-#p2un!WRumrGeqAZ75|xS~~cV=b-`)JSxil3jPqV0SAFO z`51z*^N(7GX}}H|lEdIC9s~ems82dNkOogv2g!A`od8(f6vi`YMp!6FOiZIw#-P}l zX>hoY?nj`%jpKiP2N(jvlz~Og91i<#};IU!}aZc6>o2NXPpz=F?0h(aw@8B#?ub0d()!0 zlm~C68dxcgL?K-dLdk%H1_bjniSzHa$Z(pyuntdCowL~oq?@qxh;xEZs%Sons>f8? zI~JM>H1{Df$v4ug0ec3?8IaojKf?l(%P-4mdu#bo{Akb=!X>uB8u))tXm}+_`C8Q_q=*giA;qBOHI$fHQ>epG{^n;ZhS=+J}UpXVc(r z*4XFL9sSbFV9rM3%|S9t6Z)@#J_>wE18~_E*wO*%nSo)pl$cnNxCji^!0C%W3@P|Z zFfcQ2!xpf#<``=7;3_XDc|fvJT^f*<3?Ms`cE`0nt=DC?pftEoX;^ME)bx02f$bo= zsMA9s#q<_D+872dGcs`awUqQgLwqb1(2uNL&DPhEn{}C&Cvs&%v!n>qY}+gvT}(85;w3TX^x`Zc+*) z{uQ=a`k2@f#`&fD12jLY0oTEuP}?EE;o?S}V+$Vx2Em6rqkvxDg=-nqIPGQp zKG8t7k(;Mrx!Ywo!w!NKggKn%LI$|)Ynt3u0uXx!H4Q7pFa=!m9QU4m(&ZV@PZ+pu ze0f~u%>;fQiSP6)lITkuj9wi2r{{ZFn@t~2w9NwFb!|RSKtJrh1JXS{xYSCMtI3br zDk}_256T5~XKyMEVTR4%Q$f0oaiLV`)(lb>;YMHjLXOG*!80R;@hjJwa<9Nlu!^Jb zAF4RwDFpv~vFU|lWTPAnm#+iTc|VgB)k%MVcjv*NCk!x2>Q18OxwJ(uI>`4!;G-os zndO%N>s_#<6o4^uHx*ncpd!eb@E$8b$O}krD9wX11~3V_pCEn?Y{5APpynBW8k8w` zKU|a}b$3JE5U2|(SLkqG>*IC-AO(Q@DA)>-3chRzP|^#+s?E`(-wdv0jTwmrC-Ia7 zFpnOn5ib)_02BwpzRiXt-N0Ups`K(q%2H{c(=gYD3}+3OL@(a@=-y6gRP_4qXI3?Ut?T5RmTVBY1>_`9^z@PVN@T5<@6TFcuHbu`wT=WcT zOop8vYp^FY8*G&}u_emh*dWN7w#fC{3+0Qm?VxLKJ9881CO2blu5IMgMqBdJ@q8s{ z*+Xq}ZAnkdp1JnGKT#{W>UL7ly=VoYV)=^>{F3nVixcsFA>pOUu=~MF9j>Y@>z6_U z!q%74Mm{j~pN*j!&=$ta(n&w@7!>~bQVebsdS4o=dj&3!GQhG`@h^jd^kvYi!6iNp z3;j|y%!(|%B21~x!M_SCYbS!<`JLJar&)oHe`(y?Ksmz7$R$C)L=6Qm#DELq1i;1j z@{ildy=xj10bG{0wUE-4B89434hfUD%yks`lS^>!A8aG+pUYv+q~!uGIBAq_G3VFn~PYPWd4X zG9;%TSQgol2X7oR=xl&I8_N3Jb@fT3&G3g6wlm&M5_RCz&4RT-)5L;SwJQbbRV9@b5#0U?S(@0dGDL9ch6=LqB1IAI4J!RwmIl}NeVFTH#^s@V_s zAhcbScNA?9BSIGyqT7wmeO^}Km;Ua1KxW_grZB97IkyP3#%935yK*kXe(+Zh9_X(= zATx=I9(9OL#F${QD*lqH*gm5bjh!#6tIw!Zpy`;`%GyB*Rj}Amxa#~#%VEf3&+W3z zId`B3h0=UZ^I|@iH*~#i@t^BVIL*6Z-`HsjYxvs!lWmvfogP|Yz8GRZ7hhHoVl&#p z?8M>c2^(~Vh!>sK`Zc7;kPi41UY1$RpKl21QK3sWsi@a%kzkz&zn8NB*Djov`e1z3*kIY@i@XdT?kPaoh+!0(MVz z4^6EA=TuB**jA7MfHw?=FIB(*OrLtJpen<3ywzg6_@z6r7ugyxxcRY%kSK%0VLHzq@=Mc%*Iq57X8MGGzM4qg2l|ay=TI>|VOHHN z+#~F(`w(vy%3mu~Pks&V8AC7#Z@!kGcqW)?dF{!_7vbX+K4~``s+tD8+Yh%~r|fth zw$|ny>8fW>vQ2)eQn13gdC6FkhJc zkb*2xIAbQ9oB|%e|KnN=|KGas2j<&hvpH}^fe&JIw)BUYa-83iGZlU18FAw2Ce?@d z{rNJp0=+&2w{4juWhdNzxw*gzsHYwnPGoZf)-|H(r!iGuG zBDe^h^#WN(WRv$xi-qTR-ZTD6^M_tG?8%$V-%+}{6B*+>k@%#1S!TN6m@^O;O|yl# zW*}n%l-Pu;J9VSW|Eqksw7O`HrLxBgz8d+0?)CKeo&RZ79P?k$AXnL6FLu1bBjZf> zR?AMl>SCjB0S z-aw9149To{55QG5%L=GGbGOobEdh-g-EhH-44>ab)@;~A#Fw^N)E7|}IQ|J={3+Sd z@7x?;0o`HlEgofcxd86|%O0vZ@J}*)lwlTkIQR90VHj``40Q;P;lh9?=vDcnBhB47 ze}tbFYb`7c8Dru!MV+e!qtiD|E3by(0;H(&Ya$D}alr^b8hW>oKn91KO`UtU5IJt2 zcC!4zo)L_>n>N4U`J0zh9XIQJs(~5ZbQtGT^u-?GEPO;Wm3#fR(dB{t#6$QhC=@-?*gULt!5ks%QU>s!JfV|u% z&b?Cj_(dwOqQKnEn)mvto%?!5;C+@a`FHsT&d+r{+;AMuxC+R_K9!`0fq2cyR>0OO zG-epDFv)a>nM|?HNB6#F#@63)c6=BMlS0F+-AXHTefKR3cj7Y;x@be}i=+*_6` z=)SU`K4A;YvUFGFADII*k+1ZR=-u`kf`KOTMxNVdiMdGKS5fd)Jl~D@JkL1d;^k5D zSFdY%`FdI5`{$Z_D0W#-*a)0=z{7+0HOKFS4bJUx@y~gvDHR11JSJZ4Aw=S^ctEAv zN;I~bCN-y?AxrxPU{|V4;J_g`SC;k+Byh6yXW*^K^I7;t8gPNb9}a6`IJjihuY?N= z&sKNZ7g&+_az7GV;FBTXpDrF~hR?wKE=xiFfqn$=weUY&{xrCjM>ych82RoU`Lf^e zckkxFvSA?t(aS>=gN$mjiBugo8_W+RoPUJ}`;{9;`_tjD&wycj!QY zN6u;_W}QOfNN}XS>xQ@YLUVTjR($pJCY8edpXV=5llmkCZedVo6U-tFddN^FHpSZ+ zUSIZEZ>TaVEV*`p{S(XRXN|76^R|3qQMfS|ma6choCWsL&*tBz={*+CWx0(ZPJ);` zC%W>3&ur_W)TK$Ge1R}(Pa$YD1GCVbS2Zpf6cnV>Je)>%ARR6Swi8?`5<(d?oQH#X zHUE{zHidL30Pe{FC!EOyW8nJ;&nr)}Eu^07CYrFRm#x(l4Z(5RrH9vo+bp%ya%Nil zs^N}L?X(GwvI+40I%ghz#}Q56*)X@B5^SEoP6Kf+ z5qd$a9USyahX-Y_BG%^OF`s&n87)9v!dvx8j-_zItcAe9RfPpsLLi*zFfXVeGuZ*O zOeHDG6vbh!tPaBmY8Wcc#^~-!&$f^;mR8Zd|RO3Oogv?q`#Sb&-WlrGC{fW-N2A^9WF-XwX77Q7$3-;AX|drc>#Q) zlyeU!jEr#hffJd-+l)!e|PB=Wo|hv zi-PZGM#IM|!lscA3J!s?i$Oj`nmzzHywf7A+nWg%qj&ah%Z@3{YvSNy@NB!nzS|P- zazDNed=juBEv2n@BMQ+memVvFX?mxH_EI!>sR$MOMq-1oZr{l{@5h0|2zbJinEowR zVuW6XXB9k?n1$yp5QqF$u7+m`@yWFU6F5gb||jwR`I#J-;f z_pl)hLa2v4HRMG?DETeCmW5b64zZIVG(aeUFdqUmi}IoDbrU$r!1HSm@^cWo0-odG z&i4E#mp_TXeof%WZvsNc6Ap$`+F1*7Ei?X@JuZ9VIMZVjCT35Zn7uS-c`g#t-c8At zmLS#-VYm+Liod0oSHOtv@b)%v(Wx9R|8zNwN_hU=QKk7$Al9)0vD5wl_AH1WejKqg z|JQ){dnV97K$;tf+ktaktc4Jr#=uDjkPW#|S`#P-;`3)szPHTG@OA|Q2MB|NPD5$c zVtv(OpntA50rxUB0v8Q6K;*Xr*^?)`E{|rt@b-T_EE|tu?`= zMeTwf+l$cNx^%I25m5RQErr&ux9z=&OD}?6X>E;yZBGQvAp!D#C)oSD-~V~O=lSwH zlbLg7d*_{ZX5MYi$1du97uDEBVUy5J8SHUoNE>Gr%-XZD*0{2`(p~11vq+=|kvPSN z#D#Wy>fh(U4ai{X7aZkf z6{XPWKvkt)RMHlah0ep^xu?=1n&_}U(gTjlFdG4`3d)$EjPRedU^7_@%F<`nuP~Lx zSDMP|E2H-6>pvaS{JyjeUv-yUy^=l9^D^YOe2{&QfI`_Rz&e26Wg92%Qyg@OYn zbFdsUbUv>%l&^(27h1mJRiEqJlDuG)3xCVm_tL^tsYY zGfK!HObaXnXhE3WHl7q5=rIEx=97YuzJn7A8i4nrV?JdIh4-c?^8ktpwZZ!VQ!Yiy ziYBN-HC7eJ^SkNUwNEq)EGx8sbC<=@4`#6Dp@@MGA#+4cm^wOQ=Qa z5<9hsfy4k5$YRhUq(SplkiHkfA_x@_*p?J4)*=l-7>2PVmPJBPK^Vt}ni5ORq6*$7 zz*_>m1IDg?7>Q3y0dGVgHi$NAJ9w7yO zkbg8=Zbg6vXo-h8&WrxfN+E4j0QJZGih8ECgw74;418E?B9~#qwMgujGI(5v#C+i^ zg;qmqAH4O$<9g9#`Am90hqP4%I3#UMhBgG2J#J63mWu&nQmLvXfu~`OEJ>t2`TFH~ z4X6N?-!8M?6=#hrRnHk`D;FI(T&#tGJ9AU39M~4k;Ffvo^S@G zz8Heo#So%f9D00YHOFuP?>u35NVKpiBnHodRFWdZn!rO4UQCUP{6I^Wz^DhappA40 zFC4oN@(^`z2Q=Y?z_ws8wB+>v{v@C~3)k#Kt zsqL;gSbx{t7j%rLN^Ypy+Jdwijuxe1A#se_K4WA`sfN4TMvMLaJS%>e=ko4Jv{8CP z6&B-sm#!mBi?;?DeV#3k$A+RyM&5yFG1Ql7Rl^&`rYSjKM`Eb|5T9Jq%|8SHJTjC3 zBk1?V!+#>Ym+9gkN4gYiyp4udk=P;0#h8&qYgiK!C)@oAkWh%(L-D~ETLM@-GKj?* zzfAl|V)P*;q)MV+7OXm5k_Y3X5*DWn4Y~99rKs7B+SP#Q;}G6FfY`Kf#Ht|uIfU;Z zG(zZr@IHiD(TJV49kJIF$b_KOfH!4DKxQo;$X~Hii}o@A@dZi4QH^9;KdncsD9npU zk8mmhgIno=S@lK8v_po)$qSM0hDRHe{+6mjt{&jD!hk%C-2E@QN}8 z|01*~Gn5@tIwx#B^jc-3#>o|kG&w0ObKCC)vS#Zi;&u~qJ1stAS0Z*^^?=8F_tc_B~k6S1K zE0FGV(&AfwYE&j=0Sm<=G6_=p%@E?ZG zxb+7SD>#zWG!_>L-Y84VnIUYfG5_wu8p(}e-f3W5gnObBmGu%?45}8jmI3nW7dA#G zW!xNLxLR0&$NaKnrVEHdyfBi^RkbmmRCL@X7ial397?0bPN6+|_LwAiqQ!HBc*Mg( zSWF80(#dPkCM<;981tA)STq6e`vH>um{1*)gw4VmF$FkB_%SA9Z20h_j}j_G!#`UX z6TLUJHQT$pDz}T5%-Uu)~8ZMRhxGC|F@YdK2yi)k**c|+UfMesZ zB#etqnpF{~Xk|S2%F>~qvOs<-?Dx5!Uysz}w;}Q55FA_L{|t%l{1%2o9#yc^v_N{R zdNP44S6CmbWlsihx`Ny65-N7ars?gso8^WmSH=d$Q-Yw|fUU{EYq%?`*6{j=k^az1 z;NpaT#m)=)*NCR|-V#bYE9Ar(@aw_@ar(UXMxFywM(O8WDh(z6HiXg-IkBEz|Ghil zJ?+ofupgHDS-%{XNtV;ZmmEXlzlCFQmY9kW9ndhe90=AQAMn2J7hYN(D`?cQ_=GS` zJ(v1EPIyk8g|7+6)U)t6f=4}e+_hm@J!$KP^T%DXJp}`3-H%%fU|1guDdQHDzcwsu z=)QCCb_^S#b*+EDyQ(;FLuOUAB=Q08S3c5b)L`2+l_}tLo+K2(woq2ANr2o}2S=YB zyv9h0slun@CgCi>Gj2BS7INY|J^_CsY>(GQ3&VIaJ0&cu z*M&4PvJ$su39a!-_#@$8@zcgk1=2S*VI9&^;shZfA;qXVm1;!dx|2w+XrVY0DPfYK395T0tk-a=V2LCDDWUWU_aw#QeZs1w>B~3y z2^U394Rt6=&Au*{kLB(wOG)3}ct%2v3fNz}C3Zh^VXZh81+nyULF;s`0%oLDVz^bU zv8RycrW+XsTw!p^dYl38ufr()SJzedbZ!wWt&75N(iHpUVHvl*6=gY{8ZOkM!a&rp zE(6|ufv?<1H(K)h;a}Z1T7U14+~v?A{qOy%t&e}S1z_9Suc{dj6g&xL zwI|f)JQ`3m|Y9MuWOp|`oduG}-;{9Ein-VwX17A<8s)Ud*CB7r9 zOGz42=Oc)RH4cDY6dF?Us6{@(Io5~|2v}1(uF!`xHrpQrqvjI$>u%ui#fd_tCPzET z=W{m#%OJB-c2&y)DObe+Xfu3BuYZcnWuwrdSvuxvAJ))~#x^C?dqPOk#${g{!LVnR znicS7h3~3c4)KGqzJ7u;qy*-F8|=*QKsW;-Qdq8y!!^Q2?F2mM*a7V+jOPds=%DMo~;X%iVZDhCBVZ7KunQW6fPO{J>sLRZ>;$e2DT zY#u)qhSM^BLdZGYI8I|5@m>~w89xbsC5)Y*r#6m1He*6KB@1Cf!Uu%nj5Sb6D+wQE z6fU8}B&larIzW19^%d=O@3QT2AqQRnVKS1OANQ?&u3RRG}p=Bl;#_w&mWg6 zR6FF#^W^B-8#oT{;^lJk)|eotf^QcDkVe%OEk-DRcSh)=SKJUgoC=*Dk0n0slRWi#Qz zy5;zM!25Z7!243WuqgZ9lIPVUo4#q1XXrZNZ1Z7Hj>*-8)86O8eX{;>=D%?&=lI?T z`OnQGPmqO}s9$5zHQDmig<@L{cim0j+Or;*ktvF7VIZ5ctND)pF+@6PXQ6L;)AIfT zntp=FE3i{IklvyDKQ}A|aGlee^dbc~J{>&XNLdR!--fX>&<5LL5;aI}m6xe)f0%Q<5$m!qwSFwe`VyOL(g841Dq9Ju??sG!=1`w zW1?*Uu&W|e0)fCFwM48|aN*p8tznxd3F~sF-`~_$x%q?mwf)aUqwLDRgkHK*^PX98 zG1is0v0Fi(uiQ*@PnCbsZdO~%@R>z@iF=xx`wl7DuCZlUui|%^Xn_73cM|ujJ8wrO zmjg`KxWa(n>w_s*RFCPI z-$kPEK`Pc%)gl8Bh44wKNg2a^?khD>_bf?{EYxjo^7nh@W2>chv8DG@OSmw1l2H*{ zII1w=?z|=3@Q9J?2d3@iKrd`aN(6jlJ3>1G4CrA%$MiVSLq#cu&J%2t*~o9PY=*N- zKI1&Sd2;DeymV0#lY5>_u+U*t6=sytn-^oM&l0WX9Z+r8B0{jcDl|b#at;Icw;6+c zvc;tDr9g4FR(uT3-hj974v&R^oh6Og1KxK6)aK~YP|bY2V3B?Rf$pK!vY=wvo8Z%L zjwqwFOL17qzKVml3LYm45l3aTO}ClmDLBlrZfCH0+VgNUUdwg! zb;Tq4?DEUf=MFR;goDs>F)`%I6Z$7Z{BrxPd=3P_{RG_*AH-8ZB{wYdY@lVgUVBpE z`5fsBNnTnZ>(Q`FHY85diF2qWRROPmXw62&M7=nNUbC(XbVx+%K-!p+cw4!Mqn6mh z^wFRe1MSgW^QD-(^aCT6W{6EX{mxNsEko^TDx54vXX`_+6*#xq{fOj{@25(9a8mXWLLoTMs@x&Y_HF1m+ zO+4#D87|j%{V4joepC2?r{?rp!na9D9b+4&j4(G< z8rZs&K~7vZvfYg)+6VHFVyH9aD9x?tXQK5_{L$|0fya-cOnd3T+M}b5M?vFvyGEOy z5d<(oUf#PE{dd#pBQE#Dr|=}&WfE0L^TglX)TC5bq!>_YUBaW&bhtx!d79Ra74};b zj{f`VO}TwQe{?}_1Z^KkIclFY`*z~d%1uNeN*QJk#2(edp-PC<(i zgPI0|#&^ql{g%z{erSO@+Im&HsT|rI{!oNx--nApQ(_;u{UOe@5A=U{-c?5TGAPkR^&&7Pfd0#oMn{}~-uir55+B8nHD!mJ#CIJaylS_V zC4?h`-6S?RDrx2U%~t!JA|EuPY?ByLO$u!)YiI^TiujWQWvRM0mSOG2xzT(&H@b^Z zVz2KSuW6$A`Kv>lGPv4ett|BXy3((MJ4?c9x~UFSs*eGm|AX%*`LgqCtVz5~RI(>L za^=E{vH>yrnEe)-gv2MRkKHms{4B(dNhPi?`a{Q}>_X>**2M90KRb0F_k%Qf9hzhk z%c@_M?mBQ15N{Gq)jvpC>z;v05@{6xnO|+nHgF105<1*&(x>>g`jN00mVTojHC&4i zc)#|)3X7c5Jpvo$bC7yw(>s#=!A7!yKl21>L}Q>_`B34*;Y2;{XY1;q5ZP60Aimq0 zXhvdDb-+7e7=dI%v}c_Pd|t&z+Lp4KTril7zbth)E=!&JVJB_;T`}!^c`r9^vBXw^ zO3;{Mk`xK&u|8G|pi+r7Hb{|1gNwF9w>E>)H32raABP&CqiB)A3KwkMK2l^k0JjU` zRt0sQ(vyla6k+E{&L031LHE94HkkJqEB9der>;2nDB)glk%6E_vfKjRrlD^4Wd%Av z3UG`&2Dm&sFhQo!p+<@9pyZ$i(RI}{e~a-xQZd^JOf+VQ=#{2^mAfcWq$)Ba00*mm_ge*Nqb3S)B8O+0Z-I3Q@V|DvCH$ofqeL2*fm%80f7G$=r;kf}F9^&Pw$_eA{@GXQ%m>CWhv zE6$rsP+u6Zr!#yiy`8+w2lf&-SX)uU%n|}!zLgY6wgtQyK1ZEP+^Be#)&gXKI)8%!a`)dAROny07Z2OYab^-9B*s!xY$B09C+;{NrlETvjXdj71EH5F=H5(CJ2)9idsA@?U-kYVdry^}i$?fKVw^VvkllAzJ7msK;9rq*%7KKtk zKd!8Nz+r>kGxsy8CnwtWnS^pRx&Lo5VIM-RiMD07Wh*Y)>S1p3z&cnYt=Y7)pQhJ5 zL9~MQsx|@*83q}f)Uub@MMd;D*gu2(=sYmb)|QNT4-UQz|8E5UUmJX>9FEAqOJL9# zcpQOZ?QT#oO&i`-N^vv?tWZR`XbLw=wgjX#+eUPbhd+CQdXnNgq%0ia$4p}G{VP?g z7|#aTUc0o>R4A&LN2|VT#yMN0Wu}#)ol#_LkxERDZdluoA?Kh})^Wv!bcqv8X|Cqe zQtI;4k`X87ZIv{UTcz+wg&%CIxx1xV1&T~kqZ(3&q=|SMBR3{!wfjt3Se8qeQ?Y}Nwi!T5M+*q^YJhX(xKvI`+7fMtZgo_~^M`I; zT(2AGn15QjIN>Y=Vxm56hlJ@S2D>G7YY(-=R+@WS>d}z@pM(F`g8w&y|6=feKr`Z< z7Z~wY2BrrY#DF%@CgxeB8*?nucMz^+O)j%YKhII~nmm+#yuDn6-AH4RG~pIW1^Mbk z!7RG6!1Nf<7)k}RDcPP{npP4DJZ2y_6$Dp`*IRX>-K-mc@xPGUZ zzJTg+F4}X`4Tkt!yhmUQ5-}^J6->hGgoOo9sUr)^2M#{2=Bir0i$~fdj=pv9FJLV9 z3qKc3Uf9qYxS_I61MRhpo705fMdJH|U=dC~*N!x!8aYPX=SS(`VAx{B6F!s<1VXf^ zA{wNDT>3A1-5RdfO|)hdh}>bVjOY;_Gsh{AO4dh3Z9N9w9eBnJ;J~Ij6`nX*ny8c= zH5)sLGA%pMa?7F2J41GfKL_M}NVRP>b4f>gGiqU7;G)atS6Z%|oR3LE%q`!vrcNJ~d@=Zw0JwZ$}S;k?n8FZ|l3)_n) z*@wLo$jm_x#bAE|7H8-(NQMl+0c-*6558_y8zW9T0oc((Z+Te98gaD+cFhk)Mt2X^ z1gG04Y+Du7V#MDh8FvLV15qI0uyP}`@_m3#RzUl4BQ(z#ZaH5t^gEZD4Xs%Jiwz5g z66LagO8TAH5aA*tVUd0d>F0`#7QN8F4E85tG3jr^Gxb|kZQ%Q{I^dN)AtM>XX;%|$ zri@@C?YzQcs6}){mxf7CqEm7QZU}oz(!*WFi2Vk_(tAN!xg>n6y>na@?m?M;S5>h& zIa0ziDGAR;hCz5HgWuB>S{TNuIh-ee_8ZjERWujU6D{Fzu=mrC zK-#(Ornz`1AGrZ#_*|;^s$!}TPp3Imi(pnbp@(u>!d8^!bqQwVVpVPAanLQ8OYe?U zy@}Y4)m6nQEwHfOrN!04?$VgVIXd3l8ag-ho-mN7vm7k|2-fRuz%5oU6h1AD9fhl*@Ur0qGH=gPnwc-;yg;w^YdU<@stZ(U2)crf`s?i zCz4!hkH?87gzE0*PH-nYvz6A)lOBU|mNN!ojdG^*q(`s3+j+!eq`R9#4CS3_@RN#a zr~Ha(C8C3+{PL-ao|B$zWriJ!8kN1S5)rdh17PMoN+4jIa~<&%f$+1TGt{FAEg3+I z9`fzJx?pMp|2;DnehLJGS!tn;NVky_8O^VK*N9PKIzF+s$8Ulr4lofa_W1pJoOP+ zciw3y5GQjFnoGnQ_5&z4QP~+RXA;+Mh0Zq|f_IN9!{8mVtJ?uoeza-QGTN{ga`|Ac zW9=WgXhVvR`^#<~@QVw!NMs09SA^?bCr*2;?BKd`Q8)_Tx#n6s2~Bd9VUETuxB>YWk6Z7VICj8+!ZJ%k(&pz>a|G-)VX}F}m=W`FQ*7 zcr;!uhA0zUd0b2n-dB?RX*1sacQf9DUOBVICs}kfziX|9BPG6QJi8?QD-YV${wr4E5m9n)WCuI+5%cb;Vx=Ckeao zlrP)_019e#xD8sD8|S>|v4@6z)9iF#;P8You+hNMn)#xnF_L*2>uTg=J*+2?58VbK zFD~+){lxrspMsv;4*qf6X_$)qcBCI$m|O@H&3;ydU9$@7t`acgfx2Pz69=65?whd4 zS1Q>7O(g|uX|?hx*RflgwaZ5yh3}R#`$%%)F2S2d)9T7*&g;CPDEMulgeBF^b&{38ts_qnFLDliT zBVNRy`#WZK-2B4fjqh(RE?9zpm#3Y(mIRFsBBWnk(z-$?mxJuTFToHoRTk zyr}upxLP+EaXcCEe+HZ`%EL}R>{+BFk0BQ#aS*@;BC zVd%?WtbpGH7&~?XhOH|7rBMojrw))ZnDyt~WCGK)gi=Pgvby5;eqr_BxKD6}ZVT7N zEr$R5-SGpCa-gd`)I;TUH{09=H|11(FQuG4u=Hp@X#QiB#gdG4@1ZgM=2=pZ9EHZSz)5oF{MPCEQEGr}%V1^4f7z&fPRlgK-Goe%Tkjz8L z^n6VFBJGA?{hvtJbUbW_mz?pii_1JXm~YT(w9xiL>h^4HuiHM_9oaeRivR8g!p@60 zqT%NIw%&Zmw^h>fQ6SLN6@T#ukm)Nc!KiIV1E--YHv2qyP*nW#M=@;N$=oLZFd3)Obr%r|9bh-d~PX+>Pi6vp!4w z_1FjgA24%KaxYfFwXSRlNn5*I`v2U13zSecqt%4O)I%tGl=N{-}OcyCh#HR;^H}1{Bj|i@N zwb7-JGtl+DyO5i~X@j*73$leN<4wN))z-rP<-Y|*1tWBt@JDY(RhwmXe^bEQD+y%_ zvqEo5Js<@JyuV3;W8n-uQ8=|QVb+NE2Urp?qzvprV&*9vjCY=@DkehMoS>@&62Cr` z-=dt$aG4vT#9?KK>obMoJQ7QVvG=7Uw}Rk#yBpl6bicX3P=cpv3~{hy=h$ovxGoFx z@5{AUwS>%(f#;8I1C>d-ndH}Rzy_I%IBd3Es{(oG)l)?6M5?P=qUPv9en@r_=Wp4} zdh@soN^1l7D56UG7RswPN1kECh(SiY2)ZILO^R0~Mmz%Y8zUxxS00g381b{#p#2R| zEQ6@&Y$IGV2rol=;u$et(yO#hqxgbjJEhj@J}rD4F2F;{=crfL&x z_a}lIsA}trjVSHpJqqr!#2%^v-$~|`<2)m7lE}f($SIrtE}^PpMB6d-?-E)J_F!Vc;?Wl#h(B0@STBSHOA&hj!g>g#aM&`$#z8&>9p!<*2G=#VFbzZ?XM~4( z$_JhXeQ{(!mfUgETTRMngJnF`d@_@cZvI+*`5M#+i-?RtjJ6td*W&`Dww zCAZ=K*^++v-&7*H6VpJ~Foh8}N{m)ft2i9+Qh}`O0oN~X()0jGq)7a{nrQ&nOPU5I z`;%&{M`@I12jBzd2j(mrWNQZeY8Xy+D)=6e1>Fhi@I&V0PNo5+f@z=LVF!;{MgX*$ za6`g|gjUck*C%XFTkd*D{HJsWyy*&Q!b1=w?+l=s4`?=A+e@B~8;}?ua?Y^)=Mk4Z~0% zad~xWt6BJTakQNvgr(=X2{OUa3#_!2BQT?&i|M#oTrI1k_fhp2Hd37XgBy-j;NEEQ zB4|Nq@p1qpAVaO$B+3Dx&LEbS2C-zQMro6{i9INLx@%qHG^gU#)UtW}r>%RrFpkyG zB92(feggZu!nsv=YDtVeXAUq0O#rXk1*6xhKxW1{&zP8u?q(n&3PI$1 z=I=UTdJZf88t|r#5a3mG-&NudTN_Z+o_3RU@i{EI^tTav9MUHskoEgrGz5507NirN z74L!Q5|+fR)KCIg41WTRO2^Hw9l-X7Q4Oa+EFg!6=u$LLP$1yF2Kh)l;h-AS(ABEI zVop&@G#Wn-E8YLyRKVL7Z0XSdwWZU+mIP?2USSencCZFyzxjfLH2czjnr$5>BQw$V ztAzB9K$WM#kvJ>x2VuS&%y-ahgZcH4|A5j&Tvv zRvf0ZqxogS1dw-z#{^jhCJ&ZW0-az8f$bBFR^mG&WV7IBh2^$S z@ehK2`8;sbeiG#9?}bm7FCX*BAi1=b?3W?8U(g zuo-tJ2xnH7R1z;j;+@QRvcRM8yE|z$q`w4D#C(qNB+4VXVQ)J;8Npd**b5Hi!Scya z=6C>U^P&AKLr80c`0|h*&h}Bvfu5`Yi?iET3eT=e!Iy>C;s2k<+E&RZ`*(pu8w^cE z*_en9!8M!D1Gk%r(Wk17=>Cv49$c_x5&V&mK^(7 z{Jp)ZWh*Gjm#tguGOC5n)rpZvA69KzTgsoV`PM=639HpY|LOvKw=m@q{g~QM zz?Vwv-~--WpGd-|3FCy#kI1R-hJ@!HStchF%5cHED9E#kHF17#j&HB@05BA*oO`9E z6)1bTi}CCYIVbJ4p^0;xkMl^Iw?oA@gNwDg@c3Y^=13nMdgVo&M^{07m^i$Kirk~O7|J@OmLJn-h%ra z1e9|lBKWDzYZo3}pGggk2zBd|wKqmcPI}-sxTJT(WdX*6T$ou5yusy>ZGf$xgq-yT zyDadB^OZw-Kt)(~5w87gZzLYtj`5U$?zoB*IwY>*PN}MvoPPAHt&-emGvv41^jJ72 zz2G3zp6TqA7@LuY+B<3D-MxL(yL&tF3D+K%bR91@AACXSdtoT5d2dmIYq|Y}gD->t z`gfZd*TFRiB+WgK)E37DQ64cwlq)--&gAj(@MTP?N)zaCpWxNMW7V@uj44 z;#c{9n z;OuDIp&G$)Xrr(Wj9Kuu%duBlWCU9`@OLn?VA;zD@c!8*ytM8ZNLch}7Jf$9{^(q)$1j|FG@bg^FN{1op8BgKjDIXQ`Rr=Mez69zpFRdR@nE+b z%dud$SPcMz_Q@yw<*|wQL*cE*s_j1y{!dVDTRn2j4PN51MmMQOBuyo^M`AkWZG3g( zoL-#e+UNvNggp{n%k|>%wHqQgn0iAdc1jy6B1Idc^u07q`Mrav zgXnK9Ggi%M^-#+3&Q=et%z}Rm+Nn<*Sv(T|Hi(3+e=e|p1SgW4*r&H4v_8VU-qF^h1t!SMK zWvz9QdOr?BzKWz$U}OHsU7b-Gtbq&<{dbK8MGK+I0+)eLtODLXYo2TV2F(mQb1qO0 zCB{(Mvkqhw->G16Es`Fbq|g}PO7RJa(bPNYB)O)3U5#6tF~y~rm`BQK_7(|sYZL9Q zPNba&J*3Yj;OjcTVN=$7b>_IcRpztL=Fr?*pZp1r2pa|ZR z%i@N-)bQKx3hrJ=UGOQm{lJK91ODiJ;n}|=*k=s!pwf63Hf54416!!iYZ*$1r;9@} zu&I)gRW0EhlWu@%MB-R2os@#c&P|8mh7ThB!NhUgRx{CxbCeRTKY~a6S@#wNqggIeR?{eRcc!cI=b61#!$u!|12}$7F)JA0_P-VlC4e* z3=6$ar(+~UKa*h}@;(Z7Ww5LdlX;mu_%o=CKx_`c6`x z>3-_>L1E{nE!ZQBdG@a|!tAFD?>?J?Ey6d?K7ccX37fUlA)ipTc@u6DzS=x3^srA} z$2Sdm8zq6Yn}I#E+7s|!gg@D}a8qT6J%jpfP&jVq@NB_v*HW#6LbAhz#|RHOCM0hg z{NKSh-72uNEvI>zYca2a2@m*%Hyv|ukKl1+j2l1vK3~bdXNzvC-+^=M!FRA=IOr)L z7HUZ5_N>h~@aj#fW||0Wo==wUv}w-g&r26)?;k}t1Q zGVnJ5{T1CPwuNi_-Www{SJ8xPQL4;#n6Cpgy(xUUMQg9&Vz?A;ad%WJTw@0L3H)&{ z;dhCm@Dp-#6-;q;yb(4LEJKrK05dz&Hm!&Fs=YR>YFaCX%lh5a#B&l`n|Emr^zt6u zdTl%w;>iLTgS010rn@u%`^zJj-4`TvPG3`^t%CbTQWwBYa2Ugo-Fs;euEf&hGV;T= z%H{eMZ%T!Z&#%k%;reahRPja=O1sMjA{`M^pZ`XRDY)#OlgjwzdySKSBGf4($5$8} zU$eNrAf1v;GKs@`zzN>ZBu91ANAN!4syTItNe<}-n_X(x4js7Vnc?#ir?1!U)!Y9*HzWZbA`{gbGl69tq;*&<>n;2x@-iPlr4i=ZC9x zq;3P$4TZX(XoU_Bv_HZNP*Q-B&B0cP2=XoG&wRnjL9|5l*?B1qNP8-^9R&-ywPMItD`ArLK;N5W@<;m;VCcpQe!@`+u6^ggp z$O2m{8AI2xNhS{ue`zeZVZW6$aeC($8i=+z+`Lh!0IDH+Z&1%J(1-96y^tP0z;<-xD zksE9aY{^ea?gf0{->CfrwE4LZ`J4rh6Ba&a$4SEZ=cZsz2z$OV{AWL5lJqMFy$42w zr=L%c^$q{;;uyVKB6&@Ia&cJr$MZ3GhH&Ni3EEhw#efX4ntKrxq%VT*?L~>wU_tVp z0w*8I8!H%U@<0H4sAdY@F1%86|140Ra=$k3Z=&qsR&wRg?|pliT&*QcaW3FuxpV-m zOXMyVVM8VF*fx^8R-{l>TceP%V}bpWFQpVu{M=rnq~Fai zRpaxKd`{~jbIip^KBM*L_~_Cbpl=W5M0X8O7mlVP$})g}?)9m9$Y~MPvzvd_e5eo8 zZ}!p5fj$QBw*Bgol@cPm%lE!*RBS=Odx{0sCb;8R)e-?3YimwRxJ3@$HM_Y)p4^PKE5L>}=-oD$Zvxw-7uPm6;lq+w8X{7W&9AY^H%i`*hsbvZ!2O4;%dL6*p_Rl~l;^x4F-D|KE`c@8f=tlUp}s6_ z=tw9l=)1BG>2LTWFcSX(Vm#*J$_Rtj1t*T&t{wEA^qT;LZwL2E%T!38l5uEd6gZ0c zy)8pEP4Lc!vcGiRD=h;MDglHJw;ZN((EEn}DlGp{`S0*g%WnjUdbU}KOb~wA2?z4u z>t~XaV!|E03){k$DK)H>ErpMd=$6sMag3&tW-6vPq+vkK2>dl-gSXnZpupRE^1(3sS_tauSslg)v%>1Ic+Ps zWGR*Vy=kYSTK(QHed-?Sju+e!&<-DW8~_I@*w%gb+a>n>g+<|=%o(_<1=1Bb<4boz z?DuX0?=@nHyI*1w<$a-HS`p)JK=HcxE`^n!LwrBj`=n4uw}J(?gL~Uq9<*VF@0lMz zYbtuHFH|=7%whAqGuiPJhcazW*LBMBnk~HPTmFiz7Hs2`oVyUlH^kfL7lzq#Z7gpR zF{-kaz-4O22r6Pa-tsN*x_)ngPwruvOHE;5?(Bw}$o00Urfw?z^~CZZqfyF*s*hY-il0>E1zY z5L=JK?NyXMd*I=t(>c24bgH|9D1 zK~7xstvllQQ!R=Q@Vg5oW(|5}#Csncdh%{Uyts~dNRKjqKDdS^bP4xmQ~-<2w#eWE zG@$wh``UTm=u*3I3boJLj#zSXhQmCXg~fZP;cj8~-spt2(j|%MffG*;7kFWch;s!p zBy=Njh0wlNi{}YH?o9xuZFp}+a&7Ae9ya{3>&!opnErp%BQ|Tn^h$~S1&&-!+3MJ7 zj^m0iH2b#PG&g+)TEA2u5_g;aYBKfW@V%z;-nbHd_{VV0O@&Dd({?wN&4LtwLa zh_dRpi%d5udo`7RSD~p_ZhEsXf#f~-oMMNxUf+j4uDW+h>_{KV;lEP{GsM1|A-jjS49HA zg{&V*`->EJfS}IoF9Ivn1+Z_t*~c=b-f&a9dl!rcWh1c(F7g2w*a&k+06FH{dK*nF zbL}!yXSYD}Cmh@2m-o>aYXF1Uhn-M%&RcH49If%uxBqIwK1w9uUN9LgbT|M(FegR$ zV+kODITkR-_$d3p9rWGh5MOi<^zC$vqOTgz7lb@GLgZ)fj1bUw*LoP?x(ihP^ullB z0e9R6_m>_`IPH@U=zQV*i5877+>3qk{_@_Kd$hiAPl{zG0bwx3w+%oTM?feD@w2|2 zMRv+3zloqIdttdc1dvy9W@iz1;av|EqAfho7mC~egTUfmTnu1HCjfzNGK)DA&zvaA z0x%}P1csQv}I($ZX5TayP9itKg>PpHgaX|_dQhj z^ulO2p_^1V)5+pjfJt4|5~5+}NZyjn=;1dWMB--l+<=`*#bX7OM$b!V}@cFzJ_*4nFor?{v@F9jf0@X2i-!O=vf&>0X z^Vfo#csRMK3tKL^sXHI8+=jqs{KyB`*is#Q)lN5{0!M!Ne|?gT08753M!umI{C=7} z2nj%JLt?BCG#0_b7QqL!$mv|?AI-T9T8%$)M36_0oW$@IEYcYH@|QAwZ+rOw*u4P@ zmgEQn;iMIvAmRHopywpqGKjG!VeB60HL4bz&Ae1V! zOm9ss6XBa?3>Q~(x<3rv$0vl3efosi;QZ^36K0tUYr@lHex$pPANzE{O_~zS8mIXt zhBz5w@|@@_2tKpzOVU;(hjC9NhZYLvxHB;lUb`r9b8D6mT|dQ+tsRSkeO~jV;C!4; zcfu9+63MFtzlek|293VM!FO^0^^R=`?UX?|ddLCiGno}|ZG>mpDYlK&b6!WeTl?7> zRq=?MT;P>j;QH=8mVqj`n~`hHgOAhEx9rih{nq9M4U_=%GVGfK)qTEf`1iusH*S01 zhns4X`P<&Z!x`4s%mpr#O5PqAo&ZPnWZP|!_EJlb7~+?4dWdCyJy;|oTxoDcLTjxz zhq!(PQ>MI=5EzLquK>YMBwgw{chkt7FY%JmE7S{u-G63KLr70L&3uC8Jg}DjN4=ihUEp z1JBC7K(N)%hl6G%1RAa*EV9s6jc7L!0_uc1F*LApg0mrZRaqN(CY&8HHQ|!m-U3)K z=Gr{{>8u=E_>nYPNfN;qK#mu+iQp`2@3_?EWZK4<-h@o&T5lkwJ z;2SSrLMd6W)E9wtP_ms9*1!HF@Eq4)Ux#hN(!Xs4J;nLIeUCpD4!!YKDpM-6hVs-v z&x&aH1_t?f;fOmNFwY>LEL|7S`n+AIgsS~nU}t=N|E`k!mKZ>A3MJzg^SjOQ&I^z1 zG>>&*U3zLq{}vRgW&G4+?5C*Lg4(tPlCDDTRHQR54Y2*M1T;;*T8QL~bVAjE6Z5}U zgNF%tx|5i`6U#9|P4KLMXA;AQRnP|zhu+B#foD=a?9Oxeop?+zKKAs%c>KsPe7@wB zOvJ8(cp*urgQji*VgnGSL;4kXR|N4~2s`eC@3Y|6bv9z3gs^)eVz-kR0yK*@Lf-c| zh0*fI<{cY3q@#rVw^MUYKM0;P5J-9Q`}R&cXE|bj{1al&K7?4;iqZTR zSHb6TgcskAD|>exKvsp=x7H)}b%;BD^Q-^AF>pKw;+H_&S<1j6p9j&|4V=~j znJy2dIiccjGbg`WW@h-lf`J2sK}zmJY1LwV)nbPKZ{9WmjcNosvH>E09>`ujIdpk6 zE62P4^^B7bE|;BrVL8v_d&`9w=S=>%+?`QmvgHb8MuW+*E97|#fvMOYXleip14G^9 H&K1T0A6N2` diff --git a/boards/px4/fmu-v6c/extras/px4_fmu-v6c_bootloader.bin b/boards/px4/fmu-v6c/extras/px4_fmu-v6c_bootloader.bin index 21cc353f8ac88793327fa90bd661923b7f37cffa..85f65a9822f2ee32ab75e030778a8498179a7158 100755 GIT binary patch delta 23643 zcmagG3tUvy7C5~3IcHvgGJxm^2xsPi0s}e<8fNA&GaOzTsCn~MjiNQAH!sG_~7Q+lq8Zi^O;RBTEzh zA34K|k+{K!#Ke9i&KW@Bs{YpAvX@(XSG-&%c5&yW9piK&rp`coUfT7?^R97s%OJ7M zkHjHRug8yCt2HQfuboDzwGa?OsoRerWmU=gBj+TP%k?=pbDtyUG(0aa#R9HJder;1 zgT%((Gmghf&r6zAU0>B=ofu7-L?v{pNj)zmL0Z>hlW2tZr2oG6ITjDTLmjaS%9DIj z-p>9{0-HL!Nc8iMlzsW@ltUL$=>TTBsn2MF?!wPI7+>2xP?AZ11)k2^rM}cM@kqW&q@Z|TstY=Os0OssPw&D5*{z4UMQ%DKU@IWcItxOAo@xjk8RB2!MMK zfSXI+pMv+N&cO3|shrG=$<*h7{PMf+Iy)px7)*c)A`}ow0a78{U@SBc`#%jr**_W+ zjZm&Ul{!*YNEWP~o_2e}VO)==WVlf)GE#G;aj&3QqY+J^XvH`R<631aLM)o4Zc3ky zSggAMwaj)A(`Vr!we*an)Si{p3|9&nsc}ZLs1E0_rDvtATvC|e1Sxw~vNA|~P6~Ou zgBPUsT(gKO%pwh?+o9Yg$iD>f1&A-?#z1Rbsd47BQWvEC3TeMWd;{Ve5R184XW{RH z^fM&<3~?XCeYxtE!4V(_n)&$e!ES^?IE0Z}xFlok!%Ih$z(VK6)Y5&9r>h(A_!viQ z?b8jX8xThj{pZGwy)m^X8yME`84@2jKC=N&zUfApzdHe+S1C#Wqw_F#-Ho!ZIblSr zsBlV`+wfUcA(^(la+LaeZ_IkcIkdm`sy96KNe#5Op;uk2D0WFGF^^RG0vbVDrgWs^ zeB%bl4tf6yb1u9j|6~dwM5KeI0TLXR4a)~hHZ1!t304)}(-biyir3pBo0IqqE8c;` z+fs%N*CBDQutA|^2MIYBh?gL3F0@h$tyBTd)n-=}hHeOF702w#CQ^(oE)zqB1vXlY zrspToo;+?*PCd$(n8N)^3cTQl&}3 zMM%u;zi<#Kzj+d8Dw~u}Dl@{F(0oCsT!F+C;UiVbQKu@M(y}d%vI=*hOrNW&Ft16*qg0m1xhhfX!(zdJGRx~i*-WRLZTU6N zh(+6Hc`czEWI{uRkk=g=uBD4qVql=~&d=oV&V#7QYNlEN1!pt+Y5Mm{W@1xA8d-Bv~m=Uxmes{gUf(EH_cqRG+%N(@&`(&D0!_sQTP;nkrl@biK!It3>RY0(+c zcLvgV`H`v?mjA_u#Ak$uqnFy>=x37e?SyoZmLstp-l95RXqd%M=F@pBK0m-D%ODqc z7UaZrJk&s*|JtwZn!wKtmpB0FzjYj1hV&li_;5<}zzug~eK8+V0%c!AVw}Vz|I`_^ zCm(WwQsJ#L+~V{7FuLJKT7DH@K&><5kTUzaw~XP3@_6TN;mYO__8%qxUI>m336&$Z zT|x#tF|Q=XR%;s4skWVhrC&ObTLMU$Uf>Efz5rykLX1R{yKr`l?RYCr!;>?NvnA~j zx~FF7Ne_x1=lX|)jG@L~tlvP3q&%*_)A*)jVCV5PJ9;$*+tXvK0Uak_-NuO(b~?_? zcr4V_4InrGtQ)1IBUrqDAmsfjI0EpL7QH@(2{r&6Q9b9L`mAShG}B3ozW%SE`(5sGDGNn;a8!cr3md*S!dM{bkQ)%F2yo** z2zG)b1X*%R$;_aPVXa&E-Mj*bGM+EyHM%MTEv^a_@h?cVMp}F}U8LK&(f7vSg-%tU^qGI$zbo zcv8_ZDhUa0d@M8R^shj)Dn;Fl8GBPuc{=8=3w-e4@k0IcS zANyg477zJFcU}|2Bab><>d*b@&6->?ESunt*HU7?5HUO}{$jtiL2qOEt4o*JxW^E; ze+d$^gwo+NRYUsO<_C*tQ6;=PT#wHSuHjtH6=^fj2ug2rsaZ-K9YX2*otUFneeVu= zzw~8P?*%6Ecb^>SFUx7P6&*$5IbqBQbKGW02jqc7ODJ4_bjbU*@cf8uyjD0gVg~LP z`r$cQ7^9goo)SYLTu)o6`ihN;FaeeGvYoV;EXnqec5gVZY?JNG??WrEY{=&+@s=QH zW|y4{$?7}*kR4714A4`&Z?Btd@Ul{MQxdG!*8`;g*#4GZ)y9zb+zEn4$|kB5vx$&v z=pTG{*jS*T`NG7JIEm^68EV}MA4Wal{o7)jVqJYQat zlCI!EU_LUG@065#nTspLcr?f%@|!2~!1xhL~;fxIpYt42+< zcLikpre>7obh3PeM~wjxkHAg$g=UZ-H-Oj`i3FqrDRTW&pKJqI z)`Jwu7E$7o0IFyB!R0S+AT23?aZe5`wXU-5w;r`!wZ82xhta*^8&=Hlry59W(28lx zU^82w8RRLaSbkXU_tz0eiAe#pC!% zZULzc0rAY(5cKwiU>|Sb)*dp^uAnynoFuO$)ppw*x)BSwm}oOM!~oF0`@5ReMFblu z@%m?ibJmF1qMsWnvBOWM8AufXW`!{+Ie3q-AZ0xMMR+l#c;se3Vy)J@i?87mZP(ol zv{ohjo-$s$(m&uX2N^?FO4-#-v!w}Y29|rRAHkMH7Oq^#XDhH%c$XbRrG9YqAM6PX zv9MJ)DJJy;A}r8inGZGr2&IBc7e~cNM0^nZI^|dlq8kxO37vSGWgiHJS{Cvrz%D}QT+xJ zK2J_+cqgvkW}+{mdYprVTW&b7TcMtD77$%9CdO@CgpIRt;t)E{dO_NSLf+SW z7o<9fcS8IIQZ|IVFT&G7!)%y80>oSZg2Y3C^PZJHG+dDOhV#hsl|UYe(SWdBpP4bW zbdQOF6QRR2r6}M{gU(0?PeUQn!Agh+J6JCKs2_#1g@9g*9}rTqwDxikQ|7^h9zXyf za=@0LGz7et0Ot-O4eXYs{dX5LH3xt|SOEMpPy)-zgrR>d=trasGU_sTr2%lUJmCGz zk2xK$fF&jaIMk0=vb?Ao8Gp4tWmZ<$=3C``#+*gA2pgz>Cd8Q|;k|3+ zVq3#)hkbS>C!VA=t!8L<_M%0$sFFxq!bD?aX^xQ;lvk5ZSL!$!T>wfjvUtEL76jEp{1hFZKJJn02u_epQF3tIc)2o3o)S%IhF|ciHe(Do) zxY!JgVdMizmN!h)C6L&16kREJgd{)p85~7YTsXCF&ex5Efy_%va7Gv79y%^ci+!>f z-7eeehI!Se8h2JNwNX7TN?16K)!YTq&}6BO(#DoBFcH{C>x5n7j7v$T`k1*o2@a78 ziY{e*RL;W^Q(AA+6cTW&j#;XcMne@DJzegTS$?)1;Hy5fhV!77j;z*fGcGwlcd$I9 zX-P{UF+od-m6}4-x>lHMcqYbjG>%__ za^^3jq&%@j%X9n%IMAR-PzOl8A<%UgyP9@Lnp49bDC?d+qGg_*8FAqd9V29nA3sT6 zvcZU0(3fZ;iKZm4s|Be@y&ONOXI{6pwp0FfH5O@%+d%$o1(I$BmClaw4;F3K++O>2 zgFHjm4&vzm_GB1c4VZg_j~bx8lTDw4D4y0mRQ7Y@?bT$vP12T{bq&@WjYVw9;IF&s z+dEgmxg$rR7qTYs_Vbcbd8&5^C@o08^x8$e`82(nC^2A(iE4|5B?i@&1DYbLEoG5Y zV)F7EIFX`3n~*oC)gtB1kaC-hAKHOKk(kpAM;R82_Yn5jpaFgm@Rs{oUJXi=swQZC zGqf&@7#?k**LKKb+9Ic4kd%3yim0{=5;IrE7J$MrO~kUZ&`Zesy9DvvJB?u(n}v-7 zdZ}tET_=MR%K}Bz1>tWKQ>n*;!i|XuI8sndGH78L)MP2r*B_BzMjTzt0La&>LsUCBj#^zA?+qTWU*+?dM zTRFSVfkR#)#IDm9V;!Ji-g+a;bKMk8&~SzLXUKgmM8tVmlomlfe7Jqoj5e4RTt&3ns6yIr_g=f#@`jFWy?l8{=jypr**2R`k+69>9cb5;=bX1UP z1qDJV)@?PCu1L3ELR!fCVEFX&8Cie8Vzdq z+6R+!EysL!`uKHmW}=NTcb_%mu_GQ(wwk*wt9oV@tYg;6L|V24 zl$%*bT@qVx>Ob8xCDw=yN!HtLHRK9O+_U z_J3=Ynub;?0COH`j$CID_T^4q@WE#l>pn_Y(YrYgWmo(q;_}tnLng%~jVtHbP6gdo zvCb?S>59K-*NrSK!RO}oB<*Z$?Aae3(J{OPbLXU7d(^gj)28k)gTu6vsUk z@=o#_f#wyUob&l$J1Go#4}rKB#)=q}YK1_sBsF#s(E-HHVEF$pB#kO2C~6iRWp@Z$vF5%(#3ak3gykW}*SlzET1WHeLB# zo7XZRCyF$yH;U^W==RR1SBN|&^5F6Sd15?P5PBX9?1Bkd(R+s82=OkMuEFPL4KQd} zl|)(M5Obe#Hn+aw`8d%UEpsxScp#pTx7ati>zFj6>XZKq;*+b$3u)A{YdSmw`tl$eL+mlNp8Tx|?5dV1(?g^>3& z9HkCOj~HO7YCxYwV|}KR(nmRw{(=i-oO7M(MRBKkjcDI9#%?pRJ`>-CMLR9mf7yPf z=L{V!`0nNGWXxv*4erOEdGDD!ZUWqUZ7B0y7io{uk8q)J_P&b4P!Gw|r`>tv@Ts0t zXsEob+kvLHS`9G&RV)z9SkPaEydMQ#bR)gJukcfL=$3ojvC%Xolp4|Tb-tc$9bM6Hv@i^MWi)#7k)!(|Qah&Vh#>kVxwJAD$ zT2S4mwU39k#~<#!)*-j|Wgjl@mecmWjKlVE)9#EuT(OoIP$>PhKK8J#Oh zB^g$(fn^kFH2^xl#+ZGGS9nIDgRNzvF*0SqzRiPQ33=}fyxS8AwEy$KYe4gqE{}hr zcRjrsp4Wu8lr^jI?)Rie)UeG2k~rF@swM1m1(YGov%ECPgv834khcSr8ey&3%k2u> zrnbdc7bw{YbKPhRKciQX52om{?!uAtB$|cA%A>kzyHX?K=oHXAPAM4yEWKEw49nJ< zfP_Tas*iKENx9njCtrn57DH#7ASTaoB7Xjk3jL%=>^UNjI>6415iW zT!Q~jR}zbS5u&UIMRWi_5x3uXZbI`ONoF8GZH2hiO{f`Z(=B*M$m@_u91!^0dlb^3CiL_=X(j(a$VShks2TF}asXt0z)qsgX^`mrl-$9R6hU?oE ze{Ne=Qr2CZcurF1!TxK*x&=~16*Zu`HNiyfBqt{aonjmT7)}d$POARVfi1U^w4=Le z`NKrYp9uz28|JLzOQi^yUzGVkc!taM_95ZPneTfQION@F9rB-P&0PBmh^o_zR`eFc z9$E{cum)yi=!#yN#$pxD?;aWhLa`=u^`X`GDyTLkN1FG+IX)jo9rBLzslzFG@}X^X zeQ7gQPtplcd0C)e1LS!*d#q}0G`Pri$@d5Tg+9Q&ZziuTb8KNyBXi?Rq7yg;g+O;}B z)qLq`Hj2-9%J0qdJyxkx{=~ zA~l_pqVhNqtpX%mbsC<@`#kJx+frm46YxsGT2QUr4*%Z@zVJZEyCw8OX<1+2QwVhB ze(!Am#$t-6d64F!Op-Mb^CoLhcX~DTG}1-+s9{Mtk1QFvl(BoNWw4zaEuxxPUUi`n zPuL(WG%gYCj3RS`RAgLUy`mRG&VH$+>Z%KINn?y@9gU}?)J3NxLrjvvA+cJA6r}}S zMJ&$QDNW5+=t+(B@U&MNI`dZ-(p40b<+&FW+;m6FuaYt3&24>jx`TUk#(t~)s*NDR zRVxieX7+QHNRK=5RIiJx3=1KP{!}_=x~}pZ@V&uf6H4=Yr}pn(HjKz^Ir}Su-n|lM zo4}gIQ#5D23K}gmn@D+AtwFB<$3652_>$z2h2Q|I;60DL5BiUwJfr;<<|-D$ahBe{ zxEM4_%y{yz4F5-k|JC9DVc~xbFtBKe=&Xry0^C>ThQNts*xa!tXQkY^XJPxw2KSYu zxf&argVK+|ZU8)pHA`%iSyC@FOPVCXB)ZbT_aVfl7AHX|;Ymw^eMIT7qCJZUs?E2~ zt4t`-iuQbM-&zbIUn_=igc)h)FN!bOv#3V52gY?J2nYH8r@^B@GWxyU&BTu+@ZQ@fxi9DU;N&02Ly)CowK_clwYOyfXzt8PjA5QBk_ZNT!+#x zw1SrpOM_mG5~D%dhysH(7Jmi{7%V7z3k+^SiMAnq?Ro>W!8D z2Ayrc?E_QB`JZfpRbYxn&zKmhuqnY&2-6mcxsOy#1qGGVk_N{e1D^%&(?g%RW7+TB zN&G+DaZO~iemg`o3}9f=`n`2vx+YEp#K~i-@N7|A10`ja>>dwk0M~<}IPKBL)c>b=OxSSwy>~Uh|%mO`Xp0Knu2i!?M z4Uq}_$$u48)C}knu=oH_=Rl{r1&gneQELf)W1Z4~Ys^+KM+N^2%{+jHj1`No1!eqI zP=>_9QAH^?K#D#LPAE>F=r)?C$`F48~1tklg2Z3b$U}VoHvY@DxhI(~!O&oNQ!q)kD3pX-jB<`a0F6H|>c1~OdggsMVy z6J=re(&QZ`r87>#DM-SJD8uWDP4Ic21B4+;CSl=>`|J`B(y7X-!jvY!@%OQq??>q$ zwo-LOECZdPj~oLdX6S9^=7{ML4@8#zC}la00bH2VTgg%AL5Z1i(scX0xuEx4U7^P< zf;_Sj+#g9mK%L=OOY~jWKBq6$;9p!EXyKWmoX8!rSE!;m-tbc_IEmm^O3SkRm^E zsiZEkl~{a7_;ltdJVR)ksmG5Cc$QYXe4q$mm_6{*i`+{^d~9Q4;~rCT>na-!lr+kW z#f5@-Rt`1^&&-;r{Rn9Mj!WiYBg&yp2e`B(boNx!z^=9(B`G6>?`QRl+}Hm`n9_*~ z0(n>^@l`QGZkgbkojbG)W&c}3JH~gAq}4*)gB*A_-1Fc#W%|Gr+x{LEEj;;P$>P5b z5YsT@$wDFT-ano-@Vp27#`1W^lO!kl7y;f4Jb8NQk21+nrgi{n^Pq860BH$^$^sk+ zOM^2AE0d4JV=YM^3JG(P@fBh6oD}RjI&Y4Qvi~ErzgiFC1+!LW5evDzLl| zI!rKNQ6Ukik`NXFH{po|+d?2jp0eOc3NfB!gtY{h!JVqLs%Zmo%!QSVM+3Bi#1}$b zHP*{70*+Ua_g6zi)rPd(lPs?lE2u?W|O?MM1Yt0_o1>httr->{s-#tj=0cj|gf4!tCyfhfj9-ZxrE zOspTuCZ<#qK5f<8XmZ#B)I`Lu7XVR%1x^VIfyD%1ql5$l-jmHpG&M_28>#^TgyQ)z z<6`?2yshEgY6lzib_5EgG*s1$r|z$Q(DR>g{^&_!J@t&ocIQYd(_c)TqGq365)^Y;}xU8 zy9SBff^U8{zAj`en2lS7=NBxC-|v_6Vgt%f>D*A=)N>{}u>($BLSO-h|14-1rYN2P z4*_t@5DFJ&-~wUg!VLR>_g}z3!3`u}ga4fVpMi~n&LRYUUmZ(KLGOehV+Do=z9ee! zHd%0-*!rTUgMAkmW(6=z#>H&`Mv}wTA*JAd!0rTN(b*A zZmE^4>2WhKw}dGa1|y1S;})!s0?tXpc_x%&wjy!#A6!#u1nYVWoLwbv zq=pCfrq66fiAjc_caiY$!}n0kN5X3l|A|uhh2I`tkDnA)KJvPZ`3Nb?g&~io;7%d? z(PEq{JoD%n`)U7whm(E1w@{wEg&)S(@eg;#!m{T0z=l3na~Z!+_SuLaxEOWf`Z}Aj zc?Ia*2?|biA`aZQ43oQxVX(U;b;AlVO6GA>W8bq)x;z~aAR5~E>Zrn#1-yj#6v~om za8n9;dk21S|JyEU#?wcWtmUAK)BwR&f@TM*1i^cWCcb8mSt}NCiw{Va9cQo0xhQTU zY^bE$VNR3=-5S$*ig=v7@ONog{w4SHRK_P?ZOHu*w4_SeVfc@fedsO#b*tF4>4*Z@ z(evrm}Lj0m8YWRTg-69k26QUO<;w(YG zSQ}a7XOgK7>R`w_UwCM73N_0oR4>+HR;XV*17qR(;*7Ws|A$}^JYb9ISXQah88b!@h!OSG%OF`btuk$2S}TpbtUS z$Azg&X5v)gq$pM%CwTsnkhpYe%$EVoA(psP$ibn>=WP)xmyUlt0c^&gzj+39t7*60#6?1E zikpGhxarjBOdCChvn4ij)(WfG5^HO05G3`fn6=vrq>D3caOgaB<~q_&ZpQ3v>+omv z)|6)w_zM1-JJLGan*5C9o^1>LfLckLz2R8{5AG3oGXVYU7DNVm{9Go??Vy;6^;p!wiy)LFU+^4C#L%@5@*Z0$^8BvCAGt}we?g2VvQEK03p0- zTZX?CRFw}+O#w63&BnbAls&4HxSs^QW2LZ_1x~ILV787*SGEyxjK(d$Rv8DpkGGKA z6(WVITFQktD<=;--9q^9WN>fnEmZJB_?>)`O;|T#xLppG0-txsfWi3aK&^y#>}|jY z2fXSa2KjEldm=EZ!EDo8H`tb0<<9~G3)DixhCfIHHrpjcx0U1UkQf6HmMZyyizC2? z^we7;lZr-_fZl}8_aJ=3hZY$?*}Yo=?-gECQUugG4jd%pTHieH>;57DpnYJMv`~$> zl#KmLV%iBOXCy}hq*+n+m(Hty)?2wJmswA_> z8a|R2-L*E#GWayKBm-dF+pq2-QhIFHZrfX?cX}{&poe1i^)Pt1^`=W!OqhACP_ry< z4tOa|=fDGLj}06~?%iYMY;g_sujI zd%ysZWy=EZB_!_eA3O_1!}FWM&1EC(fA?c>zAQE=AZ1(sHMbn%7l2}a0z-`- zk+L4b-yq0<4}n3D`P5BHu%mRPBAueRVo@~v&Y}UYzF)ybv)m#gU-Wyoejb{o zKr@#UcOix^(6H6Yh7V21mDhrE{oZ=%j_~sGc)J7m_E28iOx#eUvViw|OKfw%yE>rh zqC6vLPK=J6Ux02kI`(;#vH5R8?mb3J~HRY*pG2OIsG$3s#;#ZaM@>%5!z5S?Bim zph%j}X&=4v&xJNyGhK zIyfG(%x;wWuyD_lX4rh!JedY!^}Z)LdwxrTjk0R2gv!hMo_lJC?^ZA6i$jrCs&uZo z$VwzELK%5YW?K|5vnfk1j`+n#jo0vsQboxr&0SKZL?*~W>992msEJS&si)+}!wnTG zBe!*hxap6hYxJ>{Ci$V+a5V#~U!es`eAh?sDL3HVNW52=wqj!1s(=pGpE-y`jilIv zC#YeI40w&OYg-#IkM}4cr&!p%V!RzhrO}rq>ka|ThJ>Ra@%IfUJZaHNC(fY+y)Enj zKj~Y(t}yM2AmP1xl1MJK)8hodl@Yo^-oj7In%;iGqmRDd83!>NeV_A$hl`%({J>+N zI~!H{vi2_71Fe)#nP(9l4CPbYqv$%}$&S`LPuM+%=pGlr5UL(ToM)v0OCp^zZX98fWqsPGi6VX~%YM*0?{XnCok6m)geZrF&9qsCp z&4ZI4)y8#Stp=N|{=HTLaSH#a$s*P=A3>?H(H&3nx_H7<0ZVYOCPMs? zo(-mouWP>L-z;4qG4;(bFUr>4Jeh?eepqWh55nYlBp&xW__`}6JdZ`&`_>(f;GuI% zv{vO&sG>8J2Qx%PWO{3~_T&vJ5{VOiZ%U~^1S$$=nw;+_%ops#L?${4CKaj5L{=3i zMn#*Qq^n`A3`cV(O;H_M#d|%pLUrLdTuNd=Ia^nF+=G>p>wXIwLrOAEy{#C|Xn0ax zA!(k0TRT(U)*OJFH7uRELcnNo+MMED~?yb&*Vf}@a~ZffGr~p8ClK* z4--AMb7w(T2f-XNdJ4qZJq76<5dbExhuvMtfqjY=K55PD?p`J1a1H?*0fHa**irNd zrxJW2<18ml$67-PXv{EC6`kao!h@-EcTw^ejrf(ngC8dC3FUPX&Z2C0|0FMJ#W~m9 zWHuOKMM~)^xdU^O!vCLh!hxSkGtYFXJfX>k@cij*qzoxtX6I=*-p}d)$e#Vm zgXj->R1^cZDM?{w_a4(dt;$1XqCt6HBSe+TVJf(siLk$>HCXQF)NqQTxIn)*AyGbnDSyxDE%l6n6uA@n$3GhgV zhCxXW+=71Va~SD(}y5{76|B6CSbyY z_zb89f%>XIZ_{=R>qC!{1s&E}pk1o1D$c+oD;Zu`cABC@rEYi`h<@Tj8G zE)Bjh0C$APfZuWBJp{o@3Tj(bo;->eNp`gwv`<*Tz|&vb8Y{&m)fN8T-369^Jn3(4 z(me&}_=Q`qJ?F;bKk!6EeBJ1Be+x8&l|wwN3MgvIixO+F>lD##fSb(pf*~&6a`YOW zb{ESF3l8)sbpGo|=krctZfXW>iB95>WqyQgu+&bp4+)`7(0ee;56c~GGSB4m)f+hzN zV9mip-NC>tJzRWN62RmL-Jdi$Zk=`b66hXA z>1*8IBUh10t?T-h-!Fq{iY)8yTKVRM#j^S~PBy32*n4U`gc#IlY~1N4V;=SYHfB+- zI^mfcO-5M&`@jmiqfwPv*sjtSwEy@kEk2NDfnU7EVxP26rt&b6Ad4g1hO|Gqfxj*K z(W#R?*y?CJ)p*;TDh_8NxRim7;pvivXNw}UMP)gaA3oux>JzK~q>pe>;3`cCW?Obr@=j*ks78-t3)0(aA24F~6gn!f( ze&?=89{NE#KWkvatxLdFW5J+NSNQc^fbXj-eC+;T416>>Zoiy;T{6e@p=XnLIUmg@ zwQ{hF5n7Ii`&BjyHota%aCP^B6xRTuODxFyTOf40IK%dX)4HQ1gSFx`A*v z?7U}!$NkWR-`$}br*{hF)$HRjE^YUfr(_0$mh990;6aVjPL4#N1f0L}zLit0bQp|d zzZoMvzo`ePf0I4@ru)cmr`EiE)4c51Z~U5Y`em}iUva;E(+FvQ3zvPk%~-7DqSG+@ z_Raf*E7g-@45f6>-)P|`T4VT45&8DbOhNx_qJ1x1wcC4S<_&cuB|h4}0^F9i@MuS8 zBDueAhPz%nFVEr^@TjgBhB>hxc??nW$c>MkyZHzm;*=8pmJ&1i*Yn%pG#mFvkFVTR zuVH^vtN~cU@G+fefc78xtuS(_1y4~yHhHJk&6bdCn_}z|B?&#agqRhzAbq6*HB5YJZDi&d=8Eq5MC8t zc`k9n)8q*PkutFsRR+98VdKFNURy~HNri9-rkz)97?kySEq-r)NciEo35ENh%I-g^ zf;DAFz^m)W2EX?ekbTt+cz3{i=Z|ZdaGA%VZrW;!<7sD7HJ*U7B$puI6I`n#vjZ?^IB#n9dpm_gYer7~M^MGlVbz+ZYj)+7<_I{2R)Hc=0`2p! z9k<+S7~c|!Xj2~m`^k_FqJ%R*+OtAn&3I~LNHDBr=Q^N+zK-vKB=6<5;p$DG%KoyG zu^a%#ea21Dt>3BTOL(zT*`r`2@9)9h%2G@3qTj-b9Rq;#*j+&2qJz1zw;|w_Ny5Rk znc(_7MCtNqg~!rp0xq78|5Vde8F_;=xz=MzC=`O)(^_Em7i!yluxC2Yvs38PVT z;)!wzM>5&BU7+4)IV6Er01Ew98fvST*Q5p=oergI7zI|IF2X^ zW2SSkuA`ibZPDPqKk{NUxI)t&R6*ZHIeSbo=P2=Oi4tFxLJxbN4pHLU@KQlmRcwcU zatfuy-OZo~LX;A2s3~*9+DF7iPJdA1SX~48$M;&ue-5MXbID5+t8<$7+qh;5oaGe{IL_%#y%T+zNM} zm7hYWcOYfYy8i?_+%zA2Sx|$NaqE#XA3_ZTdIM7Khxj~%Kg08y|9i#%ZRG#=IR)xc z0Hh3-5U!T5r|Zetk`@+q+2Q0@74lvM_2Q{pQVl883nn-u-m0-BGwJBoZ#6&uibOhc zXv{FgXcrfSyrCeePSHQQ8SSG*cf$X@@c&4W=uS!l!Ez!cCP<7{zC#Yo;MZVQcAx7P zH%=pMe;IE3Yz;Ez0odyUV}N1P9rH6Cf5L0$l%8Ix1qV9nz}^nq$k7ah!SlQ zERA8mN!t#BXR4X7Kv22T0xXO1zLL1=xaMiF&T&=ww_<5ZD?fa$^v%1WeecZkcN!-i_^hFpv|T@Gp0#gwzD8YA~N*aZLy$82t{DQKSI8 zb~l;4^l)cmYEarZ-q=M*sTw#i!Tvl5_d!rjW5f*d_Ll-DN2j-)23Pm;X_6gHLs06<>yW0ixrXzMtJYkKI$?R;LDRG7k-6O{I zxtNJ${tubHYlo#hD1SZV?F*0rs_6^YK!y+#Lh>DF+=!DMlnHRF6ZFw=2y_s*&%!ej z&p2dtSd0nXMU1vU(jTS4Onfq2yfIw-qj2#Lq4;`*Q9S5S0v5jOz+&-#svZw_Y^3Y1 zk>+0wm)`{?t_ANl{$99*gMJ}gVq>_(28aCpVJv*B0Bj?SR<=V1*eL`uc)1-OUM3a5 zH)ut;!g8pv%*pDe7LQ1i9|T{W08}_Adlfv8NChbWOt?H+_0ToK8t;elvpc_ROwKNE zCm>CS_fltBpA$Zf@N#eiSOL$$)7D^SX??*oS4L@_=|0zw(t#tSL_xPbGIAbF;M2ju z3eN=R7EJ5g@i8EB96{tkG@cgt{FgymO%8|+tCEJe2%^gmQrf}%ae*alSR5(~d0%KD z^p!{_>Q%1sJlKE0nnV6ef}2fOo##Lri_Q6O%dznRu zQnCeWpw;y)Bt5ybstKhlTQz*`k&u`5B^JwJ4mBWp%%lhMWw7>;5w4)ow=kShaT zSCEcMj_Zt_QOWCJNRx$q8{=k7^*;eN)^zB2+<<{sf*@A~16zN*tnW&$YzCa0A#Mk~ zDH$diq5-;I2Qk=Y!$bVi_unBJ1iUGJL@^A22@ik{TkOeT``rd1d()^95dp|^;;D#i zpSdDo3{MY0-l9!h!lyoz&hRN<*7JKC`Ui~$nl3DQg2G#ySWRExio4W?QZ+UtE(eo~ zx@Co^VLIGG_a-C$S4Li4CW`h#!H9qiD z6{@$hOu&mI;f?J)btxqLy!~EE9TM0V_cDI(PDwcX;sokKP>^2SNWBsi*1eQTtqBSr zyfm8X2?^(3nvl$GM#{n+NcsLNNO=!P2=QQrO#tHs;*faLFX&$W{E>%)M}Wt|CsKkR zg2Fvs_CCxZsY3i0qWPF=CwTqEh}NhFYuly0TVPf+DS7brEV&bdDW?V(_JCBa^2GDE4&tb*0UUT|F6 z%I<-g7m$@Oq_7#-fQ+p7~)jwM+Z8x-&8>ITw~bU&#JCT(!2{BIkV?d$@YuGo)K#DG+BPSnZZbY8 zl*bPjPSvW_^MiM9emJB}YRN6!TboH0`Gm)6lSk);?;2zVe}k_)-Ea}#!f?;fpx(Dp z+ED%z+{;P)Tc$5a|c8?{gCgv!2LFI ztv><_h#R~?w-uI~+@Nzxb&lhb++fw`wOTnO!2RH=6-WOqF-JgRK~QfCl;8B!C#3u) zD37$qB;Bc(;u_!C9zC$#AKSRAfO4Yxqo#y*;ejo~?SspoG(dDUTcFP0n%@Mg2KnsL z;4%8I+uwO&Qsd5tO%J}a{aF8KE1nSB_?qdRjpUjpqW5pa-CNgl!=s* z0qK>7t4vr`)>l&gy`*-?h3~H`-~ax4#8#gd4KRFOGcoNG0KCv?5aa&P{zhmx(5I2ZW6 zPk?g)h%azv&jhQw-@8%ZUQ5IALh);f_@c1%H9fWnue`?Pn?nKbngMcD_IVGVM6LPo z8K|gZ5j<+za%3e~p{RpF@2CBdA4Ke?4if9sD!+>C^gZO7CdvCkxcyo_MfD4LuP5PN zVb1Hb@z=upug}DLkNRG(#CWT)baw`RT6lT)sKm#PBc1V9d<-1ckBdz&*ft#@$LQfU zG;WUY_ub>bRl~b`=ECrm3^+vR9G?Pi%l~vPfdB8D_ygmusF^G%$KlgIoh{(|k>mId z=1Ymbb`L%FOq1dx{Qew?S%zNqdq05>JIOoYmLHGnK-&GofoK4{Q-!^I<_<}Nc_ot+ z1q(Mykk#JOJjYF$?#3qXsB{ zem6aIm$9rnsYo03xlg*2GO*pN^bNlX>1Mf4;n{79xR}&K({fM9;1E-4cAJd1l4_{? zD=Z5V4m2M1N$_1Tb&jQ*wjiIv`(C&-!yr#6$00^!)w~DA6*WsNRGzV0Zu~hBjULr- z!HBpouOst#&tn0<>!*!TWQ?uqjv4<8H)FrzT*GN z|LOc}=fe$0!G&ZIq~QUDR|kN2j45WAt(9o>;Jm^j)9psG#M%M6_Z1^H-<`9ggR?Lx zGRoX7H$&HV-ZC)*R3FTR9i|?-&l`8{EmJmhUty_F+yblYy`%6A&jFmsm-~kHZu?_` z0Vnc?pW9{{c9FV&k>%?Iz8mp*?yDZ3sgCyKad==GADpoaJ0!Mz>Ju0Ta7egGml6O-7 zy{zQT=_j9;aKM)t+yC=rMsPP|!Lzzw4i_ArtLn7PH6!u;e)!lMe65J6&RW3_mYleW zI_=+(-U?rMK;i-TAIulPXFb{uch1P?Jjn-32S4XI3obB|ZzrnZ^Op!dhk0<8u1^i` zC{^~K&wuLr9N`oI9lY$xry$t!?>GU@ z8=M_(kPN9Rj85OxTGj_jDwqdz@=!hTCsnm;LHr^*G$cL?6&8bs_#GE$!#vR3Z73^t zp4_02x&Hee_Zg{ALg)qtS4=XqNR1Y9rD9Wpjp22rr~j`ut~Mr)A`H*$-NGIm%2yL0 zeB1#G7rx{(9BnU!qnuaHS|}2aq77h4sfMHtt+5zA&>x~m8Z+$=T1}-uQByvSE3r1Q zl>YIDF*%}%@S_QaC{Zv%%iUfNuIDq{B^u)<&%X1{`_Am{?CkE$yYIY@qa)(A83XpN zd*-y>eD`(Zhxg3lBGqYSafg)IyV81V9;sAU%{sUF5d}>L<$S8UW{;QVPsknV(U!yP z`sX!{!)RXgo(AH%6zledVqj2%;1)1-!ol@|)u+gJh@M*gYX>xHvLB!Zyq2M%f(DoG zyF>pYhm#BB(QX8BgnY->2ak@0*$9OFk*XCXFfSr^ljpM5ku(QdF_SmlS*(p2FqI#z z-9C#YL<6Q$TNz?>_8Ch^K-tZG$LAO^q?a#A) zYBn#DY@XZZ&%v;(pwp|g`eiFz>32j+HmGqY3nqbQ7Uj*LkO_;ZhW$07J(*Kid&_K` zFR*CPSMd|o()P_sn143{ysAonj4iId01rtDsw?(WeF7Hgv0RyAf$^n z(W;%7^b`TJ)IxHbTJKe&?s8e|3R&Ua($wlz=v^|;c^>3LZI$M{u#@xJNaodc?jOo! zLRfblPf$o#KzuC}US)wBX$}M8c6rt!4M|HeM~?kLQt3KLu=n;kQ+lJU57r+D4Zcib zbvF96q}bUC$Ef?W)!TjOlu4FQ=fo6!hDdMmi!p@0WC=^Wq3WNg3N^6J5u%;XhRZn7 zH~Hk^X3Y}ykhp%cxGY-x zyFNi2<9`m>hITj)=x)a#(n=gA!G^;a3AB2Z<1AxLrp>HwETggn{|wZ7PK`H%yGk`Y zv5c6!$E*E_S`<{KFxs*^ca?N#@zDv4q;UD&RSMX(u?z5yjT=7)cggq1FVapH82^DL zvhQz>=c0A>qHWQqEff%zH~}#|v?d;k^(pSLn)pRSW)OF(nX!pN8p#$W2Ca$p#yK4p zHaB*OUBl)S_u}h=Fj3MhL-zg0?~y3IdPkLwkR__iX4RIUg3-Dm!W{`q2A?Nf3F@4G z)^eXylI6PmMJ#Q6k_?M7A%s&^m_|@S9)gbq,{88j*^*MR5x(P3U2rZJo{&zDV( ziv>iQ%g1{0JlMX0hX}OfGGJ*D0Ly^%EAnLIp}^kuJMxEtQD8g_XDN~NWkhNL7J)Os z1%MZ5hit9_hIsH!pxsEMLGV@k5e>Av)Aij~ar8{(i&)SOgbqQ-p>R5~5f#2nq@%}( zGLiA@)HZq;4VG#0@GP#^njEc9{gAU4SoO!Hgriz|tlQYjV-;5!3L%?TE zf~H!i=IK~o<|V`mL*N?Vch|(mU1fg*&4VSW delta 23602 zcma&O33yXg+5mjcy*J72LX$4gbfZ~X=n82IQWhm7?d=kPds3Wl{_T1GJkPn?+1~S> z_q^xbPWIfOF1V=XOBCjWZYtN7Sc$ZW7Qv+beuO2lGO=QZDgApSMhqfxvKNU920Qz! zUhV8(@oHRUJg*lq9dDfzzR$7#k%PqN{YbnEH5&Y8iAlNOnk_L=@Dz2yRi{Q72WXUm z5XzX|jM$y<-0(Z^7Zgz+RYa{Zl30jT=!8>VMmgn^3N?f1iDJ<(vxW zbfC6cFDhxX$U^5)@ZM8x7L9b&AI}5!>L@D#t`^D|p^WgKXTfT=lvHL-Zd`1xOs+Op zHda%2P+{^CQ{|<_$-GHCG~1SJP3CuF|M_HI1=n#f%6-Uxelpz6q8u8VXn}$QMpL*P z<3E32MI_$<_wjHyi4+xS9T$GW@B}SEPJul}%Jd?xP_f62;rpiVLxwjRwQfIazpuos~a&V%O*kS;^& zffT|>bp!4~o?J73xMf6T3Lm?b9VTR8==9F=P)U7UHDVxW8kvL!YmqM!{wcow-!?SwPX#TtOK>=y27H~+~7zb?#YWBD-%~BvkgNZjhx!>Y2G&0>#PZx!`ql#4%B!Hh6HsK@>z z%IRTYB(ToeRC50r^}HuX8T%p-yA)Dwxa^XQARe;m_9 zW>Gc=^w9%}ZNuW@J`4ae64tP7NJJ93KH@8GlW{0R!{Koe;yND|XM5Q^j}zrH-EvLG zjbbAf*L+gk!L|`3hCDYyBLI>Jah|W^25Us3>;&rU0$7lywhWhJvFIe~jEJUCZCU8o zDbum=$go%&EnW-JdbMssh5k7MH^DNY>dZ}9kz9XmBO_)?<0~}W16Eor2o_oJ`#e|l zV5*hU=hkA;HF)JF!n9cAXY@tZA|B_KUNP`?M2qGA9E%#hFjh_ZJ2oUn`VR6V%e(o< ztpLA21u)g`O@?bKe3#jD$s>)Y%LZI$eP>)bAs9O*CQ; z!TUmZUjnIIF&Smdg@+PIFUKP`X(?hSrjnUQ8H|`G$t+a^#fz6{(H;gMz9?xps+o|_ z+IJAUM0h7AUABK1Vpj|Qh#8GH3b$hP)S4I}PWga*O$?bW1$kEl1)dc#H1d(lVQy z$YpU@+~H+L${-hs>mVoo(jzV8`Ou)Yr;wW!F3}3#f4g*K8On7#3c_E~yuZ4lnku-+ zN+|m}65}OiCK)n@W6q?k7^W*swoj4Ou&Na@G^bNRgV@$gnDQyPlcM>v&T7R*A4NZ~? zKkc~Nx?eJ=U_m$O#A*tQG#<6OdQqeq!>FEEeQ?oF8yR;Ag~W|8f=yCt0~Ra2A@fFru^`&F%@`l^*oH!V`$ zFQEH9u9=b!;le1Mc84A~&Byf8bg86A*M(_uX^XaUdpQLx&*9uOPOYmo(4sS7*Tfrm;i3Y~H4c@tyrr(`dBe^h;04+`v z_Q$6wpOVO`P_?PG3=rCB;mi26Y{MYKHNZ+d=97(NE)irV4rXz+9gI5z9k(*#NuP#8 znY4IEP$oen>`!wso+$9e88mnVYei;tnL9^uslXDPV#PN8|%h)lihZmT>u&Y4}uxXXc_ z`v$Eoxx9wEwsaYRVUHbJ~|(cK{at_dYqSk35HwFF%IFe+#tQobZaI1L8&E%uu-g zsE}vBPl$PHgixyK-Gv|t_5QsPo!SxWlY2RkwhNL+am=@o4hha0d~%`xJ$UXaT5 zaxK;{z<-b)H_EjXJU=0{r@WBzq?gfye8N?4LgEbX5P-!U3M~@96RJ|v@N2@;srh)m z(3JW#E)ycs3aZ!pWn6g+a$6O7YqB`?_yRy-WbmlT3qM7$&0Omj5K z0EATy=l)cgp0&C8tc02sz>&Kp_5gEng*Y6AarEl6_KDm~n5cG%;g+_KIE6H~T_|_J z83o(2+Y$2I3ZSf8&g-s;++0|KmxUQ4$J?$3WZdR&PDP-@JcRIVC;~^YOTMM?aCP?7FMc)@HnWVGC(Z!;M}|iT4MV zT37K0t;hIl);C=<0TXZe819P}XmRdF+z1VB8`?~^!DfQoGbs%>k4qT$?M+HgiRl5V zk#5>!8gLHLC{)@=3AhPrZGHA*(&bionhS`|2~bT8H&m)qFsDyW-x0{*Z^IfN2C|#6 zCFr>x%BV?b(XTsVqMbp{@527{#9@8@o_19^p=?V0MffZ|ZP*Wff_UHs0BEw%mtI7@ z?iVy84EU-rOH+}w!H+an>mT%@=2G~ZE>Jyy@Q-NnT4{c+U7`wDh5ES z^CP|fIWm_Sf=pYD-xF%IqbceAW4pB{G2Dd*_4kdEpc>moi|_bo@oh-^eZwqjUfmuI zGG+?DsvT)q@o|X=6GE4s9a9Bj9T8K>;`6l0x!4(a*I1qriw5yNSRXKl%Y(y6)fPs) ze^9uq=dfG2KVu$#Nq8e;tbTd`iM*dkh*-R@ljym>fBNCS_m4qraa-i{Olat|a5G~v zUL#~?j-@H_s_;nW1cnhONW$*S`>1-G@Kt7Jraqzq38-;{34c$tH!R@B?I!vnYQ%+T z_iYzwafNudkTB{ch7zavgttcB2V*}!YIMXoT@t6U20i~0WTVI8PGS6LJ+*JtvH7DX zVSHS8Eh{|}rtFzRz)&W_RzaqR7Ehe0Z7Y2S81|@_n$Jt`AtVNb@!49N!&k)Ra7@L} zw}1JFFoimeOe}gh3$cc_Sdo=&X-?px9dXMKE~oou(+8I@?nA)E&Eak6u%zwzT7Kue zusm*ge97YFz{_)fbDWbJ4EX(X&`(y8Y&RCJEu#e1^6gD}JQCmVRWH|Z@(PlBX2wm` z_*__aO+H1l;lDaowUs<`PHF})|LQv@oiKE{HE5$L+L4}nPWnXSSV+4;@9sqUGtvnS zBms7t5oexLvyGYY}q^&66IS@iR z@)R4!QP4x3ECw9OD{{Ek;A_z1g}qzdPM!mvw_voz9cyxgpK`Ls5V$1oA8@IY)ty+Q z>QJ@qmW~?|xS|#nblV$JwSY7z7Keo5+(O(eEXz$xRECaA&l{5E^7F@~Izx(_I!}sx zC%m1zVt#V~u%;pQjA5YSos;&Ukmp?({9d@f1@|`*+XB1=o<1RmLd$4_ytfm z?1p)6Cj)eydKj@;kjVC|YBTZC8Pn?G`SfhPm`?BMWVO-ScAFUvxsC=YL_sq? znvPt+e>GFp(FK+)K^jvK5ntTNX3XbL*9nDVIUD&bVn}V<`4V2w|6AcdXRe!?@p)bJ z==9uh8(#T9@`KQRW^|^)M^`W4f1Mf4oB21bCA{3x~YMl)zkRnckDJxjb1!Ot2@mAn`M!am!(zEe3Fr|#2cf`v{i%^L;y-h z@xh+Z02ZRh6btsThFLEI^}aAqHEwTNf)o=S@Qe+p#{A+O(o+cZc1T_QlrCDYt(apL z+rCkMy>MwAY!{o*DEnyGE?#=}W1>jB1lvW@gJ~uE1#B3Roq6ZsAv?;#)MSTpI@3qT zM`tiTDt0Hoy5-TjuGZ~!RNr}ODK8ie8ucHTGPIS{MQh_M3>e92 zmzu#;-b1|pQHilM@#-=HT%4s(y|cSAIWt zs64c!rNb>@AFWTRQG>`KrvaGSEtwBIxq!-=Yq#`?5uz zt-AnHtrxosjLsIE`2iR0mGvi?-r`h_QN1zppId{g$<~^xUuM>|Sc}vpVn+dY(?#Fe zy$ZCD@rryQp@_4o`L6z9V5>l#Ec8vUThu>|rdJc|1x%*>|EYc|K+&Aoq8BM(Ij6&N zEGcV-_q#B52HIfTjG_j~E%Hh=7$&y?^mvljNoxWg5mqPLp+c zm;}H4uVPoi#Zc!T1&iD08ipIjnOn^3yMYs;^>!Tcd=t{wq_h`zggo7$L02|M&&4_2{b(iEZ=Obb3 z?p8#ek9bg~8ON7^^%~YFQ)CT!TBLFJ#19xJtQLYLGD^8cQ3*y=x7Bo3x-p5mdqZay z88Au`Osaqa)QGi;ZL;;6s;6<^JX%C%lvCsodhSz?R6odentMxD_01|>&#ae;v}_5+ z`3L7IoN+Vqc|koPXDsfsGt_0V1802a%HXjf)j9y!RS_zIL|~BGVrmpzH1}A0)cUc) zt_c$#Y3`_A|6%fq{+HrWe)XRtuUy-D#H6@9!dbMoTS1?%UQbNk)qmEmS6eFa*|~kG zyIWiP4l3D8!z-~~#qTiE0R5M)H13wGXj=|f0P0p!Nyzi0kXfuB@zI6q_4DON&Yb`# z2n1?K<5=O-ag%f?YeTdA3ewXROi?7*AnF>oQ(819~z1Pxq2sB5o=$R?~rph0#b zv@OJhZS3e-VkeJN_|Fq;li4V4Gp`3}R6glEy?$K90=!^u8dG?lOt8>1UR9D^Nw1%W zsXlYOnzuu>9dil6?wF|wQ<5V9df$2sCW#G3eJ=(6f)(P^AWerneSsm#6M-U28ncBw ze+yCT<0~RHv+J$@q}Zrglp(jpdrU{Rac`et??=1`J^Q*2(XY6Pcm<1xM#MFputMzLl zd~(~JVh&6`2MD_1{w}^R?8Sht3qUza*TCr+p4*M>Yk z|FX4;F?w-2y=>(rFjo_M1JWjxCtIsT95>$@rH=;-JQ%8{%$5?S=m&z;Cb%1Q`t3tb zB8Jv)p!7EVvmwt9J|huDz+AW=Ot@lM$Ws6qBiJINvqDnCa{{D{I8el4%JOgam!Uhm z*D%})k;6n{Jnm=QRz%)#L&)=?e~)y3!4og8=s!*4y(2`caudAok=7c>mrZa7Fo4BW z*?Q?YRlV`x-!ab7Z;&|{_wX>;P4$)Z99+LgO6}PrC3cNozi9nW>!$eb>Ev(G)Pl-b*jSy$Od)NA=;J5k$z0S&J0lMSL@exD@L5(1M+7Uw_BJoIjQQ6 z;2(J*&o0om-jg0PP+=>kTuhhaF$E54%rFNU^Su*gJDuP3qxf(7jnVHsH@(*!y-7;z z8s0;THd>y0`oihH({!ZJGFcBxYlZ)RNj~KHlmC6!lh6I_InkwArvljCa-f_youqwg z%m^nMYa6IKI@HS4yOl>tJ9|--e0rzV0CQ8T0oJ7it60dR3vPCyF}8u?qZsOpKT30p z`Ob0@I`HgKlw+$HSaEcy@i=Jw0q0QDlfnST$g6rcqW^9>E9i7RaSD&6okmfG zG^@XIQDZZlv0_N6bqYJD=x~>Cbc)u76}CI0kN*4mZMkhge{@c73~d`oKWZC0^=|6X z>UG5TLgh{!7;#h&n<^nvb8mEfyj5e-ZI3s80+v|}&ZP~j^c&W@`k@8tX!~{Tx+-Wh z@R11b-jC*jZPYe!_amHR8|eS&@O9m~S&;kNN2I^LkLK9I9lAdHgRZU)qAc6MwU2b$ z)c`4Lp@G>Ybeab!a4OoNoAcL)xI1XZMjr^t9!SI>y`y5MB^tEi9hG!1gHnxDF9IJX z*ud?XbjlXAm>+Ev-?xL6O1r5tB^u@0jAE0$npU1)Z?WAg@?k5=H;NJU zq|my`rdIIZia*&=p6b%tN~~QwBc9LVhPa5|vnh0g*R)Xl?3&1yY_6e9D~mk8vf_&{ zXGy7{TlSVA?bGFcPi^QY`NH$dENQ$#)cv-BZ9QUxKF>*8NSgJ=RPZ z_zSB^Bbr>wSqv3E3Z&|3AG>!i6e3)8E8HKjq?(XeS|9R^4j|2t!Tf>(pI7m*)&;Dl zaJ~zTx+-8SU*Axp$dsLG)b|BTqkXV zZmqdW=V)MVKl+=Xqj-_Q3Ma5`FDbGJfZGB0b_I2w(vyml6jA3%&L031)775>Y&h>} zR_?~~&zy;12PTAj%}EA=n#pnlImzGcx~f3uhX77+C4iJ?10l#5>2H<@2PGRF+2jZZ z{e!z|ARnphh;UZIVXH)IRF#O>-xRCPKV4bXTb}&11;)KAg&)CV-Fzvcmh!T<3r%P@ z(P->+x-k(r6c(m9P}Aeyt^QQ)s9swBxMidj>no)Qo8d7F_C*({x%um?1!O^0IVn-3 zX6D2I4r;uQSOjUUCJt~Shj*EGj%7Z`zlyl|tCQAkmB*dGDoy`vMSp2*tDr<> z%!+;*d>*yP*c+qz2EHY&Zd^SHu*Z__3_iKyyr~@ZMS*xa$*a=a$j4$3FL9Hl9W_lZ zC(spJNP&?cT4sCg;c8E_#E}r?PL0~=Tz4J1p{Sg508oXMI4hdRe_>E4&5X^^+ddnhI3+3B6QZEMNjB-Y-2U1wQvk7#YSf%6}w18V_PfgJMP z^^_T`R^}cK+WTDZYlFiLC^xb@$JV!gPA{dGIhL)%VR>WO>h|l))=@gib&#>$k$t3s z7T&!(K4lz zq)jis+ZyszNNY5C&-y*vd|FP&t{Qq|+ z;zOh*)wr^X z-XN75m)EW6$B^@`RM~aSiFB!>jhW8Y(^AHw(~<$F7HyO?u^Xl6ScQ+mxNw(r|1?Do zsZkG42c?)AV47K`BZwivXBU;Viz56 z%>|4p(^Z|!AH02em2RMG_G#(z=NMjBJBfZ?4zT){&OzauVnf1Es(c9t?SI53Yge0m6NR$e z&bi6BSk)25!M9w}&RrMHB}4hxI+X2os*-EVs1iJp=2UHhN#TGVs%QyY5QOjuCgfyQ z9prV;C9In<#r6#>x2~Gnvh+5f`1i3m)sM11=%n@%KPVUzeW2G)i=3|GP3@60A|H$b zEjG{I25@1$-U_;6J=l*YpEBL~-dx&$c5j*6C4wAN(u`P=5UkhmT}v!cH$J7sF((KG zMg@lgh2l>jVZwuHX^X(a#R7FAebqqsvs48IK|@LHsMB!-v1f#p559vx5#p<6VL@10 z^&H+WT&emIUl%%OK7vmQiL=V^W#REz%ZAu|38BG7y-c^5)q!=YCHjE2(+ zfk);TRBh&(c)&d6KzhN1!RxN-*u(KaOagWY(yOpz-s83nPi@>;znt=J?BB4g(WE*a>D;)p zd2o~wdpF*0^$qkhzIc5~>&8t;-*q##h+dM^LTu(CPg4iE*Oswu4Do`3>86PfD_B69 z42jAG8?UM@fn#AJu&4o+s_J05fTyM%iKcd`ZDSoFfE~iJ`O2}$g9?ss`AeN0w%-kb zGAR?)w&VK`*6laRE){b@4f&q4~oVDS>)G^bH|pK|Xc~6$|Fz z4q^X-Wy9a`%Q>+HXt8@^U0dI2Wy&QaJ}IOv)Z=Bsw1w%4H4tI|@C#2a%*JM6*TQUD z&~qt7SaVK*hwJ#kpMiNo&`1a(z%DH@1wEGo4B7o5ZUszZ;-e>s85!CPDlH5*pHJf& zfKiTwZ3zelSc&3N&~rL~cqZ$PV`o;s!)PjQ$NJ^g+=7t|#%Wtgz_OM63|jK01NA@PW|!=%1*g zJ|Xh44S2cm@?&qvE_{I43?cjRbck@Mc)S7^3c}-~ZBP0CcL2nWB_Fw!OW@MEdEId^ zm17}N0IVxl@cU#c&lbc|-dO5zElnNkFlatrL2t!2sWoR4psSXj#9D8gou! z8;Y(>hYA1K%W%!dBHVevJxF`9ku=0G1wD=4tFDWZ+E&oll4_mFeJQD7i9P`anxN;O z0SIlPNi^9L*6Kz2#qUWa_A@u-`e^+o*f8I2L77vmAb^C;OJ7O})2_OvgU?95$1v_E zunn`aV{naJenXgGOn9GjQ0^%Q4eoImsMRlHmKob%_8iy z3^%g{td-$$9^8hD4uS@*fqk>ML&o{S`{oyr-w*irbsry$HdxxPZR?gtfjefHkhUlV zhlGiX+NiEUL0n`?duz}IkjNMk3pSkj$wfBMmzsxhBLES_Le*kzRHdI8NnN52g*=Z5 zFDy={f?nax#X77LIv3Btv@onXJN~l&1HPI+VvTQU+=dGq0UnP~QT_CY%Mi#_+i`#= z9^JP9ev}dPoRx%cs-I7J$Um&*ol>Rq0vH3nkl2~STaLg`jzHCA!lEU!k~kl49ajGN zO-dH>sGuqhLyv~3S}c6MM4O)gw0D}H2a!c*I!WYf$Rqifk&z(sg*>MK-gi2m;st0= zfcBI^($aKA$_YaIyM?Js?~h#*zA{Ti9K;`G-f@wT z39&7{0!-7>sZsQ39UsM~v`1Mj;4_QkTU!J$J`P{^L8)}{Vg7pwb)CM6GVgE4nmN`H z&*`n{&n0u!+;vy3b&hr9bCPQgANn`MLqnUST?WKXeT$lJ_S!{b1cXEYpIRu~|3nI& zC(L`ohVzAsPmHI|NP_Cg#nBmHsnl@#B|c9}P+0$D)`&Xke;31$tHSHC`$zIVo6;j>c4`N(dD_fF&v_OVohX?tf^GSV1J zkeDQV#xKJ!2>CUS+j)l7_iwu3mJCt1K2XO@E_Y?l!ARFX{r9vYv==q)ya>BEB?np^N8 zujhCGgRtlIJQm1rp*T2SF%>Y!FSE+mdOdXk;*y2PuW*o85r1$A3I8l|T$C6C(vB>L zb;!bqdb-qCrMj+^%4vPqRwDhcz8Fl4f0ZDlg-fh70yP_e80C*@eICwl1Q51(_ecv> zNS~g4a7i2p_W@6PXlo06v!eXZ9S=zh0fcG*q01$QA^SYJ{_C(rBIUosm6rb+CXlHn zB{D+lr~%38tH#NK|EY1nlM9x`KiU$^>oEYPkbW1xK#kAG@&)Y&O$nD{`Rw+eljAFX zb*Z>WPIPVM>5`$Rn96K`^6;RlhlufUJ-hhVO$Ylh{azoMEpA30pVtywj>LBchg2seJU0!3!Wv)0Ro#uQ{SYYSWr;H4*B}DIk0G?P z!lZyQ+Xk=OTyl8W44djt(4Ze=$mzhlS3qinbP*DS|A`a9GDze^2ym}dYFG^SA_fYpVx5FlM`?&obPy+(s@OVUG zKX|w_`T}zne1%*&;PQ|(1?~aQSKwfUHeP*1Vp8ROkx^O^<8Gj^mC2VB7JfRY*@*p< z6lw2PuzivAL!B%SCQn<*5!18Z8%zJv7b%-@_K<1T+5BXRLpfH5^Co3}(;D6KHAFr% znEu*F$+?SBd{gr5k|=ATmF10~t<_q~AwG`*vn8gJ&0k9lIGbPf%iSz6W4m-$R)Eq0-!vBI~$|hx%kPxBAY^BHm_!SsfCGOQErVr`AudOZ}gi_Bsx` zS!yDzszFbDaF^>)>4>v`f%RU>9d+eEDDDRk_8!?sQ>(zXf$2i)D(fGh#1l{qr(9FG zQ!W#n>%m|hFk8>MNXx~3Z5Uf!5T=N-rj8hR;^;(S)@8Al6S zp2-A;_Te*n+mD~X0U@gz+{~e0s|KEbw!wG1pYp|{C@W<#n~}x>IbVDu=D9&+g7Q3K*N9LI_b_)s+^>Q1)wof4t?*n=RSsL(Z6*Ph(~gdnaahj?1xZp zjPgRboKal05jw9s2;Y_~qu?8|sXGBweyC~EGOF7HxqLX+zT%HuRG020xpscD4YF&M zRA&|dG4v7DZEziSFNLvhy?D}H4HNQVeWZAmo&z3^3-uSdw=MG|<_N(N+u6twfM;?E zofA0_MGKJV^eebGe>~}aLTMZL^U+8SKqyygquh!JWj1>#TU113bt<*(zfw_1!JSWwNmA*?3#FBgM@qbGwDo>`SMh4jDBCVsTSx#-%7XR^XV z_N|iXaS;I)0h#};<@wb3l4GXhop+PbD76@&OmP-*2|ajU`N+>&@vg62xaskc|8}9# zmtAU6rG&`9BA1H{oDmwzm?mtStb>i{E?{6J_kYI#!B(`hm1BA$-JwZ_Ft+qODMiZv ziKD?L@W>?sQX@wTF-I1Z#7~w9M}Y0(#Yq;_7XLI3^2r&70?w&BRFopDlpD&Y}(%l;XjCG5oG|KTD4P*APQm8*5SaKRCGWYm|f4%bBvj~)h` z1=iB!mnDsXOw({@Gbig|-JxRWHVk-KsptDoVM9~U<2vEwA9ot2q8K7nhnI{j0TO2a zUW%Rfm+ZA&CvYYMJ;Uh73^?!uw_#Z?QL+P?Y6@0Qjq*9?u{)X-i=1R3l0`UpgTg2a z_{4&h&}6QtijrS4nk?|XsBaoh_wMkez`|x6>FqOnF^$C2b^w-*)SF-vpE!7+k7Yri zlt`IxCB_b?$=d9>fbJ8e>3{+I?G}5a|XI9b41m>5-fODKd>i@7(xw>ne4a!VfQ5Wx0aP0?2|=7P`ht$&qd%m z$VM=yhNC;zRyNuQKV0#K13s^a?o_wVZT&27J`3evUn0j%ARR=xnTT$1;9&>S{^%k-c<=RKZ|!OwaAk=jq9Vb~ zyTcbx5J5W<39_g$4uYy>!u~%eg3KQB)cHUE#R3RUfw5x;pxC0)Um2nhc*x!r#Q`R7FG7huzu zl@OMf?Zi#FC28E!U&^@2&?$Oc=B8wNKB052wk}MVKasBKWMF_-9Ld19Wo{hK&(&(Q z(Dvi%&U|gJ%Qn;}ydZh4oSLoNj?|$?}!C0rUjc~32zpgp0M5LIA zWP|1__3NgH%P8|y5(0DL{FPHy-ftapw1Yi3>UY=i-;7c2-&9`eUnL^T^tzgV>w4ks zTP4em|Hi!#{(hxIWSD=u-o7>Mh2y{dGhFu3^QH<`ugt`nw{JbLY}YN-3!2{)ko)-y zZsB}gZfv22?)#h;ZlM&m#v-cJJdN;Xnv0;jbxCJ-C6}0b23!d;LS-%QU~q z0os2qBhWJ4$V>a1f8(N-mf*?k#ACpFe{~)N_2OtoKeC6yzu#>LjT?1mS+p71dnT+s zJ)_l&-d(5UV%q{9 zy)fa0$u-ZyX)p28Ef)}&*$xWL2+q{*_bdq#qg{lawuV)cjjd9Np-CY>=l47kBwtCc zx@S(!A0k6)*py@dKzkiHzm}~l5{GR$_VG*6^ipntPp0sn2y_pl`p2?zX&hCSOi*b#B>>`fx0>>hqO1=M-0_6 zCpoc7EDuP0{S>iA;&_yyYKxn$hnX7bAcyQ_lN(J*7nKlOO}kMweFqganqtpVaB!Fs zUjaw?wh$%mh3AE2qQw7!D>05!;?8!k6hYi3#WIMR$QFaCDY_Eri6MEmq*rNM$Q4gC zk!ukHXQ$+rl)9q!gS@_-g5y9{gN6EoR`46Wxjxl)RZ?wyxfx}id{Dt%mDqz@;ixF{ z+HugT#zPZ=GxQx4=AIW5) z+qdek-hdiWF|i4V(bhxYPEv@}wo&v|7o&Zl{4QKyEboWwx^mH#nwbTH3nk`Cj8@U0 zfTc=>^703qzqm-#1K`pF7e_tQM8iKR&>-V~S`YTROiHs2@Ii^I;n?<7uy;d%G#Iy3 zr^4S69H5fGmS{L=8hL?fLKzU(OmDNn0bxb}v>I_!N?l4j1lBaB)Wz3MyB$YUTE!tW z`a>xdJeH?}9K@`^VPEmP&{?2oEdD!$4My?ddS=`?S0Mnk2du4Kx1X;c4o-ce_~-iE zB@UA!lic?e?w?sn;5H0x=Sf#se ze_;m|B#LS}1u6>J$V8{23D%APe@p=RNIYSun!uYXCWhv5iUwlT{W+j?{dZF#Pe-_= zga4l`feQm#5}>6HbIS$o!cX zNb4^IY$(g(s2Xsy?ndFGUxtJe**_2nDZsHU%IPSJ z?Nq~*ob(N=&{)B7>y5Uc7IiqjBx;6PtLAg80nc<`5VGzptA-~of4}F{iQ zL@@=3CKc`mAR6#sPS@}O&jLTNz#=_xPSi=h$G0hgnWJ3gr5Foo6!uDJk|ui@MD40N zA}kuKn)iENm9TD@TY)tYxo}y+S-*kyq=3+SgRpDUa9d*sX=|hf9A06tw>Cp)pf9CD z4!E5H@F42u)sB%B!nx&oeGg7nDv?zkB>TrLdpQ7_d5u@Rhp;KVAk zXrL*<@0sI&3Ouh_(CZwpfnx!~wJ=QMiK>Ag$H``N!@~Y?+y(f1nocrkGT?Cl$OCZy zW5C_M{~a*Ni?Ar#)I7?H>K+;p7N3UUFyZ0QVaGlh`k-r^uy%7=qAmb=4tzh#zvIN? zM8Zebcp>k@&HCi0eJG3J(!uxV_pBTo@)oFjz*Zj;dN*tGRKXuz7C2Z9orw+LT2XbZ z5Y@~j7t%-7JK%U+1%G<$*LIpG$B6{pOGdm`sD4QwwfqE}ThQ8JBAyg>y`;yPLfcD^ z+Csk)XF9{dxtsr&zkNXN_gEuXAT1DFz8UtirH(z)#+fL8k&|(M5&wTj8*>y5#s^q2_QO9eM3#Ttqaqrd9!h2a#U)%FC^B@SN+^zmfuXxf4p-R9FX0 zaUv3zNyFhFqTh2Nc(`=rg>ra$Un&6kFXYJ!$+$0Fzq}0Wt_v3|UY6fVNwTiwR$TPc z=B8HC-B1VLxek~1T}bBs2ab}Ym5i@nA*RU4VZPiJJtwdHLTd!K-?qV_|E3_qhqz^h z7^9Tka!uGuPQ-5F*&2bI-B{cZ7wPv*27w|3ryGRz4auxCD8jjrS)IZUujWki1~E7Z zHyQvHsJH{3G~?UJp9Yb?q^O78s2AoWyED z?9yhH1hS(D|G}}jnH+w$kD>&0?-VwP6CnS<;gI$=5LQgT-Y&@v*4*MwtDYQIJZ>lY zRgU8VxRne%)ZR{$gVURb4o+`|nn-(G(sjMs`tDApcc(wDbx&!EbCGT5yE`LbK6b%r zOWiXFRIuI48p;yGQ*a|dtPb0uqP2#LSgACg|08gD(gRnXfHt`$~7z!`kLWZxs%4G>)l zLIq4N#L^WT;SgAdAieyM%C;VyKD5~2ptlw5RvTrkDf82uDE87q| z0koju5Id2~)c^=coaPn2+xDsLpsyJQ6Y^9AKLAhIaM}C7;z$*uyC}Kc64Nzn?dxl& z_u@R~S_j1T?w05Vt{0DLsEe&L_C}1kARU+)D_R+)_m!Z{IS1^%uMEg1%W~1}Z|%h5 zL4R$Yv~+sAn^KN)w7Y3#9$YaPU_Q0y0l#_+4+_28O}39A-p55EJ~w8=*NKB37s@t@ zuh<{=zT!3lbj7fG?C@o?J(u4rtziTKb)^u2r*?r_vN_e}?-`4MohK|EX^LrYzPxGTZtgX6B`pE4MI z6^P=*)L1o8IrCdd)gTwXy~&>Z_GV<04 zXLMkgTNT5&&%mJ)uy{W)z>yLcb2X?xL9R5b5lJ| zY1u9@4JE)PCUZnqN21(Ic3Z#aXGszMH<>&D>w&?)x@K|@fs;5tq~Hz!)m6Y|S_^3| zBtx5Ud-q6Nen{qi4@sVB5Dwwb4jL}j7R@nPxv+GRI9yAorK909NQpb(Tz@w; ziQ8zR+!U42ZA7%5GE~=gwQ6eRJ+z+DSZX8mZ0(NPFKTN$B4+&TikR^eq#oCA3&9yA z;Z#bZmR}_c0Rg*C?EE{x;(>G=QadD6UR(D4N5}puT*7#)Q2&}1KP4P|Z7K<(`1v)B ze&W5|nQX!&j=}F)2yqM`H-YM&10Hz4r%o9CdM1t#X1tz)R|z$*=i+g~Yp?646@>zx zr@h2=>hrvF3U#Kz|4~IBkK|C>w&s=K(4r0nJzow+9gf^b9U_jdrTz#aL-dhDjwJ7U zVes{7)LW7;<&9MQsxa@3IS_UC;TyB?lw+YcYT#ev5 zZ#N}!Wfxn$8*ZCg{_ci2Z!Z#e8Q(A(dvWw0V^wcrxjy<6pL93fyCul_Mto-O#b&uL z#=XxJanYxiyF&)Mm{h;dWV}71o_b(%$%5qfT95f8k@cyHN_y!Mwqd*#OW`eGO~Dy`+55$XSN6PXLb;sezl`Zoaz<;-+`odRGy z2mnZU)G=SsuZ@oJr53^2xoNB~x_^gBadE9W8UUfr5~cH|eG~U(^1;>?Ur>zksbT@( z64r;L1Eq?4Ku~87lqR9u7eV29ua9Mnz0t-_*A5sD%12_0(D!D#?Sy?(@}fQ(V-4Ub z|BwR!oBkIU;D^?D>AP=0_#Id?0H}*bgPD$ot_Xgl7~cre9pHxr{4ic>;2w^q*u|Ia z1V`KLLpZ7j9EHIP4+Htwd&2-6O<8qzht0I|B2_%G5Lf5=+^vbG;ZFo~-st{R zv&I|k!CrZPRd2$BT5q&F-8`9qFqrP$1Rx|45T-@=Snu{y$}7K(pd@>7kvak}RDO1Q zDR=RGHx;2Rd8aQDcm4-UWxcozz>rP=mRw0TfTLi{*%PIC0LEyTrU)ZgofQXs)V8Y9 z&$$XN`TIo2qbuN4=-CX+1 z*%N(KObrBV;Nq(;mOJaRaxc5;xpvnR+!~jGt8{(frlKd7#M@kiIx>Kffn43G0E?Nb zEkeUimps2n|7RIjAKO$F#qVwVy4QVR*%%)Kx7Th>%Qg_$0{bv=YeVVQgl$ZqqQ+%F zQcPwbNP_#rZjdOS8hjEB;1`U|@HI+Z0z=XP`Uf$Kt;A$V2u@?FfyDybUe{6T@4Qwq z+T`@ybI*PEzIWe!ALqPtet1#aSSuB`#gx0T8Y!kAlc!kQSd2swGLO0d5J7;DhI0&>YtC%@Y;>Iaab&Z0-~PkOxV>_senHYF#k zV3!5nHOMkH05Fx{EyV^i@I%exMit)iDc~jTETL2qLgnA+lmsit+E}zLj>nD~&w(%R zgEZ_fFmgy!_b*M&Ad8LYQ`-Tz{0s)_Lb= z=XYMTmxVssyW*l<2y-dhB1|*$I&Xew{X-abb}3|k$iWN2NnQ}DS7kA{!O~us<$P1V z{CU04g=yvPA&)xH?+=Q&O%u|KXd!z~#tv}i&4>p}h> zJ)&ix&kBiG46Yb#m#!#hS1;(1wJg>t%ITnh+E3H9aHV`P&sT}uA+{tofE?!44izwS znR^+)K(!OTJnh8Wtw%L-o1%Q2T#WG!tN$M)xiqP)jWfUnOe!t$Qui@?eHcfA+QzsQ z)>38Lq_Q$@aUno=T5y(tFP|=kXJSU!f;15`z*P+4F}O7JBTemCbIiKZamHR1EO#2P zN>|1Nr{~goe?objpe{}ETz5Gxj|y};Kh8~gu7vV#LSxDW-;G#VR+3PvpTO8o#Nd6{ zQ^~E@B73kJn(LUS3zJ$UcONg3BDlp*fwYL4^Ek9_De9}EmD7e(K;c62(DB*6hnGmC zs3D5Z=B`QQ4=jF?nVFlkE^%N|`FTpCf|UZy0rhi1nsnQn|FqSp+kTgpw*oUM2fKO3 z&TenLvJUWiqF+&ddcrFwA{n+hBRLKH9?LU+g`5LVr`KQ5nd!QA@0y070GIg1mn8qo z-dg|Ag}U)BDHW+q>vOI%7Wt+hk1deSmU?*QjnI58myez(D8*!1afw!4A#;B^Qi5hQ zAu#uySR-M|ZNCLa;H0utzI&p~dc?cSo;d>C-`rhx{Vk#Kkhj}@01g_XGj%zz;3mw> zPI+lhKCh8i^;iH)+R;6349KrQqR^V#yF-jl_;2Em=_1&&L59>7Hifc8lw z8z)r9;)2bbG{u$IxNJJr>ieV&v23MG{B0o(-Hqi;+>ZJVP(8{H@P;ZTuI<XJVOuX8XDpzm7z#!UgVVYaEKWEv_ zlJ|!%XACibTUvbw@_J&AdwdIgcfp|w9WsW6nFRkU7jz`GnqMO z-kEu4=AD`MHmB1`+0Ro)E>n21&_U^KiDik!m*c-kjEL2WG_})I--@(IgT%M`W6EOx zx18Z6NL=MZVssx8%e_c^y05jT{PotJrLUKZow^IsmN8lpQ)eK)AZ@#!-ZthB7$lzP zN1_7CecO*(3!+gnYr`m+fq)Q7?%$8tr%Tr!IWM7HU9Vkd?zQK93F(?LEa2Tpk9yA7 zNo?$Cu~(N}kkrZA-r5CPF^n>aEHtW4z97ZJyUqnB(Fo7+|9S4UFBp1;GGZ;jlY9bi zhbBT&0nJoXuh9g}1=3p>Ut2CfGO2Gs>Vi$`O)eLYeQ_OG^SLm3AbF3RDh}iaHj!Mm8^qGRLPW>N2$~MoEM~7&~xJqQ!fJKW&v`Q z8Du?8it|TjalGI3^5>7%qr1=JDZWBT8YK^TO-tUi-5v8*o;*J)-{E zhA$hCj*$8F#`Qhn^(Pw`&TtBe(~eJXz!Pq}Q2Ork7#7M)G#n>-2u7hg*o)2J@g_q=?P9)0>X<_1Ep+#lF zB*DZ)W&W|yYKz7<1x*d%_156#cs|X7w;=JZlxD>{khor0rO(IPAQJr*d_wTm6VHq!#pc3hS785X?LEkDrYy!mzdzqCZCf)s7qib6Us$< z7EpNtEHnsQ!b}`lO1mv)`tCxrNn+vzfL4_ut*RuLi?txJ(TlXhN@xy=AA6w|?RhDF zl1{Xl&0?qdOGt~Ob)?e^K4n|%S5YVI5G=ZmIzt$gd{v3q1_+T&b{+nxhG%%cr(DQa zMhY3qC_E8T3HqTPW@KKFQYZc16TS}V?AqUZRO_DkbS>1nu18h>u?80-F}v^kqpvFG zQCd|HVmSzG6BZBqFyO^Vm}8reh$QmA&L`v*uS<2t)Z$K*?sL`_!IX*0l!ol#nEw-?P(C>(tuuCA#Mf{P?o*uAwAFt&u_AF|Nm zKYcl6_(Ln7GcDdi>GZW&RC=%6M3@#k`WRh~CC7^Og;xw#JEBFgFTG3+Zx{<#{H_g& ztZ$z+vADxJ--5+Q`{STPZf`97$HIG=a3&WhO|AvXD91J8Cp7T@f{ z;tM{R_^QO{l*Rg5QceaKAaQ~u55$KhERO2$cjZ{;p+;EcY8d`w5U#(A*zi!qsvvz9 z!uJr4KsXKI5QLN{#O7>3tTQ#9%o9rXd*=9MWyX6im==TZ%sxz8IE-zZ0$wOAGrz zO6BE8YFjw|7b_B<6Jo*^&3vp)#;>>XC@m8FIC#2boGbPOty1Q=JNjC}`DudfEH-@N3b&SvC?vG31Z9O=Vy%EVqPovNbEoFEL^vU`1uJtTREpVW2Ht2wxWsmaAq|*}GQw(U%@iF|7 zf)XC*R>0F}->iam;hk`Gta`QtTtuqFL5mOhuwm5_dBNMJ;pcH~f#3`uk*xRC@pvc4 zE8SR0i^w;nz~Ndd&P8qTAB@hss`nyRI1;a>u{cE-6=9BgsUI8aO}{%aC%G`t04?5> zgf$WIVXsMq-c?O%4FkmF5l{(Jkeq^At7;#FflTTEjaNj)Cp9+Akq~22&@ag=a8Rd&lVaY6L5j> z_sD#lBZNn#MGqTz>M266z5UnCjFH}!-0b&63FT2Sc#=>PrNeiHSED9|Ztydm9G`4; zyC`v^&=!@3O9g*a7TzvoMUTM$5=x>ICXMq~G&Am5vQ%it;LmG@Z9e<#&2TQS1&N>Z z!>J`6>=#{mO$?9RssL1iKebt%OYl+)`=T}M9zRZ1@N1mHCr=Dd(b?`b%JmV>w3Upz z7(ugsOM~9Z@z)kDvFe^cx_t|g_^6;5K3&-|$TiO@ro?8UYPcS+6J8yz%Xwq)C7@uG z+U8Vol=zQ+l)BG>b@cKdTz=12zOR2k;tAh)z{=-F=N43rooxYc9uQ-UUDGX6rSib)H5XW(|@2Iwuv!%(+A zCG3oe!|w@AF`CHd2XHPsHaMfpi8vWqgX^9WZpI|w-GU-^d}tz&zM%mFe@=;^LRoB* zK{}CaK;ohkNT+C`c)SH`)UfG&<-@y>POib6Tx|6r9o{9^P>^o+3A~;5G+rXyjLTY>>Xq@u4ajX#WIUV7tH)-+ zP&N7vn>-Sn^YMwq@Qa#mH5KQTdDq;B34Wu@x#k6s#nvGBma#v6s zAC>#VO{Am5@4aYOP{}qE-regQsy4vA2vDegs7yViSpExPV&cStvA$&M9ay8Gzylc@ z20gw0`9%Uc^}}e~^oskF(x%F;E#N98Aj6XuMvR z2t0wTjIybkW=h#A21p>oi{MNlGbsuKN%Lx!criyGF|>q1xkX;%9UNK1m){Gi{TPnJ zS0&1bx6|UggBbSE5|aX8W_oY9~siBS)7%&oN=pW z(sz+A*aF;G>p9^IZWMmy=uPe<#;*wPYsaU&0-$UYBPRG5F%CkEFSJZ;RX2w~@i^=9 zX2dB(n}Bsmc&VV#jTr8f@J?86KoSoQh7yGsztELD zj{0J=piS8W8NYgkuT#e1bHYH%C?#jPsEy$VJ?{vaBgf#Eg~vwfsFG1f*NzOKV0#x* zmoQlT#xGE51;JQ62UXsplhqr^C zcvy+*W|AK8>Tp3X)0 z4|M*?@2T=}OZ}e5eU_zcgWoe(n3z5RPZgd`pNR*AZ`0!@yfv`*Pmxxg7)nQ42z*BX zz8&Dz4K2S)WV<{m0YRW*Wc;;&s z`scz6jz;neadi1Fb4D}K7eApR1*bl9va*DBt0=5lQD^=_iq8{UG`x<#2*iSd zStF8q{2(|OJDavh>eErv%DbkFXqlsDMqE5dhYJ%jvc}0v*BKE9!iPGTh#h&IEl5eq z<@A$s<~5t@JLKQ4#3GGx8yrQge$T6|ARq0?m{t6e`tIs)8{}!)b~vfL*qvr{HelVG ze2AC!OfY@Us~jm^!(`VR@2(*0Dqd4&);3sj)CFQo8h_J8-`%<#Sc@EmUU)E*w_T7} z_H<7u5hkErdUaJ#K25J6!Ue4VwZKnuL(+>Ksv^=0TkMdSy!-~8NYSSuH6$Vucr(1Y zOZpG>5V54J8JHCgi{*VV_YG<|J_bDJ2VoBeQKhyCYJUl87n+_3E1*|jmWQ_mPq`?u zc^!(7wu=%|DdP%3U{4XT>@2i`#Xbq*%6pB02k zd3auB0+TD;&KgymQ%bLygQ;$Fq}pm%^tWxUyxm9!cyk4}#*Y0S!OyMHmtZZBVBT6I z$LqQ%nvmgA@oC8Yi=UkHFexpBMY1JKZG$m1_oC%rK}^zd3SXOcO%OMtaYd0B5Q>59i;GN$yE5Hby zBJ&S)%o19L5h81WErUO?Nwy}b{At`h2e@GK)}vq7&q~ZKIOe<8%dd$v6M@Oxb=HhW zkC?``n!5^?cTX=|!>o~sv}_^9nfvCj&IsrPTPakINiU~<6kBle-(Axs&WH{1mb)$$ zY43iUD&QO~2EXU1pV3yYUeKe6tX?t1Fn#_x(uTw6|JEus4XaTACC* z?+XjMJiHX^&P%!MW+M&jI5+PbR|4Pd%GsFCX8{u$Q{eZ^7V-_c;fLC**UXiFc=6Nw zBcu*sD@@CpYg^A9(Vtt2xXha(=)9P`>?t}}4qrmb?-@1N zX;nASRt?`_-BC2C%b1o~j#7Y)4k{PpmDg72o>lr}#RmQx5M9V5LA)1_^?MQqcSz40 zV-nj0TKuHFVO{hlz$oRp==)WPd|NL_J8ml4h!X`+jX60uywppc7C4F>H` zR4S|(P%ENTZSUX$STU(at!|U9x3*d*GPG_jrPDp*_l)Z|!kSkU`#nB5tHdI|=OEdC zfhruKDA_O!SXUT>-eFZJIj<>VD#QQZh%}^xkf>R-n}LKQ35mw_5m>~Tdxr>2-Uh=plz!d-orYP7lf{LadyO-7YpY+36fI#g z2jh;0#RD9=YjG9$}#(VbYd(Q^G)?Pt2r&|yOGIGv63`OH9r>&fT# zKX=bXklWve(%*NI`Y8PfCmLhxtv(FpkUVwry~huq?mmr%$;-R!XiBTa0OMcF!Gakb z;D|pScon#5TW{H645f+>)BJ)SCQ`RTbd6kHtFYZ&br_}FdRHDEsyhPeo;1NZRP}`R z|8vFP51x0;JBi28PF_^WN3QtJMUBxpziSLWDcl>U#a{|B<2AM{s5|R$&yCA+TW{v! ziY_^A>rFds8#DRd$ivmEi8hkbPwwRoYfG=b2yy{vOb4sYT{x1cSQE>%n<9*!O&*AJo)-KM;2Lh9f^o zM;be%C}W4D=D-k;0|dHUXN)rH#GBQ+-cFsa_r>Lec)ydPK$JUZPocxw0M=^jfbBfd zI4;B}9;2l72Dc#*j zAS3EfM#SaKrC9UIRI+=e@_+1J10JdGS1Z>*S!dJ)HKg%diZrsIwsj@v0y|n<4Q*@K z0cuTK@qp)g-_P-|&0xdEf62hP8j)`xjXAls1oF+_RQ`3DTrO2=Td+nn`cE?ya|alb$-v~{`(U3>+K5Mrm}`x=CNFMr3;PXr}ilF z+e~HUT}3f-B$|WC%A>ky8><#^SQ029CYFwXExkmd3`VgASUTZk-;*j-}9Mw32<0wk4(IT_thnB~>1rzgDcB zCk53~Uge!^6SY;{3daSVWE=q$P78SsYWIBa#yjzvkzKU>u`=wVri1mtiglK(GARhg z7o|@NjBthC78)3wxxVeNL;f+Wq5mG%^wn;#3ad5>03aX9Ok?MVNd0Rg8+V2_TQw84S$%nPkyUUuX-Q+z%Di5quxuC;I zH2CZR5WJhH3|V(PJCDV}OU^krhKBw^0KH(}-(94_|LOZuST!-m_CI|G;{2YM`X+3w zFW4`!_D^qcr88DjqDZM=lR5Iq5O+(gkw|~wM$A-JBXdUsd9Ui*-WP2^dbXoUiZkdN zmaN8F!Z9sbvHix9)s$9p?PF|rFMJ$a3R~R-U9TTbcm+*(A=vIFkfjYr@bWK(7U5Z1_A-nU9+Tun&4Tk-!pO$gJQ_Y7JY=1B_;pYLM9(eb-#PT;SM3Mofzm(E_RFOV4s4eA+Ypo>K$Q zavEOC4|qzXgfc(an*7=K8o@-Qgb)k{R)|v}E{3=mVk^W}i0dJ)hxh=*2OvHN@wwpg zUb_Xj9N>MTAml=bhoDaNd%D0H*e)$uZCePlzGMXvNdCZ#^!oKusp-5FlBW~Vav;Lx zUqYHZ&jDNQ#$w~BLC==H`r<*)tAYPbeJ@Y*dp7!CE-UZteFlLZt>4o&xW0tqX&$(_ z5R+ty!@S8dsQq#U^(@kc_^7D(oW~c&EMjc#l`=TajRm5Ld8+neBhFqYJ!)Ji+89Op zI;q(B)XJqj7;^SWrM1_bNEbiKm~y%Cw3J+RS~7&k8|)INu}dKug^!NFIa{Sk`3gNL zu@+K$q+!#4bs}wb37MX~ew0dI9+IMSTjx))>*i10XR%$g5<<9Up#h}Lr>jAF+<_-~ zoVuC-6H@hX+3YFWn)9&l4T()CrQh>~Z{LzA!nft@t488SlFpjVnZ?tz&T?aB zKMpb@&D^T!(p^<`+Fh1G&(%Q?#CrXs@9%2cNs~~<6 zm_0&KM9l0Y;sObOTS-Uq~8Sdjx5fC1@+!z0QO$5WyC2#k)6~=u2of&OyQ* z7Z}QOupn5C@wiynU>t*Mg(l;3>e{ARYBgWpyBDY~fxjM0-`)G?e$Utep&&nZ_RePi zEmhfgP&&)_DGm5Tn5sU!1EpSU1#>z_RB4Pj(T7q)z$(RvbG;}PrkGb0MZ5BVb$R0JFv(Fc!q=O^L33Ba|Dbtv2;WGP~p?67G}J5hXP z`kU_B!?Mql)&D2Iyc?<3*Yr1Nt^2GWnbI!&Y!xg*fqCTAvHof+8!+n^NX&zzU@~Zy zq?QyAj0}7RJWuhTaz$`IxZ?T0xgwj$vHp&q=psN(t?Bnr{a{f5J0LN#?i8BMZNU!^ z^QUT0QNL%Su(RO(BxF5jL?Q-pDH_!lg&j+3k{_H2CT08vEij-8pI?}OFA6Ufrr~dd z{e=_DPDxJzqQBJ~Gbvz~M&bqOR!vRK!dQZpe({^8kGNAriReV+a(^@ zaSG0H9uCBB2N~-^6Dj$rkjYQBeGL{FB(9Lsc)W`~fW#;IWS~7j;wG>?Dq#-TrU6eq zj6GSKENHl1`J8RZYr8ORSVXj8o#IibAoLsuc--)*Z?-r zj%!v7rHHQO=K}E`@o(~^Qxw;4M7Dg zD6_F)3#hP>mg8e=ogp-hj<4~H%84=sB@YI9ZP1PcpN*)TYfVF+PrnV@l2^Q0bv^YUID(#Rh4M_yT@% z#+3FGZhhE8j!1~Pum>F{+`6#Ij*r|1x}#C4FK_RZO>3omY+iwAXDFXyyrT1jJ2Oo0 zIAL=e!n&OWB4()F(BFfUK#=%{^CNd5$Vkt$2f4YRf?hOhzIT&1s@HB~VN;c}C)|s| z=6mbiMB>I-1-@Ko3UpV1@AuJsbTM;%2 z{uhU7oXNfRg|_z^3wpVQr(Gx9>0x2cPT3rZnMk$ix~{DREsK7CE5SI4pKmG<>zR)M zYIN9TfI{xa)sS&OCAIPynj^*DuXa&i!FWdw6PPuX^#y-_Y^D!+7*H-UCU)UoI}t?K;XySHWW6(!MZUOS#Z*HtkoZjMn#Fruz2T09+VS1 zixa2PA*gE2|s|JO0mfo8dx zXF8Q`{{%x|{Pb1=L!irTJPmGvGcE&W&!2N6`lD_o#emBo0cLjYGL3I#50;At_JUfF zWcKCp8w+Vzl<}9ZgFMje_D`mrqXSjaZ~wJ0*!h-}Vi>FE+U1Z+2FXJO6jLr{v3Q)` zN~DAxMfolg%eL+)BBf=!YzpVmcv6LIE2$XR>RmXSe*1IiX%>6URq;Mziy=&bfKL1U z(10qH&q_;dB@O7n=j~O9Nx9?DBfWLf6>1!4`IJLQoh#H^HJ77$(R?zYQLTlVMVcK& zWSW?ctN@CaZ1T*uzq(OSre26p-T=F1_Zw3uk@g4hs6V(dqgQ)(mDt z-JB9u)WlaM&S29j!rFi~nJI;#PQKvi4Ltb|DlaO0uUjF%*Z#ZfRE*>z2*m*Xf@WdN zuMRx<2CU+RVN5SqO~H0j6SmTM^e(rw+DR53EIQ?P{3VG|%>$_c_JlboElpG@<(G}7 z5_qcW&c{iBcnmCMo7_Q$j&@dbVH$~F+Sx-vIxQT~WBZu6>x~2iZ$sj7dzy%Y3JQ~8 zAGF^&W-qv-qF@K?QFc)vp3%-UFPPodqErH5wbYx=5cB{!e`t<;oN8$}rN)LO2JO(w7^R=|$~IePR1gztZBg zlmhrg7ZljWy(?3?ncz#{nuFVr=4Th|Z&g1zw6a;P_QunVcU{Tia3)BXk!u0Bw++fb4(DZaJKICrx)d{@6{(glJ)h99sFL9+eZ1`+|SB zFzv?!-HZ+GDLf7gvAkf)NxVC!Adz43%N~9bG>GQQ-IQE!jcTpbtPHI2>!evawu=t? z$q@^x8Mzw=^7R@{0~OC#w`OX(02$I0**|s^eebGH9QIKvKf}B3&X2IGMt}&iqv+c| z5Pon+(Gw5-V&KC9E>oE|C39pidOn_)^I?2^s}4>vvX-O4r|J4i19+fmc{6Zf&-E$O zkMR=&P|6<-+3yv~B&=WF&C<7k-3Fm#9ogNmV|=#T^+@*bV88!zt6-nOJsIxQbX|Q$ zW-w^TIqmaY??)*oW02Os&t3N5vPqU9kBDQx8H3%wsl3!b$r*mzb>z3xtKPY7UUKX= zepTT86>`E~b-i=j2=BfQz&_SyEMawFDVTfb_JczB%n9L!GP?U~TDXl?8Gcg)zjHfX zm^U-dwg=qU_8gghOBKwBK4~c!8aDE1OGg}W(l&$7)z&LB_<20qQ3BlrPgb`fWDfDp z0LQo>Ez+?P{*Dp9lGgH@`5Ugt`z^k4TeXV&O|c4a3E;WMFn^wJK-qo zv$vf4Tzyl`3KM2&a&(}t6)%Gk z2W+C?98;ib+GL94X-E7@oQ*Ohr#e>ELgvd3Gc}wyH4l3H!t1kQCfxBWb+iQ-gIsmz z%$kYKK|JPbt(52;U=n}5e8;7NWpT8RxCKoEi%aNb0!gHvbHdeGS$Mw?Ia?F?8RYa{ z{sC6N10ZLR(w_-Mvy(=?=C4vbvjBLju=H}|7W@f8m0hA8B7p3E3c(@ z6Lk+QRCU_Qdta#ad#(-25>MZe>IhH|2!r6@RcB3PQqi5?>VEnaiFEL=@F>J+7J&NB zKS+vG^iM8EGr#y=;J*j{A1@YN@hQNfjb+3~B}OCPB0u2w{5qJC+3Wnpg;Pk~Uj^zu zTSxDvK_^7(jW+S~I;;aeFPP$Ba1D(30ZebGR0-3Y2u@n+lY#e$0mTzcjbWcj(+(_L zvYBiq;M7VBFfGOhOCwiCHcu{#TNzoKe&bpvH`oQz$pB=E*kt{jp8$P`WR?Zwb_L3JXHt!4I8>+ zt@}xO^T-_jBU6;~9F%xG(4WWZlAARF(`%wN){+7i@RWi>rf4S_CzhV#B4Z3LTM>Sb zVGyVUlrpF9nCl?kiEX9*fX%n*j!E+H!TsDarP=BlitxdUD6rWb&VL+>tx1~@jqz# zz8$9afc$^_p56h{K^1-R2Jv}))Gyz1#)WjU12O?TcfgSj#3?($`z)l9c*ZWU4Z@O?iS0B;O{e;fcm1mJ5GM)8211uA^sPK%rWUG#XMVI#fc2C05~0Dc=l zr2ZRXe*nTxzZ`&AAAneAmwy-qosaX&ct#`JA_M9a2GV%B4HB=D0-zUP8Yu7-6jwM9{Bv1p|zSgAT}(I4|Nhkmmi=sL-}I{7IFc`qTKI!xrMB+I66+RbY}4g z`n++F{J%2zlIfb`Jn%IUIsd6SB6QhvE_Tbp(UJ!77uwt z%20!v9Cg{jQ_UK+HQhpq7C1I#9jO-1N|aH99?glomI`phx(?*G9;)bscx7NWW~Ojf zENX>Ik7{(|p%hJyLIY9dDa$yE+Byi9C9Dl~D=-HKphZY{Ok-Q$Ov)yf)i$A2wpGp7 zAECtuy>TUS7^`A%GtE1yE+M@#c@0Nt@fK_rW+I1x+Yy}@*%2|dhSvk;HC}2rsPA}P z?{U!W8)!-x^t22t26bC1sPyK04Ll3%SS?`xL34TU)m+(B5IZ4m2kLAkogp1r4T!u1 zF=*2Q9oZ{fdQ3yPC87VZY#bttd3-`lGHk63pLBVlY0%T=W$rTtu*(T`k848b`mVal ztSDIxqi|k0{P_4d1Xf121?kFrJD#CRDDYh5PoUN}p^-NPJbyQyFT6Fs9FG@n&o{#b zhb+q%_?XaRnT|ILg;izvpzuajRp@(taKh@TAGsPzTp{?Y5^$1`ut1L|2qgLU<_0ozA$@OIm-N}gtlZ{Ca>Vi#ljd$l7y!gj%H8v zO|Adpr=8c7H&wTwGn9u8)pK5$Aj@FdmiAA(5) z_ru@(NRtQkH}xZp0pf;!9Z1zfBL~X1d@Lrko)V@mO2RF|)A0ZC(N`DADBDN=eJk}~ zw1UdfKDa8g*FWToR@*|fqDT{Kz~VKin&e~gUw#ZJ4pNr_sSHS6^fT^6gf)c8z~T?B zwN2|lyZ&em<5q({6pPh<9WXKSOQ7SdCC|&iB@&nz&AufZuMxtnGe?_iBH^T^96<$d zn1Jm8{&F2?E|@F9D``FLh=qW&+^!&auYe$IvyQ_vh3~AZ@asZRO=05C14LStJM#HG zKshmRH26Jof8aVv9k>=AsEHT;QDX$h_z{bBp*ueZFF1|e>i2B>ToT-|F@j~WoC+Hd ztcxFws0}#&RyIs;V6AM!fF~Y&-)pth1B1faS|b%RD4ea$V+K6$d$%szlKoJBz7?gp z9K?U~5&t%6wgFFE5C8uH7aXa4y)~4#^O{9vR-@)kixt|t2E~_U;MIbA*;MNNLBaS; zDz#-$Sp3XL3ViIhK9ik@7bEuOa>SNBi`eln`q4ZKs@NJH>5zD>U-hU-KtamtFuaGuc7w^$rYLy;ggM6^V2D1=R|ZZ5e3sU7(#7>(Z=SRwA*-ch7~= zjN)tdtBpn&-s%3|Ty}VV$qsrJX%-h-i@CqMaN3Jbcrsx9^Uii@k70+20)^HN(=$$# zQR^h-dIlh0MN$T!f=^v_X$u1-klym&CBjV)Ly=id&??oQcbx+DtX>) z7Q*2iTxVQbVm(v;ogHkzHEOukKsEt}C$}bS$h}%w%zHgIfj%CCwr4uFN%J5scQWp6 zK^LWM6`9STGLh=R*b1Zl@?xugqslsBqq^W&A23_7*Ivart&O`I1=E36paQMtwZAkf z8#kNOPVH+E@K){wI28u9KAu4AD8m~F@jvDL%oNvN!4KFxeSJfYnfv_bT%Vb)U%K(C zN}^8V?5ZW>8nGll9n*+&u5Q@fNUGT!XygZ%eq&<6=sG|S5Iy41@l@$KO))Iol>QH0 zzW|-(!2*A@#&}1WvlF~QZrLM#G~Q7J(g*AfcTI4M?rS^oMc-+%jCM5Kt+UN_EEUzV z7dw~sR#Y|L~!+OOL6*w4!|~oqED2OnWME znSU|cVpW{t1+r;PCA=TQCOLBunpVw;9A>pF*O6}64|CE>`z~>?;w-MksJo71m z-vIDPb4=2neywruD`DPO`Xd^*6;ckg`=}|lz3P>{uP7TM8s9K6&b>>JhO_Zo7jG#V zB8TM?QJ!stO1^G>OJWS<8t9N-t2ayjBDIw!VcgFTWgER=DOa>)(F#<#VGK-#(s~@FWh=M-u6gqZA)ztaqoKl zNU~M|N2lxn()4-e_{v3!WkB$u!2=X4&37ufA0(AsF8pwl{qTpIL7VzLpARs6UNhV| zlgS%$!S7;-Ju}~#q9;ezo3golpJ%Ku)U66xFFjIw>enz7_SMk;o4?ZNOI>2=1{);S zOY;q^PNlH|buBcM_YPkURJN!3CFbrXNLjX2SDWs2R zZUGy^fZfaXBP0w>8;)$S2A8Td+oeYg3>3$rq2CHhk%Qn`9w-FnO|R#0e=0mZI3NQv zDJfUm6v8v9dRR_pq}y95 z-Hv!#ce=5Lqf#pu2!=Az=C`gggk7 zAfV#fqKA)8e{MGp-XAalvb@i;MewXlu)Wi#;H?esue5{zgr>hpN

      Fc+$R=Z<%D5 z^8kBA|59-{3hI0Wa{4_8F2&)oO(xfcCoLb;B2H>qDvm%t7vXIBJ@;B9I0!ea#FG@~ zE!KX|O<0Y@$H42UYCeo=M^;v;W!@u!jkC90XZ)=pvbt{{?&xFNYM&d}}vlnzY zUFdiriOqoPO<*w}6sT3HaFt8HD$UmCc^S;rNW3{fW+}VxI;fz)OVkgSVS&Hx_dMS} z#NQJ0C=%y_2|8>F5`P?&@zr21W}Lc>U?t7b)#breThQx(Fr>KL?|Hl*S(((kj#pB9 z97YpLg$t9qMHXFMx2qo5Yoe4oIT%z-Z^XhsSA`9`4yA|@nFXJV2TuvTtHACmM6Vu? zD}<@5AEBmug%4J*#W#ht7ym~_*!0!HS1%^vBH@=8AH#aVyhcOOKH-Tqt8tTXZO!rpuv83@!KKjA`>o@yOo4Vnz!BrzQH47LK?sQ?3iqtq1Q3(rlCir9iVr5Zs7X z{N-@V2H$O6Y!v`f0LV`QwGiRr zT!VkOX9H+YeI3X8LJVci*EV*@gW*=tTf)ZmalqWazg~wm!nf<=sLVm(#`+2c^Ep{d zPYRPZOb*{afOVibh1+m)xUt#?x4T~5kYzjMM>_DzeGWY4Q|`LRy-~3#aw_5?r%)r) zt@J3JHLh7_skVqM5!S{AK~kL#U;Rpbhyj1u+J0h7hZcgb@;=B|5+HdFkm6Psmms*6MUyj0!g6HK?_%$J^euT2m zlLezMfe+#2`W*b5u)KaO{$2R6{*g&$px4`tdm1QPNEx{y=<`s6f%`GwbC?Yy@=xjN zW?&5AsuhvlCC}y-lDkx-P;HASOxifpR^&@6!MT6346}YEh1e6DQ-M-z1~NJgd=8Ja zJFPR+xGlz-)x6gf^<#`Rt@*v!$dX$wH6P52u6ip~Fq9frng%pd>{WG=!y=+{r}b^q z-fm32*G)0+b~AXV<+f8+Lg>igJ!BcWjE{hY6NRu%vOKtK33_aE!!9dI!4K@R=&X?q zyFvUzSIExjgPj28407wNK?S=kW^1A4G?;d~T|&jC2jNEYtDDl|ynSG*12^0WJQ&ug zEv8Mar(+RkEI{H?}!O)RKgJCl)CQBqwM#_g?=JY)M5x-ibBt0F?X$8+R! z{|p7{+e~Zi-@>(*gJ>unr3o2 zQY!a(UOgGn?1Nhl>Q2f%g4T&)!E+1Ioksh+ZdT^={LTBY#J>4mVMsf3elDn)jXbh} z9y=EjV0MEGsZh!54@*qEtXmnR5iusiS`&L&QEZ*kiblD`8;KT#t?CdQ=9(^DT2~IuguLd^Y{x5LEQ>;`6dc9BahJDCL&R3;c@YBK(NY^N@GzmKju(SD3Y>0(T4V zZ}}Ln5oW$os4RQ~Y&Q^cgm>SFlWhp3zIfy5@R#5d6JGeZ3&X1#@J=7xgPpwfMc7DN zwx%gwILW+&|FIzVpA?C8-Ry1a|kS2`58NwW4`lErX z{zhQRj!y*V-M>5L!Tp-c?aBed)_@hix;Kcf}WLLO%CN_maG?cv#=?Yw+GI_bJ>vO+lC9yJ=eP_8aVC zQr%9I@lJdl^-y)eyx8{|kNPC|42~+Npo=a*K80t00GeTt+n-|>gEH#&1Gu7YVF8tA z?2;R=$Dxr44Hu0__ti~g&VpquzP#C_yo55rZBO{-FG;pO`})`_Xby94^C+{^0dUi< zxTt3TzXU=#| zo4&J~c_p9=kfOq;3NPrw1;c!3@Pk4E89+CSI{!f-vfVjpXZiQKhcU)3+W4mHYd5Dj zYSela{ZqQ=5YDUU#a?+&yt$8zSP6o3gRc+#qX{ZXpE`g7>l+3rP+s|+-~bw|+y8)F zthd+0P;9Uta8qnm!4NWiqH+kCeB>K8_!=N%BY4B$^jQJ#QGX z`HwL>Iy4I7f%c)q!tVi$IY z48wW*Ts(M0bNn{gr<^Vazsf~TtSZQM8F;0O5Q)tM-}*qUM0KlbQgX^ElINX%*mJ52 zIdIp_l{`E83pmNM9e5=2d=@@O23%g?`)BZh0S<|$`s8qn;Dy=_Yo!^9AHuitF2R>V zh+)398MPAA9y#v*3GZ9`5Wv3&|3mo#xO<1$;9?i~%p9<}5R>!_xFw80URMR4wD18s zZLbQRK{)vLXX&)P_P`rJ9bDPT=gY|FyO0HmdGL8HY#C}G`vhtF6euc4j{3iHB2FOj z`xE4=SvI()5ejbBsoPr1d%+qG<6ur4rY9V*vRwlTJ8}jiu>=ZagVXapC-mM8)!hYH z@!-jI3Yqgi&)48<9Dou8_%0TFaDj|0QlUq6WnxpTmEpBzU-kscBSMnuE3KcK5?;_d z-pSkexk(1!-3dvN`A|-!HQ|N)J2bt^#5qiNFvN)vljnFxe&CsHotv^CF_E!-lhpOib*+*=EmZR#gwm*v1G;Ou$yU0Wo5cg@V*lwgrO z#lF!{v@q~*@?q|tr+ENz8BgEyG!3Mey=gKzQ8Ib^$-qcBSu+;h^L#jvQjEk9P_86H z%=&a-Kpf^w5&e|5Y?n#-r1Lgd9_8(XkkH6N^C44SYX+|b!n+GaEX|L@KJw83sdB?W zXjyn^22gw~RJ&#XYa)w%o}>Xv69I7?5llh!yguObY#ormOjw_bM}7es5@bY`s8jgc zZY}o#oDat#5SgITOo)IJZN|zfGF$CHuY&5$;fpF;NK(~_I*Fjq{SMh zm~Fb};Ri@zq}^2oX0SjWbsu)ZzhS9B*{u7|OzP0#6WLDsa!%O%W~?5%(G1LBUJJ1& z`dpnveFMm1u*JbwcAQA#_gn($+T&p*!SQB#48`xX)|r&;_$~^sGs!N=itDUzz^5$L zLgZUI4A+j|O2HR|$KFaB-weVX6A<%0@DF;;%Xu7?Pb^~?0)-sd|QZq=Lh_zaP6J<;YN0+MpovOLNY1%_GBb{ zg(74U`4ZnCj4^|}vQ({KbI;>!5f1Ii0NdZCJ)4W8O7ogHxQjd8Dzol1#X6jeH-l#Z z)}nf<#y*`A&v=g2c@JwR(HVN7eanSvIB|H=O;QP-Z_v6q&eDu@3vDo%)I%2Ezpgn_F zL(*x8ZAyi^(GZl7-Vg7hAx?lW`+j&U6S1MA5nBkM1;T6yRS=+BG!^pRH6V5$Jii5D zY7Y3qz;g=Rqn`crqNfpX3-y1ku@xBVHD=KqMQ~sPaI&17`!;{%#v&N3i zT9C6S7YUXRl5Mj2fDMG9atMXqPcN$itgVQRw7`ezs)zD_SOl0Y7)p;>xaiMgR;+kF z-#j&CAv8VpDRAXkg4mKjA=V6W&0@sPfj~ouhA;wx0CukMWkcmBgJA*Mj6}~5CD2&N zBuK<97KZQ7&T_2;&mRcn)j#jYDa*&CEQhwPu7yiQb%;G_AId)i>34+Z_s^5PdE0Np z!qxp6LEO&@)PV^0M^J-770K{2TF5$}$5!F713J83s5_7p`W38<$&g#|{|(p~xHNg~ G3S$6yHoMvY delta 22036 zcma&O33yXg8Zdm$y*J72LX&PZU1+lu=mw+C^#39p$IA{LsAwg z-~wD!XkA!b5L8H^GZd_?qK=N@BrHy8VW^@6TF@I>$ZgU#|9euLneYFe|9SpA&&fIW zp6xy7yyrddcCP&#)#0L!wNcn4v{RY3xH6=Tvj`^b`JtA$vbfUirj+wYl=UKUoDYe! zdz-tuR%I|i(5}%g>-tfTC;9MeDG=e=bFx&*|Oo`1hLx`MN7G;U#!_3jv$Y91i zex9|KuZ02(6kxL2_%-Og^kJiA%TQ9Z2k!(s{fG ziIary6j}|becU0%pqwb584pI*%M*IEahUrFsxM7kSLsG<7{!3 zxKj1hcx$<6&yHWHweDRw6UUa(9;=zYyVz`k4Jw%Yu1EkcvNTMSU`65zAJQpHX$=ye z^yy*m*vw|J!>qT8dNQU(e^tT!GaabI{uAn80c_aJY!ZooK^@@?O5GWP*he8mH`w)< zJ-n1-xPW)Musmesh{*v>qcZEtO_WVti3cQAH6`$&<^*f6yQ-LN2(cvcBnY2{sFidH z5+CTzf_Bp&v>d+@GM}2<0?j%hunkyz#*YC+M#37l0f|T=|C9YN7b1HSX&~0J92V85 z7;$$KF2Q1@ARCfmqeZEo)~j{nO7+hfxN(+oE<;wNfHqzpRfw83;?m;UpcKdTJ z_(Pt{eJIIF=`*Xa80Q11F)iNhW%Rk$Tpni@T`}->M2n%m42v4xFjh^;ej5@){RjEv zl6L-aD;A&ZON3!``x4+k3Esd62CB#xKl!T6|z#j$;T?p%I8s&}JiHB9*l2(9}On;ni=6{Np}@I8cM z5LzI71fet^9y2DwOF2RYGgvmGRT zs8`#O!%YvC_!-{+)^=nW%Jew1gKwq@4%M)X0}_+m9;|8WC9pT$5VxS_>?p*Jy6G)v zxCrj-O{D+5J93L)-4#r<`aIVrp$epFm5>UL&4*pJ$26o}#kas}j+XMuWE@K4 zT!H#6fbJ{AFf^e9kBa6`Hsj%VVy1Drq~C$NHbyjhkka7#K|;nr{jb*VphZ&t=k53E z-;xX}*gkbSv68|fjYq7mTo`J`b)`1$iPZ-e{=AX#6jDgs2oP_Ql6GKmkuTu=dLRyv zj}|}gWpujd0^T16N;sN~=T$rw8$NbN^AV-;s4uB9hcJ7Uu|b zv^nPcK5VEl{qDjV$&CRiXp!y}=0ztxTq}_cplVQS8NjY?N#i)kxAU|WX;e+5Ex)^} z0fyD{N);vE8DO{_uo;j0Wywq%;E;G}AdRbPVmztngjFt%_iH#boEBS!@1my+iH9dz zyg+bGJS4=$q_Epg-GIJeJ3JU;8d3=xDB%4lK(dz$FUJf6uIflk0nQd~$E3%G_doR% zL2T6ji3Ffw9-ECn z7KRLsn=b(c#d(@6uM5b0o`%bB%5PvewHGG6}#(jQ!m zL|(Wybb83Y1~iScN+|KXFgY$0za=b<)8`%;co8rkrCoHXG?e&TA4)su#Cm$wS$DvD z#-F}sACQ6bemU%_ET@q#IgZ4C3(axn=!yXypggo32-Y7F@V+I)sz>3If>}L{x)dku zQfJ{CLbH1Em~Z=W9c`uRDmN*Dd!mAq?V`jR{jyrp>@DX{+hw~7deF+BHWt88J{2nGr-ADB{-B1|=Ugs%-HEaWA!J0(K z-O)SvZ09uwN=y~b#*e{Pp+9~KZWkseq-Qqv->%;b11F1snyrAHqi%}k7kR+EY2_jn zqIqB+xA~X>;Q370nV`)U`f(mRHY}?Xwug+2Vk4=eYB;l<;Sy!B7bY~?`80?5d7MeP zvY^Mm3fB_G4S4`In8AT{NK1($g^`IV2G!|Q0}@xBLV865#o--Ts|LC{u@CrVyG29%IE2BonJv8ze4X4f{ zB~JU_gAzt4p}AkeC_^Jv4~<-<;Z(sAhyPPT`JWQhNcMk9>?I|HXNHYkxXw@bGIAiP zLs2SBZ+R^DNLfnS=40n1bW8!{y`zP-;~PVbq8)m!LCT;&5lSI&d0uvMpX&f z7nJzHDM6JqG+I&eOFbp-@sSk)ngJuYEPRlXOU>~KmtzgU9SqTw#uxgK#%lcoz0_PH zf71=Zgg9DQp~=>c@%h}p0GlGSP&QS=Oesgj0L&A7NUwj6Eb=eH=bHJ`pZ8%6eaz6L zgnFxeaBxH~<;w4cSA8rY!^;w7#IMofuLBsUb*V`KWfu9ayX6o+2D|xZIO|FPRZhar zYKI^{h}a@wxi$`eDs0w{#P;JKYfocr7nbVBMcN^gZD7QOenxy8!lQyiA5C591O9WU za9PieKKm(ZCLArH170{WBB$YjKQA^+L3x{^N8cz$Z$#)!i0qP2s6`{ zK_#sue34!lMv23ujwNXT*%cu&BmMzr0O@v1RusvRwH)xqoXT(bYMHz=gL@6$4tT?1 z3#uDQy5IXl5EnjAhg0_b42@vTNX9z^TSjbTd4L?8(PD)1cV~n?deJT6s|;;y&OpbX z1K!8|niT=>0>5j-$~2>y)m*dmP0oQeIy*3885=lc)*nF!-UKu#g$F9pm02<6p| zrW+C=yQd{sdQ^gpL|C&mgq8AeXkQSnWX4B-*_R8P1)Jq@F~Cs13+r`E2+4XbGVgda zw;0Ei|2lUx6MNwkI!f4?HEJSTN_$ik)`#noEq0OH}WzEq)u)hsbg6iy7t>OrcPRC zUQal>b~(Nn@P64G@V?S4EFLwhWQ%%W-M0>Tx~>%tJ|FgE8(j`O{39;hC+m(kz0Ikd zBRV7Gztj(`Cfg@Tzs#(2Saa2dVpBGE(@o#qwF+36v5HZ@Vp~s&G38=hR#46Y=cqMAh|_ernbiO zTLE}H!RMki{ociWNW(U%5Nk9Jp^-|*Hpr7KL{5$8zx|(L(}TrOvq~s142%0dpkJEU znBNrewg-CM=^UYzwt*gDNK(A;iXloz++0>c3eA(KG{Bey8ZK*8a$ zn$Af#CQ$co=*%Kx9+ZMru+D14TEzz0dQJIq+%=aLkr`#=I=`-&m7G_2!hf%aTOVyE zVujxF&d4kd^YsTwVER) z#pR){+_mir`eNmJqL`|DR=ZwpDZ}UHbS3SoukSjjWZPoPuwKP)H_|YkZ{5SV+wR=0 z8C*7SV)2Cm@1KOoT>a2bS}WJjlOMTolHfH!poWmg3Wvu`5O$17l2 z7akmwfWw8kV+@Mm9#Dk|Wx4aX{s9Bm4b0iAfllD9l?WKaW`wo|7|^*4>YWn!C`I2z zf`eqr^Bc_T;Z%`NxJa+hE1i$$&l$$#T!cj&DtvEH6{eTb>*r#s%N(ud?NDv|9D;n? zD>Uov81{ERaCz%7h%Fn8`c4WIbt}Z>a4H78UH2I%1pFy!%ogx|5TMpamxgL);F)vu zJqR=pJIpgH`n_>J{rZS9N;@BimF%rJaJS%TqWrK|Mq733X`X^(7VEYJo2RW`-=7#3 zCWdTYviVs;0CXx~l_NQ;A>d6Ms9eYB7IiD4D_0M4f9Nw+8Ds~%PXGv^n$S`Lf?2ei zL0=P1K=`p&UWPP(bW7Hdg*7C{7U_UYlW9H8os;7W0dJc?kDY9Lt#44T1UT=#7?9km z25Kq8=^D-J7jB@)P4K*1T5BM0HbD$v039i}b<#7-JEK9dYMiOx zAagRF*dW>&{e>L|*YB2+I(AEOEhE=2T>ta>shx_E1)a2Zw={HzsWU>S^lg#C>Xp6? z1C5?=Wm>E94ih?0N*C9TMQrHXS&YNp~71a=wZLD==<+J2zVdq`_TQT=RSB&bZgeB0N}TsDC12R>3|wN z)P=^_ddiOuwld{j*-_HY9uy{@+H5tzf>mjNL@9%evusSBL?v$RVkD?4)Y0rwIgN;W);}5z9o1PE^FhXA5xe@(u(`f@P_YHztao=q3)IoZ>)LhY&}RQ9 zB0T#(nFCrCThF~uaE7g?`;)`hb?c@>?r)!v{<=PyX$yAf{^Sp2>*z&kww`OB=(ec= zQr1EP1&nDn_fV^Vd_gxCuMbjj;6#mnF%a-VAgZhFr7u~+`9ywu8QsaCBqP;{z@h+3 zG5c^j;^G#|ma<`d6d!9G6>bziw1c>+-BgwsjxudVvCdveD=)6M*zOnkxE_r%iXqjc z(7Lj^da$O5Kig53s%>o<)~=lv&8KmLq@~~6)_a53I4FL`(ojb_x1(4q3%$6q^qU~L zNnA=h_JCS-c}c(b>)xN`3ob6R4C7^@l0E5>D<8fr>k*@m+wP(|7V>Qj6h{YaP#^x&8u)!j%4c)#(#4m+RHJqgtFMM%A{?gPp8*fB!Y zUsz2V(SRhK4;4P?PtwzVcF!ItL`ZE7#1C4MOh_!M4tPiQBakwH#| zGtZ4iT$NhvSEbf{Kwgjit{8W*ypxNcE3s9eJ~X5lB}L*ztRE@{P^rWk>ZC|Rri->g zx7JLhYa~#-pZe;cqiB)A3K!6GA1SgBfZGmnqk_6f=}E;2im;0$=MR91T>3~q8_ZkI z$~{>Axhu{+h`85WWFY7m*=_-^qp#h4Re>%J0vzLx0XEJC?2j?D@0di$Dmneg$w$cQ zA0$@;`AB6)gxnIcTP|9|%0iZKqz78WKsQQhOdn!Y6Mh)!DmxFy+&^<`3s&G487`@^%<+`M(xY_g%sU6d$N z6&VpQ2TOgkErPUG69sc3hi92@rez*5xQeKGtK-+z$fGV^m8O2aqPr-vcHL!Aa#Er) zVnsI%%F-%i?2J%-5AWhv*RGxbv&WL|41T%dqNxORg#o8A!Kc#O$jf|SEODKs5!FpB zA<*SpNP%Q)z?<%~2dgb-iIy?UlN7emweC7}Ls1zQ0HAoE%T11)w|wsF`CA8SCh`v? zs0%+a9cmuUrTAWy3LtNl?@(gE`;u?`)|$c(B-Y-3U1ynpA8Bp2o{OKP0BM1#0_Nn0 z>xt7?t;`dPKsNHd)*EX;nW60&wyyOvJ1M=)xojN{G9k-WH(p=1j?zi)gN*I2>=PBV zaNu4KrSA!Vu~R`4e(?*bC;yxzjU#m93y2B%s)EC(@M3N)?1Ca;yf$9a!_h zbr%vQYeM(|4BDT7caLD6oQ`)2%O{T-mO6m6WU#!1G&ih7Fd=+4X`rehP59enjV%>v zQ%dgD2fU@yGn%ZY`@H@AT29A31Cm3b6wt?)mG{`KKs|H5kUFxXtzSqeN0amaFD5)i zs3pm|z`9`3Wos?0O)i)Ri=<`i7I)M1veiT-Xsc=>(2!w}u}KZPiE&g!Pn$$L7)KNM z>0qPXQ8M5?(EBRJwI zQKWB>N{mmfS<#Il=YUk!a?OQwNh6KJUG-^`0c09@J!eE73V9DXn0m;G>i7Ywv3zVz#k&D&!D>>c z+&)!ROmtiMATP3fIBbzv$&@7PLMmAo6}9pB8>SRIVFK`F4>%Q`IN5MfDLZO1v=XJ) zs6fMAyE6A2p&fq?$f3%nrOa_1e~>?H$~gZsFIW%q!f)mg<#~Zhp3Ng{ZXw7Dq^cft zOj6Tu5M2yh7Cc)5r`=JS@7+n9n{EquUmifb(Zqs@ z2J65`qs@Z$Z~#zwEYdR`16oq~<;|j8BpM~gvkrYJ*(;DZ0n*<<`umEe8~H{g=A0zv znk+-V*93afFNK}OV{HB2kz_%khhnf*0YlVx6@*I$;Go4@Kuvt@swPIvJqfd>h2C

      kYlO4#Gq#D$4I_3+GVU4}L8CxMV&w*C<=X(Atbq38256qiyz6`^ zv)eh}l-Y>&zgn>{u0*-uJ4wF{XGXZlNLZxbK>E361=Bh7F9T{uEGpeic%puTstH_0 zmIl1iXJjNpIPFq0o5KdMfp%WwG1MZeq$~ZTC($W^CR*56k`{iY7_k>2RL%m0QX6vn~3Ow!IhH_atL`N%aW-RDvzR25T&cs$Li8U&NV2|bk461E_)wFxHV zVpUD#vDYm;RQlk;LZBKgORI`g8eqSDNQ+BgVn1r8_7Kw!Af6v&_JYu~Xg!QR;;c5K96AvU5SWT{_GLNHhG3 zWIZN;7*BX)Bq}zY@(fq9PMk{#dVV@AIUak7+f$tNlOW-JwMitG+U0Sgk)gT=xs%*U z&lIJl^^_-5IoTNlu|_%3dCH?#KIlB`G0^SxA(`c^YVf;?YNq^(aV4UirTp>-6dk8L zqm=13C~8o4x=KXMQgtwGM<{`Salv)iQv`Cy6?zJI*fYv6p;Xk96BRN<@k+5gE44T_UpVzu;fRUT~khi)^RPpYlAf90h%?R%XEe zlgd%NfO08=>{$Y1ueo%}Qwa<5adoJ8m7WRWN^A8c?j6fqi8(^%h;6Rr2*4Fw zO!IhPI|A8YcV$4%jFYLQjG-$lz= z*EmkkYk=q5Q;etdy2ciw5u_yJ`~z$D6u%{<8dzAoRprr8Yn4UaoWi}=r3ek}Qpn;Y zoVe83IF2Ji+P53V7JkQ3bxqgH#ZjSW+~s0sXp8$KG>4s<@!!@%N6^hR_nG=DlI9o| z7Fuwvx|3EW2#%@IwsdErhf!v>3q|Q|r=boRHPw#m>WWg^!aP`k>#im$eKp-ElNSEk zoY~p6N~XuT1Xu)U{(7@|yc<#I6{cyCGa=k<8!Kis(P@#KHI z(a6hgwWw06n{lq&O$N>gJBpb)Y@4V9uIV1kKr;9Lo&hpj;jVg)=?L`%CK!UVrRPa0 zQvMN+2G_&cZ3LuRjus-0%rA_dC=-r!h0?fotw}IVYW{}@(Xv`nJFD5CKfmC~q-{ma zE*+oRM(+)n={jwF%#3~c^A&_bg-TYuAC_#R>>K`=rB-H|qRpTeRrJfS)}#s=qvt1Ip~iwDFO)R2r+9V|IC-_f{&<`$V@z|Ac8PXR zFz(!`e~je#svtm_yj>tH>BeCRd^cyW>U{AZ^3yA*U@GdS0AXJ9Gvn~^@YFu4#= znEj#%yCxUzv0W!{CICLe=tuWB@q>3@TQ63!J(@}icF$7fbFSleH7gdn$VMcau=fUq zQ5w*R`75ExOi>jkZ!?-K@Vv0A0H^r2`x9YfGtQL8icU-;@r)gSWkdBQIM&AZ?(1S% z5R4^K=B&in!6mH0o(a=^vM2>+z<$SJFTA6o{Pkg-6r}=%V5S%uN^%ll<$;Z}M;ta4 zMoIBmh76pHu&N+zvMxal-#G;xthncFHqHNyf*)>9B%s zs}IR2Z4JpRZoPVg7Ar<@@QdTPaioJV4-?W3(l~Y^?N4sfgYSM1_WG9k9(S5JG%OT! zHrxHtWFly19GNU?w3AHLGNGv=&PK%1HGN zn=IgPEy0vQ;&~4`0xVi8@+nvy3F9*EJMIBUbd%e|Na7RuhbW+MG zJ@b!tlQsZrFticYC4+=4uR@V!I^D;9YkA?F+l9+c z{KmZye1D}-WSD=u-??4z!inGh9xVIlMN=uOR}ROTcWytpZ0Bv&3!2{)ko)xu9^vkc z%*Y%I-Ssss+(s`Lep7_Kb30SWo|$NS7j$v&9-Dqk6~>5nB!H6M%ApL<&C(zEZmIj9pl!XDKM+w zM{ETUV5e|%W(w8|A+xk&Pf93FYy(WwmWVW5uSR9Q`1Ax z$B;Hsk_cE<;pnVv{Dkn+EN!#}a(dd%x(m4poHkhdeIfSYlo6AB-AgTn-3xyU3JnJ6 zbJ!of8B|T?rQMEz_m(8gdpIk!N9u5seJV=Aj)y1UEaAI{6DJRNTVXfAh|;kOi5aJH zFy3~W`0yfeYS8HciQk;gZ%|HSxQsPXV!txP^@T!l5s9V3@JCXT8$mL?*A9+Wy5HPi z0q6UD3~|?Er&_Iy_`4)5dL+kI)etgO1`a;DHB<)aW{h9I24~7##QU@9Miod#ub(FB zDpFn55H(c~l0>qTc#X>@)|%okDJ^y22Z<`_yC}ET6nTyjLwgyq6?9Bs=M;aI81a3O zmdJlyovnhGT>7rw<0oUn(Y=;aOkvky3Gvb6^S)F#G zD)UAwJ^%oTsJV0wVjqX_cL@KS9SpW$V*cF07rhWS%tLGd!ugzhW~XXqC06gC?m!);xiJXRqRk43V5kN)~FuW zuWr(G4~S4m{IZ&<14mAp29El(YOF`YDa}@x53+9=F&(6A20UgMPIWr?9x>tLL)zxl0Xd`lgXvuEuqnp%4b<2P!%!e`VRdSwNpQ`Lwvh>8>FI7Vnc&X_Cf~{dSW!^cwA?AK zmhGYUQneW9D9-uO4M!?)Zs2VSdJEt}4N-ng3!<5&$X;)wa|XF%E&&W*yBc`>%^slX680A9BXMz2+Y^o+A# zFf!@w^?*c%jh%5LdtA&|GLc72-?zf@98$ay@D3j!z^mx4>%_bErGR3`88_J%U&5xd z0=+u{>5~x1{{2200=y?1(h1LsBOs@Q4dWJTC;=>uKZ9EQooOJ{;D3D8ol!YICK zXETxQ&P#UE?6&_j+t^P=W~6P`3F;k&D$j#ka$4XI#QZRrZ>LuT^J^jhNvGn&7?|3m zfQ)0b@*Q$O-`D%oIfBN!NNLc^&$+%BT3ZgKXSRP;pFFCfm9+jszYV2XoaH^vDq8Fs z*a)7-=OA@`V1%WvXo_ouWshl+>#DT-7%5TI85TAdKy?iamOno*r)WygtDgYsMibN> zMBI7(SAHGboYVS6$Eu_uE`r*MLzH$fzpS4C@VM5bm+9A*Se{x&E*;fsf?+IOxjZ4%GdP(Wad)l9-N-1zj9rxJeANZ99le@z1({VC~+mq~^)Cj&^E5A9#;Lt5e@eYH;y2m9d6fqtw2i&L846t*r&!B>S3 z;s2k#PGr3G-qpx{Y;*pAO2Uu)+B-tEGQC$*HbPuTV30vlOj zh6BIBE&sRQAo8qZjhx>**0)=F6!?uL&fU`d3N&h=i}CCZxghPfqR~^GPxDBdyH&;4 zgQK;&@I-Hp=5QAsdhKPLOJvr%dI4;sNUwY4<@zW{XS(#SBtk5AK}i+1=|JQfkHlqC ztb>elpzm-|a%&0T!oz*ppwtL>#{f0`*8S_ta3Zzf>_y8))l-tJC7~YY{=B)ao^&_Z z!4K}kMP024+&{r1Zdl>i>J?(53_vtwI`o{p>>I5Smg?fb;GG@9Ac|YSu}v0!+nw?h zV)Gj|@$Ax|zZ$bThII#>R2BsU&FTd9!hi^#aMPQGHLEfT`UbFmlQiD|6M^!ZAf*}G zXa;74T-2Eh{KBmP0&`m6H@FLU%k{rGR|lYU#m~azRhc$f;19nqyY#4v@b@BIMcRCf zxNX}ViKsvYF4q+f58%f{@kOcSqEM^(L16F=S0=NVLGr0 zUw&6gJ%+Qtb~B!rU;~f!@0K3cWOF4Pp0Ej0Sm(8WEvf7|Dxscqb%xFZgS8+M_NT?<8BhE5SAfZ`e+$d)J-H)_ivEViSWOPAHvx=?Gg)b)V^uuVc#eB35%b~ z!Y>FrpPEK>_=S$A(x~tJLg?}lRGlQ`EYC^)*HXlOy9}{kEl2D)AeXTm3-*tt05IsS ze8Pt1qwyz#V|lghm)^exrM{&D$K7zXLUznesu3|&$?cMumg#F>UpuuEXSvoo!T({G zMDO4_@rWI3BG(u@Lq@ksYbqi|E2H$iGGKGf1aBQ|G&iw|Z%l``<9oeslx`GXu|Mv6#bbm` zXoO8@hc}z;nfxAUmL>tDr+>O}`Z^ap8F1zrSF5zo@MaMOwD`@Ul`fRE!bR%+)DQV8 zl1c%}{#SQ(dS$Q%%6$BPYbc8zhAJ~%nS4?eNCsJgbwz^h%_6gFj`Y|Vg(ed&EuWMa zO|5;8B-hlgtZ{48$GQ}wb4eST-9=+uW=8`5jr5qNw&swuNK?1AMp|rWm3W}DjZUQ5 zQ~Xz`k#xUDwJSoTBS>zIG^Yb)9&%#MZO9M5pU*-JHEo%1Iw{Rhup}D9!~bJwN$@%o zp)ao`nI6*_)wtecmVg87{vO zuEQzhjy!AreZ`Xb&eSw8y$&}4jUL%M#G{H}Ja2*n;q0o|x8Za97 zdFB1@yDPX^khpOZ9*RpdXW!-R+ADkFs=H$#eHe;)X^sc z6D=uS)ez1xX_-J5!0@f5hozv{X=yNKRWH&XNQ&n+nkWxN#k3m{t)~o?RW0?JDtQO3 zXEc_o5ItM9z3Q8)s-}=>zqmuD{S2YQ{o4Yt$w@c~ym+Xmu9AI&;FxG04hFr~A*dk? zgMdn^iXS*$^jsYd`xsOYswNhW;0&Q_%`n3Uy$X(Zytl>2YHsu52tQeUz_ysn@tjI<;`pGWW_lv-{*Z94maZT;Pc)-c@$NR zsN`Gc8VXepBDjz>)T08!26@xxUF-jqD4xo%NNM|OK&?BBgPU}sv%ebt-xEGuI|{!m z{A=w@{JfC){Ib|b`sJMH0LHL=)T!atu+VKWHb69fIiz30;~ z5>j4BxAl3ez&H(N`+l+-dA+}Ywh1Ke09^G2j=ImA(l^LalQ}@*f|DQwi0uPP3&YLh zhjBZ=7@f=!{Z=DLQ;N1euc8m}Od6P?)4H8TQ$CoYpR#6F(;W$0!2+9;P)(FUHNYtm z9n{|jLWMIgL`QT$U1E%8!3U({wD8Ld8n~PyTQ?3D3X|8(rn-BD*Vk>p9wGiOZ^(#X zus~?|OA0m%7yt4oP8V|5YpD->!XxX~VTW*j{kYIWKKUNr(dRuO2{AU)uw9ZHmRZJ- zYpSu#&u(H&fAQE5(BmQTSz(n;3wK~%v!zpadW9Anho=Y%yOwI|6*BBbJVaP#A33b1 z_rG)CxLaUj8_w`D*IZr&t4#|>?bGltLccvdenkIAd?kOx8ttgvigRkgX|bR`=yV`V zsa}})DChzG-Y0>NtZLc^M+*{X0cN38KWGC_SHFPY7RGJR!>Y{RP@H)xz*~oue0`IW zf$IV&!02OQQ@FvmJ4FG%c;+$&R|m!ojm z_So?dPZr22q&-)-?*f;6Ka(8QP9Mg5iI3<5!qtt5wqIcP$Y4r{S4_a$2qi$?1yGlP z#);JUr;jK-2JY4vEQzCV~U-eHUEa(UAn15%fqMAI2v(hFL9eIVy^;cL?B`9=q8&Zx zC2*CXDbKXdv?f0%xo7f$f1~D;(B_xIuoumEn6U6g8`cUxy*L(^32|F0!*BQr_oH9j z>wRxPcyUYG(1HH{V))?I6vGB894&$PGlHr6x(3wKdQ7lP{$d=l$6l!G9%%+mjp902?Fw zvpNjW4ASr9=d1C>NItvqpeg2ZB%j{+OG0$%EzrJ)a-zG2rwa#D5oPIsB(r>~4np>$ zI(G7}n+|qi`rR&?+26(Boz~kfSt&uJNxqM)gHj3t-cl^6Ho|Sis)h*AUt1it{BRD9 zz!Pe%dOq4w2WD$@rK*X5bfZrXw+w6fYCg2E)@tTCYYP~2yWo5g3b#!H>9TrTI>q>e zkG84tP2sC;*|tvjJW1fz1PeHmo8{njvy)3AB1FyqEe9&Vy4LHh>CHES+0u)59CP49 zlDDr9gMcP^-|rjcpg;l6OaUz5ms#a&C2va~`P2dU36Wj5F_%BMn3$1rotGrWfV9aa zuw!j3NC6!!>Z{V4mc+7xu4^li{+2%iBk>22^f4D#Mp&>mIHTp-UZ5pL0O6m#yQKvx zq)$mdxHt+t&HUcRz8VL-v!YR7J7-A?0E9{ap~WqSW$yJJ^k0X~9V-7F{%QHGAhJ&} zDUlI^?dCQ(YyVL@ksJpjgNhmAMaGsXHLQg#h3}l`=2<20XA)c|(l|FRB~EdBe`-ZmHWNvr=uGE-hcSi9n^h4y2GG7K4ISvu2w*`eX}L@qlb&aTbXlk z(+k8Y@bQ->LG1V1!TpWc=w?eylDsQ4OeU7SAP4s7fTg!N8K6V>GTnN(a3i$|*;^C%}<<~g2}2I~GEvP`xuz_Fgcxf9LYZ74WGH zAJ}FXPUXOR{a&+>vg54Vr;^+5H6VC3^CN4gSbjCZekw|>}q}Z^9-+YWX z+YRN>n3+O|Fa~D`{4LucgOAyO z5*#dT7kz`f>f&kCT(FtwVaVM?zn2r1>>d|;sqteE8@~J|^8-o`X-Am}?FiJ3j@|L_ zm4)wiYjL@7dv_wJKSN$iPk80OWyKNF6^ZG%0+>j=JB5nZN^CE2$^k%;~@Y*!Xu9R z2l}+(5&ooHxO-N>`op`on-rJUs>1;g>KrjL-L!AwzD+n-@9+p@$VxPRbyffw@tuNe@VxCAq=uPo$0ubT}2n8X2*0-(5M)~A- z5ENxEEmViVWQU&_ji23-@=0;^zNMU~wld1~8q%ngYvdn0V-ZqLx_f*DtX8C0qLnM(&*ug%I+)FNZ!$K>5nec!)*)T0GsV_Ri1q7 z4AjLMB--kG<=`swd{sL?$Be{xdXe}~_^1iEtBVbd@bRDfQqfs>-_VPoLM{9c=5GZ* z@^EtP7icQEQ85GV?}orP0Lhoz*is#Q5>MBo3Vyllzu$5rz>*KJk&mwhKfGoOLIMzj z*kJI1!XbE?f@{Dja{AW$2Xj>alM{Lh^meB(c)gRx$XCRaX}g=td%*4uvtUk+$Rzx+ zq804^J`HFtn?PHS#0O8o*geq8T_`6WIK5FJbCGA;;EOi++6OcT0UG9mP^!=Zy(P6w zgb!OVTwKkW?lANSpBNtd{7F-$^Np=1O)?kOgb$bbk?s*b_W6Q4G$oicPSYI>aWcf@ zImuZNd}f>H4PTTT#;r~cEfh>~=VBzhVouWf#w%I?} zgCBRxvE;yq>*%|-X!`E@nRS!^7}4n)4OQI1|6ky18TY)e!5y|d{+@Sde}?5vQ-KSm zlDFIXN5Wy7XT9g$+&{d8e40$gr9vzh9cajgOBSGYE>xc1kG0Vye(&UdN*e|7cp`g(boqO~-&@x&f&H*150Cu9T?5NlVMKH6 zH-sPSbha1aG}r@yhAaMa%(O)#+KgnqTLB#jheajJEV7dDW>$-}l*mx=Rz`czo6|({ z3Fk$OOSt5oHy!YuJR=>}(r{nmo>$XP!3~iFxG_QAt4Uk;%SQjFEL9e)9CrT&lQwwx zM7NUBz28TV3IW#(guOgOnGZKnDmysl``&gko=gS z4ER3WiE+Z`5AxyrQ&Ef$WJI`?2&RuY@I{tSpp-0F>Z?E+=(;`?PQUdGUM6I}y%LuQ z2j5z zKNRbPllxE3xCFOcC~!t6F?~OlV}zRESpm-^hOc>|Mu-o;vxw9;oWqI=R$bxez=qc7q3Slwi?1)qY=B4 z#1Noav>Ea)Wg~VYy#EV?>5!fY@!VX*KD>O%aum4r1t~{Bouna=3`{}U@5&P?(5c{vk;V#0W!Tg;|5F2toJ!bKeXUD8wy|%zS zZTMp7=Hr!!y;%hwHmhJ15Knm$v19(90r5@X$op#`ehb9Cr3@U(c@VSufs<1}JB1mP zAq)mysKm$2$!5!q3_n*eaDXt#U5}x(YO%g*G0?7$O+d3688}WiK;$n2+3P3ITprDO z91O*5uzxgAcsy>sTaf~c-OtmC>Y>>(trQ=+m{XfhdM$PlqdP5 zyp8>z7i{YM;O6SrL(jZa>Nc8iRy3rR!n-V}fKrXZ;dy5vCh1++*G}SSh>b8L zl)4*{HxcPZK?+?&q{A@Njr|5AbQenRVtnnBp(K<3Dx@yh#QxM$;rL9WKtb{TR3~&| z1Q31}>P(fs8wyP*)~KT`7epltRR&|Hp`QIEMG*sTnTRiVW03aonpY#$Z5GDOxs;!njV}iV%zDDVx$~ zAr@;cLM@X`!1Ostq?Vi&E0+`|I6=yu6DI9K=frM!cMaZMgZOude}`De%{m8< zi{h{F;#Y|KA@0vrwhYYx+0oo5{s{CS6vRP{l>CnpcKPs<5yi03dC_%rzx~)2adjwgXa>%0E47I4di1LQzuWGl-FzDH& z5zQij_CYI}^J3C;tza{mgl^O4kQT;j$)uNkEN`*@jJknR$kDH;`w+nCh62f3AjCG= zwfKWdj^ToyQeLeXgQvnXmVa0g7BMu#tn3S7`gHzjg(?LXA|ZDm^$3!G`!vp!H_07T zW|$+P`JzU?3JEFvhl-RF4n;bpVZ)GI4?*69g^2+S17t+R%A1f-ERv@!$oI^xRXImi z;ck@ab5<3|nh1nxk-&EiKPF=KiexWJKiW#wBUW%5peYA;b-0Vb`D{ z%i~1ZOqY~xxt3?Z!avUBwGe;@^+C_IV5(YDs1V#hawA2orVCrH$)Qa7r>J!rOkfpa zU`tgM;6f~{;D3%tu?0Q(L0YTQOfJ$sujeM0OfEflU6Lc!Ua4h-hrAPuSnhrcBfKf* zl;HQRT+W;%3#HXnVIgJk@^yr1VP}BR=2&v9SeJiUZ?z*@csGz)qJlS!g)Mx?hJ+J= zgVyB2C6!ApSa>gx2*BJMNPy>e@LponBs_yODJ2OO8k$AIf&q!}H!-Osya5SU1Bno0 z;S*m%C{7l!@QV)%NBxYj&C6&Ng`~#c`OhL_6IKTXT{+ezs1az%aaiaw8A|;gCj3n# ze={;+LVgmG-%dmFFOtdHqf|zi=arNg?)=HPT#fcHFq-LuEJqzD8~OS{Bv&2f?;DmZ zbq_=G^rQTv!$xBXzj>IJ`X-A1VA%a6>KVo|xq+Oc{IIAb_3M5$hlCuF;gk)S4SGfg zC=PS!@a_peES+$UFNvBm>V=kYE}FaQ`rLBEMK#mq36|?FPZPsMLAeL`ccMn&U-;Ij zk@#)?Qj~hknqVHh|IDvy#_#8GwD3}p9A&r@rQdR}kn^#qhi3z?R@ROx8FafWFk^z^ z3n0#GiYkfVMp>%>ibwd*luPgoepK{)yp&%ZJ(2SI`NPpK<4OGFm^56&KN7Pv@%|CwCIo_vI8_ZZqXi8=JywgAe0gkk{D9xm zptG{vmB&_CwT~n1!R1&;;t$5oRYd#Q<^_ec5Xt*vb@(iw5vR@hZSW=7o+!QDsbpzk zxDTZtbYLyL<_A~M6P^el(LT6h8p2HqBDQam@P0d&MdF8^KJWW186 z<8|5h4{B{P-5*X}wOseRlfb3bcg;oMaBs|Wha)*`vsaPuD8D3Li-+;H`03;R@ZtTm zh1y@SNp`&Dn(#^)C)o{i8kFoK{r>LwdAnry%zm``=h~St*I)SF`1!H_^hx%2-KD3$ z`w8@G`MJYm@ksu$;Tci=1L>UfcvTC_{RZQ=@ox@)%ywmfNxrWO-V3x83F%%YIihPz z!#r*ZKoAS-AXfspNH_zj*v^LY^~H<1IsyTbPu zabd+!_H`uu6-xZl6|rw7jay*BRte!~N;l4q zww`LmX?RM8VZNw7PWRRfJMBhMe)pc&5mA60T=T4 zTA(dcu58x|6*fB7#JJ7WmD-@E1-9NMG3huKrVRu=qHhGOGA$^4j8^-6(1QjSa&%~o z@IDoBuD9H2kMoF9d^s*Cpcz$ zn}`k+!gSUQGTd=<5zz56_*ZBfTww0VPjn)-SY#qTvCgY}&@wbj!!4|OKm`6a-Ql2x zg@ahXZiUqRmT~xboNLZ^J68!(blp`VGNliQOp2VtuhK&PU=4@&vYf(=6||5rILqvC ztr8Zac6f%P^RAMkNUm)9qc3_B(%LnD^eJokw?;?Okj{hCUtq9ch_jrpPGfC~?kvIM1Jd=g*JQr%Ve-xWWeHw#c%c zP3Ke-$3x{WgU5^>r-h}2Y+ju_BEKp47x-_0|49LcTL`5M5;R6RXUrOwQ|6KyhyGI{ z{68hAG4lT@!SgRB&o)mMQ?0jLc}1% zq>RT;@NcG!h|~qkni=;32?1Ri|5-}f#F$`uGn-4m6B$%B=d~c={efFRsFx4)yQ&H# z&|{J{=!t?+0Eaz5`U`qgd?GtC{)Qj30nY(H!5?{(-I}hagxC2Zb{t;7zrfDGv-xH= zBT5&%(YP5#L}r0n7w~R25$pL#^~m|@15-FX^eYMCT=~TCtRC1b5<&=S7XUhwqbLvN z@HXr#eFMQIN;nfh?8@@IyLhQ=GFP%(z;gx`cL)wI@Gqz*!y(w9j(y}0e^$4i%i)k_ zuXUaZw~w@rZ+_Pp_v1)wM)RSB*rMNEDlVK8Ty<8;Jd_$%oB^Y`;#YRB65>%z_g?E; z#&>%$b*PtO-sxrVUds)qq=-Q7J6^4c&4U%2rG?elXGLlFzI_(0HMU{D6{OP3d2mQj zLYH4_O@!PUYnXYT#bnL5v{~y5dR=^##yIknAF&q85NPsRR9vF+ z#QTs|s>UoMG>J%y_es?hq>qU_qs>bES!A@ps&f^aknojwuMrst=}+?|TJ6##KfwXQ z>zsr`ozS~@uBJoO!${Uw4dRIj@_~b(vl3$l7oYfS=Lw& zT25H6Sl)J(0Uk(waYcmgkk+6TQCU^Z5haP%MC+Pn#L9#>`BCX9cqczSeMG!p#CrkJ0f1Z}l9Xv+1Q}nM zUVuG(L;5280Uw?*PWv!uORR%KEdPV82S82o$C(fR-JDCdOW3S5DO)%u6ySQ=e_;@6Sw2(oQ-0R*FSFMmLFor&u>y!CEeAMsj`+=3mf_qpk<|4|E#pwX73=*WHKl zabA&~VlzK|Q9O!3sWW&{JgIMUv#8b>;YiV46i=~^hiNya!dekX?k8CYdcae55a=Jn znVyEF+Ke=I^$?!a+{KfGmBr1ASKilrK|BPldVR`fa>6YA59U`j4l7%R%owSgI0Ktr$*cWz%l)xIT`{X;4CYJwasy zp*sEmzh~S8z}~OMjT&(=a8mq}K0zvNKPgu06Qxu;DZ=x?k?1aqzp1>GB~*& zaIDPlVZB(Z;bgFMWCBNEJCkJt-q>)>Of96(1apuCqeXgTliQlYi>$!EUk)OzVs;V- zd|2X?hDVe1IaY3`sDNW`A7B<7T3K!<132XX8u23pq8?E;8Lcy`W34F}S|Nqr(<)Dm zNR743(0*Rc8;sQvK*(g6Dn>r6nP)v%rfm5X)SSwuw(C^POsjmB+{zmH4{|bXBJ2i( zHIjSTN?R|=NteWtr9r>psge>k8`y z%QH0Ho>>VfZH+C@tgNsuwn+O8Ipx+cD`)^G#G1n4fA{KT)`r`5+x$wcaGF-NnxNhJ z<>l6h;&5xiL_>HuTb7SO8m#tvo*t+G%GD)nZpWImtW>X) z;`ijTs(VA!H<_y=)G@_CcWLaSHT?IvhQ~t7bJA3ulnQXC=n}?98&0v_zF)XeqH$Re)O8^Q$L5 zA8kGn%Pq(8rN1p2%fw&&h>qn4CT7o26wz)ag|$vGsgO5lO`nNLc|wbt({dL<*g@fP z0}}g!pa3&;H|-KtZEQ23JS_WExcq#2qHkl(%7onde`VC@@R zgqQYAF`nU+jjxFE{q zZGDlTog)3x>&yFQ()3!Qt>TA`9$qLfbcjse%m%GM(QS|#(rl7!6TG=irVG_T9ujhz zL0n<6FnNICR1GR15Pr`|kcX9UK36sI`ncg{dVQxfx;=c>MNyvDC5vdkC^8ErY(D6g z(*!Iz2h9gPe~1t-ywey`R2`9t^R*(4=WunQ=4pb*v>1qM{8NCy)R zja`N07Nu5F99u3aiLU%cirev2uajm6Jqyo}&JB??G6*b^6iZ8#<tlHnpbQ-f(k7tnUJ!H$ETUxM1o#8}|qgPtFP1Fj5?aAV*5`(6C5kt%+7Ud-^S zCesFn`?qvjJH6rlq9u6A!ck0aJFnCZ=d-3M3v-I;4T~_A_?Xto4?F(--63}li zV?!PAL3V?#2x|Zr^EMhlch~N9e`}=M{B--n4}YB zzIM%qFm^=IoyK{1{z7d(GMR*3ruk)qo(8{mLrgKHUV>R}Z`n{ydj+Yf+0YJMP;Mp0 znr#Ns73ua1co+062$H4ylwbxRw45L{K#^<;c?mp(Cdr1B(x-6mB3eME-6y`RTacV< zKIyyD&uxe`5tWUp=bQ7ARuf!QDtXvuPnvkxwkJ7ZuH@`b#8N@gkb zqtJp=|KXY|vIeYAvfOqlNq=|yR06rSfO_^skkM4EU)Cp!tynuGDxEolG|{jSH(SM~ zVU;pKtw)=~H|Y6GQ>HBW;M0l?A118odnp!WS3DPX`AXdpqwGhOGv|da8Qos7!6X>y zis#fDMwS%g^9y^Eb~iTm9*hd>9A1pI=fzz4b^{F?Iydht*C?*nm9sUI8xK0Vk!Cnv z`O5pW!;f}UY*;LP|Ki7YA*2e8mVa*QV%uXuJ=X_P-Z6gud>vkIT2P|tk@ z+7Plx5WkBj20fz!_2LV9srwuXEuAonW+x|2sasH)ce8n*0E9ngQY1cJsiv#ap|zDz+Q&ZHT{8Qu&dGy8tpc1e^rH6U})_|N~?V)=$SNV z0BRsB40?P%I9CdSo+H5V5v*XNQK}sR!4h*!IZ<`S%x1X%FC>j9A}DGS>?T0rSc0NH zA1RAiQ~wZRlI4-Z@(`)^9@-f<(A;?`z8Lg4_@&dQ+oA`DY(GGlJnccz1(2O-TF(Hh zDA26VAZ)aw+q<7#C2*KNm{SZmf7QR|2Hct?Qkty9L#Sv8}#gR7UNimU)@@@(25r?W+vS z-4S(5E?+2S38=N)faHlYk$g48YwpI;MkIgWZg>RZbr1$-422h<9J`*AG3`_)rF5q?ON^nF4^$*J-}zCb31^#EMCYvX2g}G2k#XKdOjaS+C$=_dRUqo8rUPO z%XCn>2nW(#bfS#&&bB@j+tz15?>uklF(J$I@!eRk(Nf(P9cO#b(ouYlL2Dy(JnL_8 zJ@NcspTFZGgZXPa%KVFyv`6ViIMFy;f5kDVhotEtVc@Q`ZJE%#?81h`dGz!VosxUGy2(Mn&O{d1c@C?et`;8503pD(#a*7ZLtPL zgQlLg&v;$;=$uao20ah}kxMrp z|4BUF*d@jpxD*q7)jMVrYL(92qgI2SvHojTwt)hrYgj`Dx2r%c32Uz{`Z`3x5-Vw2 zLwx~K+X@Fg3I1QCi`xHGGU`c*5T$5#OQYufDCrks8gHXU%d{NQJ|GD(8V=| z>?54aJqjIeEfoymDPG%lH-0tfx#RsyZ#eArU%jux9;Y;U+>?D9>6akAE_8&fTZ{Mp zReV$l$BI8mOZyacgj}wIGK5%`l_VLFP+1f7bPnFto4wK@!|h6Iv}K8$ov_e_#&EOy zWHZ4Hp|q!9G$*#_qUIS0s@fRuJ*jzOtEiC@=%-9hn_c0cWxAHK6PFz#912KHE$x%SA~`(#wRTuYkw0UJ0IW*zj5^C?4b@}$Gs>HQ_m)PC}w3@Q&iDsn-W zn{4yhLq+g@Vo#8}ljKX}n19K+=;{#YFNB5{?)!&}H2CL%&#&ff4b)AwPD)UjKQbO} z9m}P7UlM1A@(w2kJueMR*;;4*t0=dBe3dPpx1JINN(qGL_(wxrFmbg(y2DpT&X%hs z?sx=aSU2$6K)fF5wy_`-5=I z%V@$70S%l&_B))zYY1<0!3s>kd{ckh{0o*(ej_LGe~)_pNsd)W2Qa8ggPxapp3A^v z_!cgE6f~kHb9+>jbJs0Ib|IP}Qn9K@$IA*>n_2@nI#Ya>jo>n#8T7mXDK)3z20b?4 zsFEOfNdza{X$0p61%z;L5rQ}!;zEcEA+|zng}4slI*1QLd>G=dA^tiXv?3N@XMo9x zgOCd$34$sev^e0y(jl%`Z(9z_y<#olZ|{waOzo9ovFW@Rk*5{V8o)jPKm=fBMBXCs zHriTf7~}W+7^nkv%caospMfoNf}X9xEhVM>{m&q^3Woo;flWmeM{~foMHod(BIb;i zfadeH)U!wv;iKY`avohi@-fEdu9g7TVK56yW@XjIMm(WbeAuvDuradCTCvcuvU*h? zhMa?9an%(k(k6{Dq;)p7iK*pnqCPrFZx>m$U5rqJb|MDn>=vibl<7!~jgUGZ4x4+; zi8K{O&w}XF0satl=a9)Jw{__(yLRd9gBIHrD_QI-7Mk^WngZHNu#9)%=^m%HGQ@3^ zKUng>EKTKkAb3ME6iV}X-U%FB5l0xboP!l$m=Lwr39LzIqqUYRpyfjI2|IVi67cXK z_@PI^fhdnGgceW-{^ybZLry~|&tSWSwH3=ifTa&ED*`POGoC!^ ziK-;tC^*x=1t!R*79~L`{=K3E+lZ35!hPig)fQV8RVEax1=~z@|9T8zrdkN%FcVTQ zE{`wXS6-vp2lM(l0HXWAv*0!&8hoBPA)l-8qjD4hA?zasdiX=&-T=o95Pt()9lIZrDEU+h(B`TN=XXNn*u!8M2E~h zLXsv#NsbxEbr6+#cChKTJ!-;vvZbF6N_&xVQ{`ZT#(L2DfidI4FIL{dPn$h@_QYU? zRSwQ!m^O>dG*U4YOh;l%8i+M|E(`w83V!N}VSjKXaesHkf=@xv^EMbeRSjT`QTsfD zU`r$}B=RPo=W)Jac3(zblL|IAaogo{vB+Pt;6&|Ga4r*$@TGh4<%6re*VFSGI2Ry^N?B{@D_4D&usrMJGCzt zaxsmGjr)wrt!u!g57VPegPxoG*@trQMc(t!MD;-s67D!9ZZ@n8>RcRTk`uamt7#xa z+fS6i!oAPWUf7$E<9#FKoVc`&gS`rxzqzQmyz#F4Ko&5_NAIRpkbcjLfKg`LNm8O!c^m%e!RLy2 z0}QzvBtw}!UZlBvU)k>{2=9TJi7FunkQ>_Y+Q-GwS6@!_8OHZ!<@A{jt`7hQt;-4&)tuG zaXE>NwctR~c0D?WUY^h})7su@o|SpB9^(wPT#`ZqwoF&u?;KLj}e&uhHGGHS|cP>V6# z=4w1$cHUwQcs78EVCeX2K6MOLjjphEEYh2m_k$azceq;_b;n8G1UygjOD*xTSbq(G z^jChJB^ykh?_1_ma|3+9@?`wpK`AFRpzM^c+Ulm>vr&niK2HVzV!0Lv`FF}w=={0d|ZGz~#;;p$v&40whG7z+?I@RU%3 zkHnHw!Qa6NZx#|h00LG41dMTNx57!6qpcy&N^9Vz;nxwtW5fC$By(qhrx)_ z!4F6Km_=LD>teusOT0$6`ojw8nOm_g0vIV8q>x~a$>Q^Xhd_wt$qfOI185#y1K@5Y zm6T01&^Q$b)Jd1wj1rUd0nhY7{@=?c;T?Q@#Y6Zv{;7&u+{3#o{wIPqAoy${j z7yse%BAm;6mXEQ$HTd7zWMA(qkS1^C;<$S5k*=6#BxLv)jvA}FjNd1RWLN}Yx8n{0#&A5atxl~lB2GC(1{97 zn~%$Y0F45-I1qdSOma*Y{Q=%9$%A>l$d7zHF<%FJL~>k!!;#_28iF1in(e`@IOib9 z)=7bMFv9|}gbul{A>R$l;_Es&5TP$=zOuDT8V)uS1^>e1iP*=#_IMM%#g{x`!VdnG zCx~0YktfvQg+M8(PU>*bvzY(a6DibKA1^+k!C8EwbvBOVE3Fx^or6cge0RhW+pupd zp0E!(?&JSreQNkHuxeDb9Iz5g>{~EUlp63b1AKbrpAzQ{MmD^YALZ;2Yf2FEyz?w!^r ztvuA`p>}x4@Jz^ES%U#;c!LMv>ACA;6Y$JF#lQaK*yvaMSc_Qg^U4+}c=P!@Tln@T z$3GDVc41J&JP%6IwA&$%RiP<%HezFEQKK`h^cZl6Y1UdQEJ90+wXuO0m2J`McjSwg z=2}5gY&&}$si!n!cD`l!^Eyk)^9fu9c+-Yk=3A1V7hUtM!GEJx;%u~le`>|J1JCny7+AH|SC1Z2+%(B#3u&)bP_D~(&O zRT;dVv#lg|l|Z4YmJa@%r=~p%lO?DbsrV&J&Eo?YHi4JND3Qfpmdk-p%Cld=w41*fXe?ttTTInhbwI66f}4|_|I zJm=B~a0qRCYh+U4sN#EE>hC^OP8_jXgIe%vRuvPL;Ag-*soH1rjQ5kj3%q;8hm}a1 zl5uc(bO)j4e;4fy@Xms=zi?c6N@vkNy~5JwlEQR-o)LZ*Y{D?908d(aBZLSuj8O=E zyKkxi;@_S^^2wlo&$4ELFB=jb8W@rgq98qY030M^E4k7;5mg_GHl*JvQU?4Q7M>l% z;BHuCltG~x16N&Ah^N9Re*x2l3OFhRgiZ@#4uqW$$cD~WvDNa1qekS+Yr(mLp6>?k zxTumaGD|BGs8e#NmwjC8wkb67%7Y>U!iyqIEnrN*UzyM; zE40pPMPnWi6;)?tGT?L;w92iBrOiw7S6?_~JOXdz=j)C0&L8YW;WU@iyo9sma@y{< zjlT0;iKjW|b;`KM64CIj^%qOM@h`o!#BeFhdOo4V9A?p3BCKWsL~;vs27CxcD$}=+ zB10M(khtZ{67E7nSg#Cqg0I1=mgt5~F@pWpl4*V0m|)Jd=q~vZ-d7y~H-chIfmJ48 z*;JFsVz5DVub(vXhySE;x8r@coEi_PH{khfaJvf-DEz2PXI1pl)Cv&TF`a2yK?VT6 zv=|(KVF3EiT&55=nP4(nI$fltZ^4e;ynUIVKlMeZ(c4 zjIf4teAwz~_$|I*bsE0RKec+q)P<%(kf*8&2pY+`@o<%f%E)b9C2YPcK}DTRX_6k9 z4;~xfH_L_;e`4C0^858U~n4Sl8~4ESzyKU%QVyUiQdZ@0-oiy)PM;(ja& z2!os0lJIzQzuo*zBhu7%n+1w73k=iYG7EC19iB?&yzAs`WNW_giTh7cnJ}=mQDflw zWR%*O+HYTOJJe|IXP39RK5=J8MLD}Ai$H3j+O<7bs=g{kw`&ilCxwzJu z9I#B|k#K6z&ei|?iTm*=TmOb*VH|XBj#4Y!GDTE|{BVXK3r}y2QlI{v3Ww_lzBk2G zz)}T;GmVaSWu}X^IDv_Z0H7j8slX~?g@`DVgLDy;}My>h8a z#EF&7(>Ro65Ke8p-+YOqvi6_5S}J5KK8IbUQ?$Aw8rUh{H0rFRo8Me#8!wCO0nA%U z@V+EtBJW-sYs+#ZxS6Q2UAyzMIti|j`BK2A?aNQ^41ZV0YVFnEY8Ie)TKx1f<=;ye_iW z+eQmLR-R|1Zd3ghK?lFmvr;PnMFT_l$5t}h_f zCHrK~6G@~6xEKNr*B40k;R*CxXJDq|-5XiB(PX3NR#yiU+3$r>dv@+w3IAiTx-7iF?D?bSth1yd}xT5q}lD? zx=~oRdT5dL>QCH?sI(u4{xLA@Ft;AR>%#j8MiuARwJO|s6w%o4Y1ONrG~2-3Fi_VT zBgQ7x7kuUF2D>w!^ree*PXPjc=F+LpyYToA++ktgG&)`1!7jn_NH?p1Jv4Qv$m%t+ zsCGa`W>$WrlQW;Vif7zI>w^44y)x;Yjz3(Vjue5ur*k6#VL{>>cg=xkT!n4BJc_aP zvlSE&kjkiP=ZV|wstPCBYOu`|-*J~jM!5tO<3I%#p^OYcsgQOWj79LTymux}fq{>N z%`0^f$kEQS9!w+QbG!U#7`W)c<{V%We{Ccs@E+LK_6z}sne$VC@Y!#jw3}}!DIj@$ zHboBwW(L}sAw(;nNpAwIITAjygG!5f(i|g>%+hBXgtzRO{cXjWf-;OWkN}&}Abe;~ z00WrRaoT9Vbj6mF18h#ZU54 zFO0Ae9)A1a`QM5F$Rhy)*a2WJQfhy6T>o-{jhF zTxQPb(sJK&55e;RS3p?bkt9d1h6qm-8hu5Q?qJlcd4p1TipYLAwAg$xu`Gr z-c^x2?1OY}p11bak3cnJK&M_`@XfsuPpdDu|2I7sMcCq3fZ;R6_M;b)I4NAsOKR1^ zAw@QBJlya3wOS9Cw=|py*x|1R6qzTvsi9JeAN3Osu%@tbYy-o9a4aq=d&F7*B~Il+H+y?w&~@4gI`eWcw`B-cizVfO7C z)A*uwQ*8PYy7x<(zk$~2Z_2{ozLB}^HiyazA2K(v_EukH~LcpN7x#N7m;nK3tFFFG7gq2i7N! zzd=$j0xbsS535n7-_y}dSo}y%T}f2lM!4lfJFZx9&J{~ui{JAOpZ{WxaU|4;hCph9 zLVuUv1ByjZV!MI&gsYr;{hpV|Z6r|Y!-Y<>vT2(!mZKd>)p!ER5}m39Wefl5i<6#Q z1FBD<^9DHZh$cHA&2Y{L@_|7l3L%A-wuD&z+D6f=-!GG1^m}qd@|NVPy60C;Z6*>& z6{xprKM;fADTwB5vR#?K!qJ0Dt@uN?XnbJzYfK)rBWYMI6p#-*$rDnblh0Zb8T?Q!$6E zR8BReBmK_x<$w}Y;v_zbL>vYpf0~#%M}at|Y>J+xg;gBoSZ0j^AM%lxqQKjhcB2aV zHpmZT8sH{m73A!O<(u>^=wPQXRB2`nL8Y2QfiC!!q9mv`Gr`~OrG^jra* zSlcbJh7{@pGY%4N)mW36bad-x%}>|hetY<^=s3ivmlXy*!2qdF(LcEu_0qySp=TdF zA1xGINojBoWg;a+h>TjgOA7n`S|BUC-}##hr;)b52(^8#hTc!Z*BfY^!6uxk!CE3_ zQY-)$JntWbJK`JpKXjOs~H#9`s7Ah0L8T}FdI!SFg<1bFG8&c@WBv~irFn`|Z2fI`@x2RmRI zgj5xT5hyhs;v|xvJ;k{?X|hB5`p%+a>*vioxL8gOH@5MxCGsZwr22D<(#Y5uiP`8`mgBXFUE5=Uvj13t4*6Q~8t)Okp)htDeP z&!6GUD5*D2bN(bAI!;RD_t?V27XbjD2nK;&40$U|s6!+++tp}m^y z7aG=8G(1Ef{VcM!gh29h_>?C0*$j)=Esq zgPw{{@>+=XVH%(t1E`n>aaM>JGqYH$-}4VY(9Ileh}dTFKk!~4gtynlE;`Ey!KFPpinY2aPB<iInpt>k@jNmUa{m$$08y5sP< z247;46kr$zTt?mrRS}sjX!~3tG#+o4s2T$Ozc{7Y5&i;lGz{>L)-!SM>0(^MLl#ag&5T5p(&RB&lL51`Ih(* zMKA#-GyyvF`42ML0hgZNxnBc z@C_MnRNWZvH2b%xRsH^-T_skOO0=3QK>aABr7y$9b8@h_S8_;;gd2nW##hfg>IxnQk_%sI2^)K6>N3<3bq*;br^JjRxqtD0tIlhyO3xL82Ge zvk6t0{f7%@yy%2~daQc^3@u;l>x~qsPU?-%I8j!Wlhpf{AM%wXl^#Uw$F7=;<)Io# zXZhb6(Z&a%$^s`SFsjbGJ_Xevzl%?>)f-Jv>Lpgj>fmTNC2nK)+3Up}?7r1oTKmNU(klW%tz`hI0E~s1tYSJIHNC-6;oR>kFEoM$+9rRZd2r8IoHk z+6|z+b71xc?juNru zGaP^Oso^%{KBOoF^=}#&1U5t8^BsG{T8K-XjQi8Di{htc+0DdKLF^F3LieOqw^eB! zu~lV0IRJ-f!j+vkr?qi^BM*LrfB_oy%da;o8n+u&PR+|P@K)-Ca!L%I8+ZyZPXoi@ zQsW?8GXI+~u>;%=Y~Xe>bhG7P@N3uKjK5yGx>G4qZFoZYib;(aE`g0~#5q52-rq=? z*&gcT2bXSZvUzL`3=Rf*+@a;D;;+?Y5=8^=yN&^#AFedqQsnFfpV}Mtm>&(d zWTEu?_J-R=_{Pmwc4C#-Ym6M{Xt-TtTjGHICE36`cf=cF6VAasN|d$=KKX+Lm;Ivn zl0MdQQrxEJ?R#L2_|*b@>I4nGXpo_yHdY9iDO%+TWC+`+a%VO{Q|c?63_64ZDVcV%mHS1 zVBP%pu9EK&K?<3=37)s%lMy7(-4W&8F&NXh zC!cbl{U?kG9sEbzhuenM{yiU2%4~%`zHELI3<~7aPeTIqdpq8Ja#G{&M~n;J-EneY zv;|LyX?)%I?j~|85YY!W;qhO(823r!^X!7_6feSuN(>ynZxf`j=7=b@d?zZawu=n; zI0_q6xvK!Bzv=kFHM7C+v~fr6j+n@hHw<>bvEB-<7Snd50;JMOOM09Gt>}q&X462J zUfVn*#(=+bYgG%e;=zU~edTznhS;7ZhmqO?7Vc7kk~6@|(r{%4D@yx|%YG1*b}9eE zb@}^0To2m@K4oBb&jS;CxJ25JYe~PWt}xwNt0NvK=Ol}5oX7JoU!+?Zu}QR5eR?el zMSU^!eB&C8KG!A}Z-#i2xJ575D%Dm%vmN@<{^4r?-40Z|#N2)hQgyp3DvWo!D>jMr zt}C0E+mEd|xGcKl+;vqhbK5Y#R;=E5R$L1gZq^&8auLNy5C_zp6}I4duOvB@eC`9K z`aEI2k6aI%iK#DYK*Ajca?O$h9zt{jU;LWJ2Cvyv10TVq8P zTP5wLwG3NQrO?W&wpV>!Rn;Pyec440W6A7Gfb5Kv)N!TuBY z^)8IR;xGSMP38J_*WZs{=V#Qb!MFau-Vnq-KIrKOt2pp7AfRW$N1p~g!}!|zH284S z`}K*`i~;`3`b_+H-d(R7_1!@D2Vr}u!+5vfvt>|0&h%b#p`JP%@U-(&_Rhr5@$2@E zg3oX4-8-L}?&WXpEu-SRCk*?n7;od>-=8t%*;8z~#G%Mz(szV>B|*Od5_%Z0h1*sm z;qg;QW4IL`jfC=3Lem!O=HoND*|A5G>K(7sY=D^2`q+M`@ zjKlT7@ZR-%@p;<#D{m}{{18A$AQJ&=^%-CE=4AXcU-M>c;wtg7$aG)6PHEvHG#KTG zdKc*uyO6MqKlY{?&*hzOCSntR_S*p&0nFotY*2H$}{vx4ZkL$(W4qJ8j$vj>&P@7lncU^?MB5Vlnur~{*|{= zYyzP>-`P!^0)`7E1({D7ZSKM5VLlXiFQ1eQ4R<_s{=Ix; zyLH+w=MMD_V+=jC;SJZ9ZdP`}pz+EEXZ6q#tXI~Lz0$rU(*S{35rTAsZvfnm$xswN zRcHuu-!K>g<(1wF4-G@^4&G-M>g;s@ip}=JZc1Km9vaL5e6uMun3>2oEbuZ6#zw{s zz{_2E{^k59FHw2rWH#`S$Vy4tLtZ(~W00U0s4L`r#7+BZ!P}iv_un;>l9Zt7I zlC5>iGMrhAIhqV-vJXD|h#!>7=Er6gwjcXJY!j2ga2fNDabQ*zdJBl%bJ|AtV@=+^ z=e_Sa_cZ68=A84~_kG%0M?G!_W8MMN5;%4ciX90e*poq5443;2*MndzAdxP7C;b%h z){DGIlw$m&jA1p&KU#+@TSot=0beHpf9I(>!=wf_F$z!lN)3~~#1;H>&`T0nDMCVH_O!3yWCv zkZM?uts8^mNMt`6G~)mh4FgzvfZI)>Ze;Z8C-a2xGh6#3YtJM;!6DL+jV#fSt%a^g zf38PaZEy`dT9B5hE@*dqu1R@qMWL^42d_y&nA53E!YnCwd-B?<9x4>aC0$5*$U)~r zGkZy>Dq)Mk&8Fu31=VZlpWjuP)?j!sduqtkVNEEO44vzFXAD7NRha;`wCY% z*g<_Z#gtd8nEI&xE1ovS01Q$63i1EUs2z(v4$fZoIq= zVDJoxnxa^#(_Id+4^KozB3mC2+(fjmfpb1 zPAZ9;j6Eo@(vGeI?*%Lb0}v%RYTOPs2Xql{rMrnetgRSNK3{MNPIXY!b0BO|@;Qx4 zeN?`4iTN~RWQ;}Wa?Yqca)|_)&A26$PO(2Khk&M!;Y4t}iN!fGAD^l___Qt$N+dMC zO6}cwUSEu}PTdvF*~96tuK$}X;l_#9-RAS>w#|1Aj1TZNF#~b>Yh!9+@oxd4&h@^^ zNgrlcc6D-=;n?1XjR8byPOfd*VKz{Pn4&}lyp9lc(1_?}qOXscEIAIrm4kuPVzX%b z3CDKPGJAJ|?JVeD-C0}*mAi}Ve07KCfTSAcrbxyCNf;5F2Rui>p!}@MMvTKgi0)!K z2tG1!5;m{Fo?%N=UPia~m_UT`X-|P|a88MkOZIB72eEfMv6W|}SDDHg(B#DB^Kk)$ zV^O&mwb&*Fz$s$!WqH#qz1_19lePBb9=t;sJh>m_LH1Ka{HhtMKHY_U>M_0G3dhtX zJSdU1Ad^tr88Pe=JY^-B5zK}-o>j?Zdh2vCH;-~>4mlUEv-RtcSzGH7JRMSQD7^C! zkV~%6Y`p&HV=`Z_oK+Y>mZ3N*DIV|&VA(Zkp?Lr}*pcBFxa96TSo|a@4BR^7VAdVD-5S&ig|>5wAj$T@VsXl|S1=#M%ZT4s8IQ;ZFMJHWRVw zjbwRbI{==C5GWq>nx zAx9vckZwo=fSQrR$sScW9kZSs&@|k)SQV$q3#aMxeo0wju~_JCe@Wnk-@<{hbEt2J z_!vw$XkkS4ELs~VqP~DRXM)E{CgQr1uViHnyXgkrJxOl_E?6?kiC6{_s}G^qLf(h4 x3heWLKHSUv8Mc7eiDMGdr|C$x~$T)%fx+~5Ac|MNZ1m*<%? zlQXw>-kEvlz0G<58r64|YCA_^PUxlbZOPS0n`{wG+8@SPlB<)ewwW@2Kw{J|5~ul) zxMa9{u;%6N!PPG(R44L!5z~p*`H^_O^^Y7Rwgr%Q6KZ@DFiT9@8TUMiiGfti8TT$V z%GyJtEQCbGnbz`v zxjMDZT-{Pf-9W{u%T3ki9!TX);=XydRBI}~69-PG@+x>vf>G{9fz#6EX6 z4jE06a!la#ZB@~H6U37tHi;A!ZJiWJVMswskW*yQ=~Ar*sHYPZlu4v1QkN1-DRrLD zm0wv+ zGlcl+1WP<0V@|ZjM=}=ki>)nui*>%lKt5A&jz4E*yHGb74cmz362SiSd#E3wFfM@f z83^Yg^g#$?q`C~TP$1VVPO^-tPUGXZ&_nho8yvVO-kz}KNykwK(v$W3bNlAO_$>z< zjK=UW5-mrn9C*q#H_H3nX&$n#kyj^LvA*Ap3f)dU{HNgmPj17<^%Vd}rLbR~o-VH< zE7HCu#)`CzCB^(H)sXEel8urWLblOv@UslqJX2Dk6X7am|Ey-2t*(uf<5mwYPt#$XZ`8cVX z_E^pIjpb$&Y+V6L#RI_cRWX`WD-yr*A)T^{)*$hOPY=7wW;Tm`X1!I^lTkkKkqTyn z=|g??A5mT(3nPJj&Zd+2XVmw$9A)i}LhOSO5?|K zX^G(Z2|+e$jxE!Na^CNznvq7*W9fFd2k2^%b}hi)-Lr zR4j$+E5cW&&&K-cbDD(jM~z|_ag9&t8>O~&_$F6rxI3(j_>NR!!SC^0$(`v|N}pek z#qog)R}iK}A;joQtR+0oFTY^m?T8llh4L(Fc*9sVm2cXR_(5ndpHaDF#r;++wujOH zl|m>Lo}a^enJ)Elq|3CVT4`t%iFXal#H8VLON;}FeN#hekig<+{?tgUmay3G$KsJ7 zBVP6~`lw1$<;##PQgwfU+2| z%_pEb= z;ThFfd|qf(rQmmk4wZKNx^O9!JQh@U;`d59T6`%?jvssu|w zNzBC$3Ew9c;e!Gmos1_5DWmmRC(IaKm=qJTI`Vl9cj>{Ey#67i-@6=(If8BU+^CeG zrt_{!T1*noj?QPl4m=B6;+R{oCykk6ti0Jyi`N3r!7G$=+NILaV!9vY>~&&2z2;jt zti@n%!yX=q6N7RNTj51)!fS>Hf-G6}J;XLcZQp>X>cJsu-088ai<>&LCMm1?cqtZ3`H zEWTXJ$#&9Wo^WtXGVT}tK4$*-fBR*vy|>8X)gZy(RT zkc-44kV-taz(La2hP8dg+}ucs4<#n!w{r(pqI{3DDDoy{_^LamwTg?bhO)09@hK?r zQ*Ug`tjMZ)3;y*+T0Aif%QBt}>v`1Ok%HL5D^iV|6Ressw(&I=rMH`oaMO6C&7Olx z&Pu3fKbOaEHN~9I;d@{!t{UFNUG5w?VOEPVD4`GM=kZ6nu^vxNHQp=fQ0&0QxXRA& zBxL=$ebD-)gbd^~>bfkwj7xCQ8FxOky#(c3&p{5fkLZCP);I?0luR#e6AOpGl2BW> zyH?U7Tm(fl$9X(8(P)wM=vO!Du2i6`*%0o9PE9fMa>|@&AS(Jj4;yueV`lV7Xpa%P`&WSB9A&eB3fIEF z_XBs8oh?r@xR9n=Vq%Z-^H$trr6WtvcpazQEdj5Y<8;#E#{q0uw^CmAhH1=6JZZKt zBQ-hey?~v=yEPo^!7MFq2$YpM-K)jL=rlZI&`G!QeZ&g&Gu1Q}vjid4oR~0-4O>jV zyRb%b6PiMcj|f*%wfJixCT)!}FKmTzt2)$L2G-mr;l;G%S-r>VJ77FRJL@U&TA1N_ zfS6A4%QBdAu$IJA;T*2Mi}4ho!$8DtKRd!Q}l%bGTY5ZrUYl*!#9m=7~jN?;c+cRI3YL zaZ4TcacDd_bZ_(3J(|`DOUoGc8inrkPe(l!(!l#EVbaC#!i!^b@lN4?#@-+EmJjJQ zoPIeHmkQd9T%09XG9IDgL&DJvLtSM^##K6y$EqlJGKW)7E{crlpvmj9YAA6^h~XBJ zTp2Y!`OfiAYB=>IQsQ{{9VlUh5;?a@7-eX@>dx_NG@L3@qWwQ5l7%^$$@op-!OS_C zHBuIT-Cf!-3it-2BkcW9dV9rahkpG56YUCn|3`3TCdUckzD^aKvnnGczSu3)FHBCT z{JEVHH-yPv%IQ=?uOAATni486EI1PC*!#* zk}eV6(`46a!a1FqNd!Y_VRdI|7aRn`*MYb`JUryCuaH?(9qD}7n5OX z6H2e)pucXla8{c(r!u^fU*nkAfZs#9Z>89#QXrbR6zh?gH#~(i0DNP^coI7~rl22s zl9Ao8Neye6FfgTnfCI3F3=Xo)DDfL%mM$sg1kC#g(w-HT>29|zlQOIDq(`lB{O3}v zJ)@K0BN!~`GjPQm((mAxsPXA|zNmArY4rJcKDYDd)WoW*ZWR~JiS8{tT{e=6tImab zo}j94wU`71ZwLR1Y3~50-yWcuHwPHJ!+Omnt0HZm4Zd#;w?9vgFJPs_^2YNp8TB1; zv-P~i(ZXkQXdIr}V%77Bj#eJ!qYL$2q}t`6o==1PMn1Z%#cJj`YY*RCF#zO_)E7j3 zs_?izE9FEGX{^=}JeGE;xitQY8$=tx_CbASYUVIVntHhwYZx(Q80m3~TuVVZaag#l zFG#y4F?wLSxw_3r{6YGo5rr0s8-$5j`eivmva$%Xav1sq(prJ^K9EmAjk?J zv%M0#hdE175SfaXXLU~DYGJbpL56#(wU5A7It4C8uXPR{KQ*29WsI~eiGFfj5FwwtY1YFGgyVhSQW%<2Q7Z?r^VwCKJ|~XsCji~EbP=YeoZIRD8x&`k2#t6 z2Lb0MC(RkgyJ6n|(oLaJq>O_R7YK#971$#@nY#%4gzs}F>SqU$$OlFk{oA^Uvg7wp zKKS?P60-ZEXJ_+_ctOzSO~X$LOYO0CG1@brU zxwg~N+X#t4;gJbio6}#y<#9~a$h&{}2|orWJQI&zEJUoKBVJ@>&$o@{Vx0-A_O7A_ z=FxkXGoF1YR zm6X6*zP&Y((UPW?G%(E4w0z%|fdE8&%ZP42S$G5t3Bu#-RQQGyvL?P9XGl2jh z`ThVxovQA}8daC7W2bc3Fq$iIsGy7fu*yLWj(fvGy`gw=8&Wxt7Fee6Vd-f@vpn(i zVW~m0L#{kc3YA3Orpo2ytszZLMc!T){$*Ibcr=W*NkjBoqd??8CGCO}ej~hVhIj+S zuOSwW#it;MVmKGD^su{8; z%&H7}zlKcG!7_+R2TLIy>0lwGnl!s4yJ|itJf4{!Xxa@&I43|Gzeu1n(@>068;~xs;(Z;ZVHA;MNx^R-E7uk{&<7% z@FdPgUW*t)$5y_K*Yp2Y1WuV7W@dfS5Ia6IKhlIxK9qVVG@l)tt?<)zOZcm`vAmgo z&05A=fGFQZ)2Cxs=*yt?GBY2wVv&^^GM1F_+KARK1~f6$P~Q`?_`^5sHp>dVc#Kwe zn*lV-G9xb=TSfCJM#hq8j4{(z5w;QmC=(@y`ocq4C@U!yj!ZJx3SnihTcn!QTrpaT ziw$}OpK8J{t`V7sKyQc8Gf3%T_1dcWX0hWN_1E`4*Z|aiGa6?f57hp-$3G(H_;Wz* zQ|=sF_PU8W59*K-MPDXPmgGGjdyq2Ig|lzmJt7L-o1W@a&SnPa#MmsxPsPV?=bvya zZRly=+CUAQrXJ*lhRGWBAGkAglr_X^6D$mK z9iUZ0)$K*M$*MOQk!C~@+Si4mNS%@Zsbg6iz4ogHQ$MXUZ@?mrd*%3a*n6To?0uNw|G7Q%1Yuv&^()Of zhqXjqCUzBZSKRcCoohhEnXD)jW|wj{HQzHh3N%%yn}xpV^~(ll(ex8UcLft~|G%|# z3eZqaap*+~NYwF&tWV0C;r~q-I|FU79Y#@u7(p|IvBjN^CS1BA`gGKtGR-8u z3=ABwWtkFd*z1rc-Qpl&D6n}5BFI31!>9&5yT@ueDP5jQ-Mp+biwx+k39?i$$!f$} z#SYm9P0b^CU=b}MGs-J*ezE1Qj7epO{WpiW4T)x=$}snzV9a=eS}2;HELXS^<`nWm z?ex5fc)-q3=fy6Z^_@G5$A)z45TH;+mI4Fm?(TTeaeEiuDT5$ zq^=%(E)f;h{Wl0BDH zjrA&in~?_izjBY|uDMHI$m5DY8BfK(Wad|Lg;08f#dO6$=g0>QY zhP@l17s5=$wt^lf_K^fd;50!YL2+q^c>^$v@~Nlk4U?*t;3W&kGQ|R(Hoh#kn%=Mo zQv>EiHE)L++ZK{FwyjpP!H&aTXAtyS8?Y{h-)PkLQ(z)mEj|LgZrD2z9O2`UrnHO9 zzAfy1H%x6vtcupm!}AyFhmhGUHks$w2E2-(enVU}rCow!DtFhubz|1!MBQ$$OSI}X z&^+Z)VXWI4X`Z%zaSJCb;Dl^avdLMp(RC`2E8{sUD23BPb?X`31A~ghx+g{?MD&TO z8nVOQhX90VO>`9j!7SR%aH1v>5WWb=s}UUeBi)keV`2J$p@|@sV92zA=1$7-sj&B) zP&0Fe?Jt25;tK2Adpaz+RUH)2EnTO1!vljGX)~z{%*Ppj-Ge3VX zC!_pw+l^8V)K_~5x*>iG-xl`91!bNFT6W{LCl#I(NMAYmJB#7F%QViC}aA+r;#F(&*{>p-`O(VxvyK zb;K^n(E5!Om?j=4+9)I8Dk{U?*ZpvORfN4ofH8tCGCDg1HKa#FC`$kV9j2`C%3uY$ zvGYlWTP<>!FouT%jK_+|Kim}deh}Ct%_w^4nbm{GY1}+Uv?>MX%rUl_etLdQexel+wjwd+5L*~v-)Z6E@@1YsXtDq^gS=d zv@3lZL!F*jWzHGpbtZbTlqstKd}?;TId-!&wkN5N z7HzaV|M;2X1IOuTc@5Y=Yx+0Qv%9S&}6f( zSvQ(s8!A1Bq0Z!kH21(Dlc;~WoR`=MiaBJDDYDx`VhA8u-5mMdNiE441+#4H`|5!|!1HmtDS7=Q5Jzh0NyhV%#L z_s7w;q0ED}i8F7eAFNwX%x+Zv%%L#{^>7}N#cJ-4O-!_EEV`|UM#2bTuq$p{qu;o} zJqRsO2Rnb&uCIYMgCC0U-}m9dei~Z5`614;4Gn&{|5x4mxsdzYhorxO59iw=9lAgK zW5rz@Mme^jOCRdCssU2gLIcqo-EAJCz@BV}ZchI?LbE|`Hu}YI*b9LuX}48vx5R?X zyRDk;XHdG4>PKL{M&dquHXV2RdCT+FWBCL=$ygX`6yLL_@nP-e>at6ST_bT9s7M+K^LYpbz#?VLnDhZ~_L0dH3DGOuw^pt6m2 zWXYOIS_uVmBIhQR=Z@l+Nq{irV(O;`Y-u{anf-iLEEv{!F8!NIQ-7W5h73 zl2}8l6mQ6Pf!1H7t@%pVcp!2=23nz`M3KP?P=>zbBSn@0aN8j6R8XfWJ*hZV5p$a4 z`~fggFx?YmBYBUoau1e&>PiM16fOCVi4uAi3QZ^^J?eYF&2Gu&sv{@5Zl zw|Kp^h-|1D7bS{RZC)JUV1;jiMUd8N5&$Q1_%HL#w=4$MRgtjxiInwQ}nQ$QCJw|bDKkXVn5{c);q;9bfSEl*4Z?6IUfgI}&VZK^~AF~D3*^{Mn# zAB&^4GzoyM$wK7i< z$m9!se;H0Pp#13GJlnvA`Tdk$=3KcRM_7!NPjvpeay_M!+Gv_i-6ck^EiQ&=) zZE7>YcnL~R=}Aq&;{oqANz3WDCqWQ+$sg9IRD&wQ3M8}mGpVmA(fXN$iZ#Xm|6;;B zL|f9W_ge3L;Jmd3CZq%$Ps*j0>z5DG^vWl|SZV{v2wY@9WROzFu85xwdfX)1BYfyw z@B(TAO-La0GCYSP&zqr_YT&dCzXV3>p~sO{&D{YCsz6{{6~)mU@Ii4kqA}JaS<{f# zWDV);4}JCo^(4jhNCh~~kD2u11tnW$n`)qm5Di#AI48kdVUMv=Qw zsx+=@SUrd#=Pjwa=aLKQ(#IRKUG2xEtYya~15Pj5Bx&L|NwM(?KZSAe4r#_LMINcq z2&uhN+}z7h=TB7xll|bxK%X12_T1KO*VWCbvn;PkwdUFQJGi>pCecXcS!s>mD-VPH zG9UNi>0TEGSAu&j#r#R2Q+OJY%}|!#dn2?EMr|)14NBFJ_Y>*v>SDr~iam6qH6N5x z2y_B=b3Wv?Nj0RTHQl=RMo(QTzxVq2HM*gmdB>&m<9~oaJfUpl57_CzC5F1OlUi)8 zDn2gtX~^^E$n$dKc{TDBBhMjC$U8S2^45i?M7YDSHr*rFZ_OeLBdb+k3Z5?e|9dg7o|$op$3?7cqxBv>mXqu<-wjk<}`RLuJ< ziiHsUVHDDQfLOA)7>Kh?h>Zne$U^u-v@IpX5wV#@6gRT^`d}53E!GEtP*y@>86-@w zWZ>z-9Lq%fnDC6{DRq2V&CpwqtGW7)Z&HzVEJxpX>(5AB;1^MMwu zpV*36J{A^sl4MGk4Iq_lfJ)eO=+Nv;JasCtP`5c1o@80JsFWQv8O{*3cwxBXhFw{5 zlI;CQ!*Zyyc?EMw$M5C$oAQ46i5IMUc_I4FaW#{|bv!$Xu$^VV$&;#jP!&sE*&tXL zxB~cZ2_JJOXuff$bKklX!O0-(eS>IU9bl;e!;796Lcu?TxZ3!=OND3d9Gp|%QO3t{ z6qv|a%P+}n#i zMzyEH@7*DE)jT+w<%+=li^`qUy;^)0gn%SeUm@sfjVUy*2Zag-ZP>`mdT7D`I?Enm zZEY?-BT7<+YQbtS$`8bTZO2o>KHn-H9s|B}g<%jAt`C zA#JGze-21HA$_Wr_#+{)_y{p*PBH|%tZ-;7&)E<8=Y zQPm|p9J|SOCZ!(tp*+86rK+wN4&LRHc5b?9E)~khH=tafOO;w*L6zYtG^gqiObRFTPy;?+ z76hJLf(f};RTud?43>iV(-)M%*6mqQUqKuuqG#)PQ)l#?=sROT>MgK$K>t{;2h)<+ zc(=q%J7&7^gSmY0WOIebtx5zR8Srl<0l^-R#9E?>`ml=<-w@uNUpN+|t%%tQ>1&31 zAE&A)@B&Ne1V@bz5j$P*%zqQ~=fYicagp%LT~ATp`i1-M?!%jfnfENf3x!wjsQ|^w z#d}u9g}~tkGodEsR3n;<{jbjduL=vt`r=KzzD+B*OW(lFk3s1_!- zTzF*RK$9U4^@vuUx;GY3hCt+{dtuh%< z<_;gy5?*^1#DskCK0SD2jNlRGV-^zIyLh2ToE zP&(RM@AnRcZ?+S!sd}*2kX@E)K;k`N1pXK4U_qE0#*orLYIY=50I7;F3X|=Xpr$I z>eJdcZASW@EAb`t@)QSAlZU;nT_mor0Bb6-fP#Xjm5+#Dus|8%)BDqKxp3kBu@ig3 z3XXTY(_n`)_`YC;l#S{;@r=Ci9E@3}vc2z-7}n#-mc+bdfh9Z-QX6CMn{Bjex@E zgjQ=IP8Pnh&Zn*gg^XnnC%qbwbD{&5TJNTYj)CLKv~zy1On7~n9=8ggF3V(B24tMi z+ZPrtFU!Geg!l(?ZE$9TyN%zwILHIBojm+AkiIZX4>*jSTW$(@!IhD40pQ;O>M?QY z5uzGK;(I}*h2a+SW4R_Ea~W_x`M~Ioaunx6-oFMB&*T7+%NcYUO{GBOR$22K>Aut# z;IJ)DZ6s_j3l?DFVESx9FuIa{0q4g8)uI~-bv0Z4-g&p^ATduj03D&m<=<&)5maahoU@_fI9fR-v(tF^f?X8`k#Fl-Df3@t!TiJ zZms3Mk~FjY-d8|36Y~BLWIS0kaUgrhTDMI9z}r%p{lpcyK32aO&c44oQ1*1N7>?+h zzLL^sU3AX|BanPo>7<|BtHG{(2%a&rHunr}z%6z>8}X(X%i*12uO`G~B=pkz@oqu~ z8sVQ{d`MkB5q5*DO@u>};c7w5pd;hl`vNZ63&OVs4!zPY8Rw52dS62RAfVshdw4k3 zVClT{La#gqj3}do*B?s5VWIP(4*Z(1`cLMuPY=5R5E(?s`85~lq~F3K~)+?9t$&dhhTYFTR0k4-f?~rcqE+wOSTNqB>9<) zXkh%p-eUmoo81rd0<-SWX@~=c99;bT-V$N>;i5nF zfO8CJZ=M22r0g4R;19 zfH&mvD=2$LC)Uijj(JLN&3r1AtK)uk=UeAnGoF&%^ZD?une1#5*gWEGR0ZaT!t9-4`d#8^WR}C=LaL#Qi;rA}@gu|f3c~)W!NSjd! z`;CP|wy#HhQEKQ(tDZG*=`p0g>W>4Dp)bOE@PtmTCWrL~@cWS4w0>`2fczaC-X-0u zLi)_yy~`7TnGbn4Nn0H7&WZ}ZaNZ@|3n0`12t95&4B7AfJn$>*g=qQj@TBEeBa7h= zj{4I_faw7a`}U56IR$)yBfb(2(%})|LkVfiFi3ofE4Z4Qw%Ga)fFXEMqKx=2SX>mq z;1^kCQb3_8!@s)a5Kjg;e*&|L8aS#Gz!|wABmnuF3xRCIIIcV+Ny18%V@=w5;NR+j ze|>8BhMTg0t(H^sNTiOiP?xysHUc?Ra@tPf;33rnz3Xs<8--NCo zw!aC?Y|z^uTp+RU-(4PihB*mVFs>4I`#xzp#6d5D-3E=kyg*{o+w;dyf=t?^Un^(ez#2EDvhGvIC~ae=wH6GY~DCb8??)?nzr=D#f8ZtJ8Ib zGQVbxb$ks*{wCAk1}HgqHimCaomUoPEw-|}5oC>eYbAJ+F`&A`bgKDliO~eTp9ke0 zmbu`F8DLQ_xM8(e6CAx#tlOy*JFs4d|w;2}4{_LW0hLGRye zK@znFKQ=Wx_j_1s3M{)}Fmvp1?<*g3@*UU_<=jDc9*45ucbD+d12nY;M14#bTi00s z040%tVmRiW&K+}`;93&~Y1wQ&=_V~d3asrO5(~@GxYT1P5$eHls^&0SSgFyj5HQ7sS<%rc{sB}egG~4 zrQsd4K#3pt>6Tgp-c9__|Ml49>>WWJm&-Bxkf@dv;3K7i^CIZI6Slt9fjQj5Le8Ir zqQ{GD095t`$=W7>sfs9tk*L^w)RV1bf&ZceJwF%FfhV8knkx!^6ePT-C7t9_J3+)6 zAFaECJHj3D%v4&=9QEWYXE;YgtWi#L9`)#zcK|vKbZ>i9e$5#*+-ghcru>TAD@8j? z`Q^7M`i^=EmAN)3YEbsODn-mvtst%(pacTODc62aIp|*-&O`$zUO9vo-tXJ$Bh9eg z^6^JK4=RV-jp9~2E~*@|SANxwbldtWMT)Hy8TOpJQe@eG!BfSaav!;YY)5}M>UmmO z2z@=F%!B8{$}CsTke$!;*|tcPLmK{5_fb!tQsp8YECD%&a_ajpJ@pZIB);2CAkN_K zGgXRP*bkuG1m&4XIit8{6Lj9N7v8N>#=tvdQ+ETX{7BQJWz?_>a`{NEef1x?s3Frw za_#)HHps45Qr$TK#K=q3u+hEW^B|0U%h{uzI+&0T8l%OF^nB3IpJ_bH{nfHaVh#`- zvE3~k0l1bM-93c^W~vB@-v<=jYd;?KJfyS@{rO-t2Ov}`wJ{z=lropymn$lwa=Mk; z&Z|@m63hIrOSUZ7OHmZgGda~Fr8K$JV1&f*1GJoV-OlNG4Uod-3OsYzHMtCpBPAKa!u`v3$yGG29?r{?yA3HTuzG{b#pqoqX zR`bjb5<~q|nj55DhD9=523|b&Kpn%V7 zEzdd^D~YEAX?T!suy${^grDDaQfDAW~YwNI!Esgo9Sje<%sD_w~`~EDV%H5Wv&ST8YZB< zj$4nFN4s8^vNezdl#HM+aWYTKt16wG^x^XMY$Q>WXAQPihhyAPy2t7K?uSXW!P+g?KB#T3AT!1E76VLKhFXm_PgLD1!h)IbeS4~i!J>Z1 zWWWBo-J3etUQxDpKo$dj)c)qavp|H9jbKgQ|lcc6DsGx_x2$r^!uj zGU8M+;{OadN0i4LwRsjQ$@n-pELPL!+N1KS&P3%`oVj?J7Hh|G@Jr^n+ers89ww?6 ztWnsBv_HB@7rt9v*xP&Bhuk^hn3!m=S&ra}b|w>CQ4^d5Q!Cw6Yg)rS`Oz+_l^knk zK9yJO#4t@@k#7im@rwmeo(AZ^PC&XvrN1z;Xy9KD=uv$bULj8M1ciUYr} z`mfwaxH7kyJI5`8=K^=?ki7<$S_$f-N_yL^?pfF6RBAt^oH?}Q;2>!O))9s_Vg_Vz zG9EJBu=V~yXvl120qF#y0Gos~lmKh?DCaEC?|m0onlEWzp-~BS-CKHFyS_QWS zguwJ}JzUp@T^^OrT}Up4TTVJI9~?_R9*)X8${mNhPg}UC^M>LB<#NzTvfXc$Up;By zx)OnZB+NT@-d^l+FDU-q9lk0Yd0Jx|<5~?SOY_(=kz%4!4Vr(bUol0UN7=_x5a_}d zKQ{fb8Mm%DfvPg*clY7nj4__yR6gooWg^S;yW4*2S@+j#Wh)Q=#;uFIzfdMJ%)i}# zy*6vz;otrqDZBKvsfyJrv$5u{*X~%kZVzMzF`Xr19V zMa*BXF+?36=5X|KBW0*`-i5ZMLIdUX`v2F|xY zUNyq3_1eTuzFc72XppVH_sM`b2fe$6C)a1=w}jU9&PivwIGEmL)DH6?P`rA}3Kr8j^xe!)$b6d54f|o3>;++>L{d3~JbA18&obVnGd5^vt=N*=^Cg!(&9uvQJ2bGaIt=`6>Je~W4i64 zq}udi8_GUR9AGqC{Q-Etg@hDdP;&in73mmVUt|AtNIIT8$Wv zu(VEa_Gn3KNUWcAJ%OgQihXGO2U0p%#g2zK@T0(!vG_^&BrIzzeiz0Dqj+~CGwGDO z7=YRZYQUcBPd6rk&DkjaxiLQlI#X=}VZXi+Y?d~3eO2Q{N#j_=?Kh2feF-&oz%YP8 zSk{=;X^PmHGvMgUA7x#TDbqD4SVZCFu%bd-Xn_I`I~DJZ2FLHuz);C(|v$U4abd9q#o2I)iO1s)fiSquKm_;16iBE+_ zDy$7HET1{_@`tce6Uj;)S*MGG7k(Mpi*tgaV@>)f7g@=QeUx@2zdA?&c{eyJ!efvP zlt!oJM*(RBbAkxB0^vD3^qlFE^CYl12_^sAa$yiGT7vDvU&2>E+etopfglEYY*Efe zIc&EYrsNa7UWPz{2gNEn6+v?&l>WA|5J{vH^-{siQzcl9e=d6i&z<^ z!2Y=}5g5JDHV;L4OyhOm>(iZkE_NP_JVI53> z!@u;98uZQZK?I-S5EgTX8O{uzMj`K$V0BLHO_;NS%ZDM>_^4Jb$8-9jBdgY!MFUL< z0q^g@hrzs;17MW<3>*t6u7`2H-&r&C<0RRfUf9V$!fu3*u)wIvh$jJnA3^-bh*$pC zh)G_QMbQE3#hjSlkpW`33jY1`Ns~z)v3PN6nCd5^Y7U!Nm(+!ITCNoE)*iw+j1$j5 zg*RMyl1S*slRh_m|6z+hWi2=dFkB|sq5|Fvz7boFx(|zk!rfc61**`GZVL}i%RCaB zK>MibS}m%Xb8e)MX>`J+tSbKamapwJPp+#7FKsbmM)-bk5f* zUtw;yVA`2S`9i{@J2S@h!z6^gIpN>ndq7uREqVfQ__`+?lnHqXcy8@-8tvVh7yx(>;nn3fj4{sUjKBAMiGWiRxf0bbJvmz`hPgGP$}di%=v` zp_uy4zPtUchiA5*Txz=Ot?h@0$JOKFg!WfWZ*9is-pL>6I zeb+39@ln(EP1{F27qBzzy{o&vqO@ZZfA0$8^{A5F;8;6gPdIP9u85@HwL5N@;NOO@&U!jYiudC+rs4dO_KgG(BE@0_@=O1c|@c?~K(D?A3S zQ1JGg9j-PS!2c2037Ayy@+vikz29^R%bV_@yL|s6bTw)5--L@zDXPYx46ej$xVNQ^ zFtx{m0=r`Z^*~T4-Qi3iLnGfnnCoD{zUTM;Gbl8@pkV^ue};s^FO)%|JtPEPC}oDd z^-yE$9>x#MlyH7)F%=gORNFRFU;Bkuw&hVBe&MriU>fySgoOTW#Tk|@h@Az?cE)zZ zf~AW~;#hEUSpk3`ah6Y*y8RPdNw5uo4|{7u?}L#hN%kHPH&O*;SF@7aDKR~B*S@lL zc0Vp~t#yL8=}w7m;`;HpriSgc+tuzeJ_P2rC ze93;l?^2c1L zV6}_X`yvSWDw0YD|B8>?jk$G^8Yut%|E@8={BEc+-<8j&*8^)|FIK3laUTLv6OL9%iV_V$X+{rG*gc4Ftv#VTK^-{X6 z(}^_A6(2!X`mO3}SDZ-4oq=1cTO@lQ%HQY2nro0Bdn=!X7;d!YzviSgKf;V?5D(A$ z(1Y;lhzJ#~dATi1N4^&z1Ln@}{W=79DWVvC4RGc}gIF_EUHh%1YLW}zUSVxVzr7OO z>i5QhRlgK0_%RB(W0JM>mU_Z`{fQj#lgl=NrEXtnlt&fEcuv4|4O{&umzC(mmBPDE zT$y`?OES;fNb=giX7BfI_Q}9? zkrb)#h~=1^e3(D*Ow`h2Gf~nUQUVxu{afiN+$Iy{p{UWlMnvl=LtTAOyQW^=N9!4l zr9Mi})^Dr-vcA46YR=E@s5w7D=yU&eFX+W2oK8v9s*7Z+ARy^ux~Dqe3tbQjAQVAB zmGu>tL-DWlV%#lUdsR#Q(b0xCU#({K$6dcTZhC0 zPiW4@yM@l?H0q)x{IfX^pAhiw{IR{mG5e!;Q~QXSYHc8jd}?ffT==KxE)EN!-L=$5!-r~Hc=%eM(Ak|COfLpdjVyTD1J#Qq&1h(%w!;|@R7q4)s52cB;$(O&}IO85?wyqB0s zaWnCa9&xJidzTB|*A|Uh3iu;fiG_(eCMz;EQHzVyGXisSyP zG&pWnzENr0&XMaVo9tUn$y~+RcHhS9CdX$U4a$N~TkbHvYBcua*j>h&{^Ux1?8koT zW~T4?5bGcFsktAU<^DL&Zd24*zgq4I8|-3A<8G7j`j|%Qj%j5}Qr~VrT}9o%M8oL#Gq1wg2iM2fv) z-^_iLy0_io4~cPpRXhM(#`=-8r(AIh2^PSOa(}+~)+qX20VG{LmU7ee+fDBBMkC)LEm!Ovgf31V2)oe+=mk z@WTRr7#}rs3rExK;)`~IqpkK495n)tBH%@af&A>PVE~S%uQ|ERW_s)_RXU~Y>r}uH z*Wmubqlu;ALcGowJD6_P_+q`-Cm*coAAP6R7wgG1Pa_}Tosr4L$Y(JV2K5nB{;WidfiOa#TXQ)U|g*=z%(!x6ZZ!hkSxKN zWyzA+8FT>$eQg=C-)+0OKi1^*-1F{d&%N*U-t*4+jim{D$EZ#h)&KR(z5(wQ6gxC! zC5z*exD0lzl%Q6A{3u(Vc~n{T+er7AkhTwKH`Mk^P?Sf44f3bKR=FqmwtOU5B3B2y zCItP<>oUDTzB=;pB;;|gI^4g8K$0YG2rG^#Hh;UTq`Zc(QXX9=g%uls98}eL2#nwd zuoeItaKKBr?@91{jA&uEZ$9|Y&~hPy#r4*(y5jGx6f z&&QtWIGo4zJP0=i=9%NELr85B0AV?Nr?}n>d{pzKAqHRh0??BWmZNZT1kQiZH#q6*lHQ`3CgyriR*)6hBP|ey1f29Bn*>)_DQ1oBMrvdy+l|?pXv;Vy z-`&(A+!i4ximpe4643~|-!6H}5b#1u!U06xzFHYW^(?I^1!Adc%A2X0I=cCsz_1D? z!^==*BKG}9m`WjKC1$bA6H=B(meibgI)*VETwM~e;s{mN5K=4=iwpkY(;7J+eARRw z3>ay{76dn#f%uU${1k={?dYamSUAL5RoUgV^%coUSZWs|8rj{m6_#WDbKWG4WYiR4 zjjuqX(*U*1L|Dw1GlD4t{1kjUN&XA~jAoRnnJ|nLZDrIt5NyMg*4l}?1)8z3;Y&to z2mTNmK`O-CyDL>S(zw^or@sMu$74&yFuR=O;laE00EiQPVP#dAmQ4l4g88GV z>**NDG~9xJySv%r%V|z_4U7#4wE*ZV@rm0c-|L=oU;j<}WQ!E{n&pcuTMh@;!rA*9 z{3dll{I4!^lJ1L6ai2SbX?iaQFe zXFbQ9$)f-#&N$}OKG0O3^t3uZff>gj$JaFJdkdO*pS5;m(HwTB!$KFayB$Vb#2uz7Sk@<2#dC zFh8t(F)R6=R&p;*V)h$4U9`?5!K_UP;arvAT1topvJNumB4mUoiOGrlB*?scNvIA6sG-|{?R-{uw^Fc2qh_1#W23-Z+ zLo`nh=OA9;`YN=$mWZ9Wei_tM4$D1wYXuQsduNaTgX`(kduB7t_Mmtdgj`6Z_ts;} z`6i;hx1dvZJpbqI7}VByx@QME1MzxS6WnsB*m8)>KH0dRh>tx)w1Rkk@jmDwk>>KD zJ@4&)_rRJpQdJ#GxiP5b21Ebo4Ff&plh!&uC*r=(h`8+(UWkGF+X&uz5OE`D2WTg# z;xq=0V<&G+cOuTu;atf~{<%pXB{KG~CZAKad}S%?^DU(V{wKZ?N-wcR{=H&47;^+Xk0GqGF40=VAm^x2>s1areD~YPD)YPOzriEB*$U1jyk4 From e1ffc2cdaa670494510827f65f508c4bdb22b57a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 16 May 2024 15:51:04 +0200 Subject: [PATCH 253/652] commander: add check for 5V overcurrent --- .../checks/powerCheck.cpp | 30 +++++++++++++++++++ .../checks/powerCheck.hpp | 1 + 2 files changed, 31 insertions(+) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp index 8b40191c4212..0b23a949aef6 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp @@ -142,6 +142,36 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) power_module_count, _param_com_power_count.get()); } } + + // Overcurrent detection + if (system_power.hipower_5v_oc) { + /* EVENT + * @description + * Check the power supply + */ + reporter.healthFailure(NavModes::All, health_component_t::system, + events::ID("check_power_oc_hipower"), + events::Log::Error, "Overcurrent detected for the hipower 5V supply"); + } + + if (system_power.periph_5v_oc) { + /* EVENT + * @description + * Check the power supply + */ + reporter.healthFailure(NavModes::All, health_component_t::system, + events::ID("check_power_oc_periph"), + events::Log::Error, "Overcurrent detected for the peripheral 5V supply"); + } + + if (system_power.hipower_5v_oc || system_power.periph_5v_oc) { + if (context.isArmed() && !_overcurrent_warning_sent) { + _overcurrent_warning_sent = true; + events::send(events::ID("check_power_oc_report"), + events::Log::Error, + "5V overcurrent detected, landing advised"); + } + } } } else { diff --git a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp index 72ed92839101..b81fadaee062 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp @@ -48,6 +48,7 @@ class PowerChecks : public HealthAndArmingCheckBase private: uORB::Subscription _system_power_sub{ORB_ID(system_power)}; + bool _overcurrent_warning_sent{false}; DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, (ParamInt) _param_cbrk_supply_chk, From 4f64acb3524d39967bd7f516ae2ebfe4be5246bc Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 23 May 2024 08:44:34 +1000 Subject: [PATCH 254/652] Docs for camera_feedback module (#23103) * Docs for camera_feedback module * Update src/modules/camera_feedback/CameraFeedback.cpp * Update src/modules/camera_feedback/CameraFeedback.cpp --- src/modules/camera_feedback/CameraFeedback.cpp | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/src/modules/camera_feedback/CameraFeedback.cpp b/src/modules/camera_feedback/CameraFeedback.cpp index 35ac09296dc2..b38f2f83d7b5 100644 --- a/src/modules/camera_feedback/CameraFeedback.cpp +++ b/src/modules/camera_feedback/CameraFeedback.cpp @@ -194,6 +194,24 @@ CameraFeedback::print_usage(const char *reason) R"DESCR_STR( ### Description +The camera_feedback module publishes `CameraCapture` UORB topics when image capture has been triggered. + +If camera capture is enabled, then trigger information from the camera capture pin is published; +otherwise trigger information at the point the camera was commanded to trigger is published +(from the `camera_trigger` module). + +The `CAMERA_IMAGE_CAPTURED` message is then emitted (by streaming code) following `CameraCapture` updates. +`CameraCapture` topics are also logged and can be used for geotagging. + +### Implementation + +`CameraTrigger` topics are published by the `camera_trigger` module (`feedback` field set `false`) when image capture is triggered, +and may also be published by the `camera_capture` driver (with `feedback` field set `true`) if the camera capture pin is activated. + +The `camera_feedback` module subscribes to `CameraTrigger`. +It discards topics from the `camera_trigger` module if camera capture is enabled. +For the topics that are not discarded it creates a `CameraCapture` topic with the timestamp information +from the `CameraTrigger` and position information from the vehicle. )DESCR_STR"); From ccbcbbe26832146a7e0d9d14b82bfd0e19b93691 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 24 May 2024 16:21:44 +0200 Subject: [PATCH 255/652] wind_est_replay: report scale instead of inverse_scale The estimator internally estimates the scale inverse, but the interface should be the scale as "airspeed_corrected = scale * airspeed" --- src/lib/wind_estimator/python/wind_estimator_replay.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/lib/wind_estimator/python/wind_estimator_replay.py b/src/lib/wind_estimator/python/wind_estimator_replay.py index 0a165dfe8df4..dcc292286df6 100644 --- a/src/lib/wind_estimator/python/wind_estimator_replay.py +++ b/src/lib/wind_estimator/python/wind_estimator_replay.py @@ -78,7 +78,9 @@ def run(logfile, use_gnss, scale_init): if scale_init is None: scale_init = 1.0 - state = np.array([0.0, 0.0, scale_init]) + # The estimator estimates the inverse scale factor to have a simpler measurement jacobian + inverse_scale_init = 1 / scale_init + state = np.array([0.0, 0.0, inverse_scale_init]) P = np.diag([1.0, 1.0, 1e-4]) wind_nsd = 1e-2 scale_nsd = 1e-4 @@ -118,7 +120,7 @@ def run(logfile, use_gnss, scale_init): wind_est_n[i] = state[0] wind_est_e[i] = state[1] - scale_est[i] = state[2] + scale_est[i] = 1 / state[2] plt.figure(1) ax1 = plt.subplot(2, 1, 1) From da35c4adce5a3baa6dae4d6a3ddca33abb3a2c0c Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Sat, 25 May 2024 17:16:34 -0600 Subject: [PATCH 256/652] cdcacm_autostart: handle USB power only (#23183) --- src/drivers/cdcacm_autostart/cdcacm_autostart.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp index d7ebbddd6b0f..3c963e798820 100644 --- a/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp @@ -206,7 +206,8 @@ void CdcAcmAutostart::state_connecting() if (_ttyacm_fd < 0) { PX4_DEBUG("can't open port"); - goto fail; + // fail silently and keep trying to open the port + return; } if (_sys_usb_auto.get() == 2) { From f9e2ab8d4446e5549fe79e9beb3a558bcd700f59 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 27 May 2024 09:29:29 +0200 Subject: [PATCH 257/652] msg-rates-setpoint: fix frame name NED -> FRD --- msg/VehicleRatesSetpoint.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/VehicleRatesSetpoint.msg b/msg/VehicleRatesSetpoint.msg index 88adcf3bea98..35a06c35aa5f 100644 --- a/msg/VehicleRatesSetpoint.msg +++ b/msg/VehicleRatesSetpoint.msg @@ -1,6 +1,6 @@ uint64 timestamp # time since system start (microseconds) -# body angular rates in NED frame +# body angular rates in FRD frame float32 roll # [rad/s] roll rate setpoint float32 pitch # [rad/s] pitch rate setpoint float32 yaw # [rad/s] yaw rate setpoint From b9d3b9f2117311b06b3884518335df128f44ba2f Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 24 May 2024 13:34:12 +0200 Subject: [PATCH 258/652] RTL_mission_fast: continue mission if RTL is triggered while in Mission Signed-off-by: Silvan Fuhrer --- src/modules/navigator/mission_base.h | 14 +++++++------- src/modules/navigator/rtl_mission_fast.cpp | 19 +++++++++++++++++-- src/modules/navigator/rtl_mission_fast.h | 3 +++ 3 files changed, 27 insertions(+), 9 deletions(-) diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index 405291969e4d..2f416f29e206 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -314,6 +314,13 @@ class MissionBase : public MissionBlock, public ModuleParams */ bool position_setpoint_equal(const position_setpoint_s *p1, const position_setpoint_s *p2) const; + /** + * @brief Set the Mission Index + * + * @param[in] index Index of the mission item + */ + void setMissionIndex(int32_t index); + bool _is_current_planned_mission_item_valid{false}; /**< Flag indicating if the currently loaded mission item is valid*/ bool _mission_has_been_activated{false}; /**< Flag indicating if the mission has been activated*/ bool _mission_checked{false}; /**< Flag indicating if the mission has been checked by the mission validator*/ @@ -421,13 +428,6 @@ class MissionBase : public MissionBlock, public ModuleParams */ bool cameraWasTriggering(); - /** - * @brief Set the Mission Index - * - * @param[in] index Index of the mission item - */ - void setMissionIndex(int32_t index); - /** * @brief Parameters update * diff --git a/src/modules/navigator/rtl_mission_fast.cpp b/src/modules/navigator/rtl_mission_fast.cpp index 70eb4819ffb0..1da091ce1bd1 100644 --- a/src/modules/navigator/rtl_mission_fast.cpp +++ b/src/modules/navigator/rtl_mission_fast.cpp @@ -52,12 +52,27 @@ RtlMissionFast::RtlMissionFast(Navigator *navigator) : } +void RtlMissionFast::on_inactive() +{ + MissionBase::on_inactive(); + _vehicle_status_sub.update(); + _mission_index_prior_rtl = _vehicle_status_sub.get().nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION ? + _mission.current_seq : -1; +} + void RtlMissionFast::on_activation() { _home_pos_sub.update(); - _is_current_planned_mission_item_valid = setMissionToClosestItem(_global_pos_sub.get().lat, _global_pos_sub.get().lon, - _global_pos_sub.get().alt, _home_pos_sub.get().alt, _vehicle_status_sub.get()) == PX4_OK; + // set mission item to closest item if not already in mission + if (_mission_index_prior_rtl < 0) { + _is_current_planned_mission_item_valid = setMissionToClosestItem(_global_pos_sub.get().lat, _global_pos_sub.get().lon, + _global_pos_sub.get().alt, _home_pos_sub.get().alt, _vehicle_status_sub.get()) == PX4_OK; + + } else { + setMissionIndex(_mission_index_prior_rtl); + _is_current_planned_mission_item_valid = isMissionValid(); + } if (_land_detected_sub.get().landed) { // already landed, no need to do anything, invalidad the position mission item. diff --git a/src/modules/navigator/rtl_mission_fast.h b/src/modules/navigator/rtl_mission_fast.h index bb3db38c6465..c782a471bd7a 100644 --- a/src/modules/navigator/rtl_mission_fast.h +++ b/src/modules/navigator/rtl_mission_fast.h @@ -56,6 +56,7 @@ class RtlMissionFast : public RtlBase ~RtlMissionFast() = default; void on_activation() override; + void on_inactive() override; rtl_time_estimate_s calc_rtl_time_estimate() override; @@ -63,5 +64,7 @@ class RtlMissionFast : public RtlBase bool setNextMissionItem() override; void setActiveMissionItems() override; + int _mission_index_prior_rtl{-1}; + uORB::SubscriptionData _home_pos_sub{ORB_ID(home_position)}; /**< home position subscription */ }; From 42bca65cbf574ecd529bb23c84c327fc6be59521 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 24 May 2024 13:40:21 +0200 Subject: [PATCH 259/652] RTL_mission_reverse: start from previous WP if RTL is triggered while in Mission Signed-off-by: Silvan Fuhrer --- .../navigator/rtl_mission_fast_reverse.cpp | 19 +++++++++++++++++-- .../navigator/rtl_mission_fast_reverse.h | 3 +++ 2 files changed, 20 insertions(+), 2 deletions(-) diff --git a/src/modules/navigator/rtl_mission_fast_reverse.cpp b/src/modules/navigator/rtl_mission_fast_reverse.cpp index 967e280bfd69..d7c42516e41d 100644 --- a/src/modules/navigator/rtl_mission_fast_reverse.cpp +++ b/src/modules/navigator/rtl_mission_fast_reverse.cpp @@ -52,12 +52,27 @@ RtlMissionFastReverse::RtlMissionFastReverse(Navigator *navigator) : } +void RtlMissionFastReverse::on_inactive() +{ + MissionBase::on_inactive(); + _vehicle_status_sub.update(); + _mission_index_prior_rtl = _vehicle_status_sub.get().nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION ? + _mission.current_seq : -1; +} + void RtlMissionFastReverse::on_activation() { _home_pos_sub.update(); - _is_current_planned_mission_item_valid = setMissionToClosestItem(_global_pos_sub.get().lat, _global_pos_sub.get().lon, - _global_pos_sub.get().alt, _home_pos_sub.get().alt, _vehicle_status_sub.get()) == PX4_OK; + // set mission item to closest item if not already in mission. If we are in mission, set to the previous item. + if (_mission_index_prior_rtl < 0) { + _is_current_planned_mission_item_valid = setMissionToClosestItem(_global_pos_sub.get().lat, _global_pos_sub.get().lon, + _global_pos_sub.get().alt, _home_pos_sub.get().alt, _vehicle_status_sub.get()) == PX4_OK; + + } else { + setMissionIndex(math::max(_mission_index_prior_rtl - 1, 0)); + _is_current_planned_mission_item_valid = isMissionValid(); + } if (_land_detected_sub.get().landed) { // already landed, no need to do anything, invalidate the position mission item. diff --git a/src/modules/navigator/rtl_mission_fast_reverse.h b/src/modules/navigator/rtl_mission_fast_reverse.h index 889dd8716b5e..f1301a5ccafd 100644 --- a/src/modules/navigator/rtl_mission_fast_reverse.h +++ b/src/modules/navigator/rtl_mission_fast_reverse.h @@ -57,6 +57,7 @@ class RtlMissionFastReverse : public RtlBase void on_activation() override; void on_active() override; + void on_inactive() override; rtl_time_estimate_s calc_rtl_time_estimate() override; @@ -65,5 +66,7 @@ class RtlMissionFastReverse : public RtlBase void setActiveMissionItems() override; void handleLanding(WorkItemType &new_work_item_type); + int _mission_index_prior_rtl{-1}; + uORB::SubscriptionData _home_pos_sub{ORB_ID(home_position)}; /**< home position subscription */ }; From 1206005ed2111d755351b1b60c7eb076e4cbc10b Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 24 May 2024 13:31:43 +0200 Subject: [PATCH 260/652] RTL_status: improve comment Signed-off-by: Silvan Fuhrer --- msg/RtlStatus.msg | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/msg/RtlStatus.msg b/msg/RtlStatus.msg index 94c90d513e38..f25b22243a19 100644 --- a/msg/RtlStatus.msg +++ b/msg/RtlStatus.msg @@ -8,8 +8,8 @@ bool has_vtol_approach # flag if approaches are defined for current RTL_ uint8 rtl_type # Type of RTL chosen uint8 safe_point_index # index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode -uint8 RTL_STATUS_TYPE_NONE=0 # RTL type is pending if evaluation can't pe performed currently e.g. when it is still loading the safe points -uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # RTL type is chosen to directly go to a safe point or home position -uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # RTL type is going straight to the beginning of the mission landing -uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # RTL type is following the mission from closest point to mission landing -uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # RTL type is following the mission in reverse to the start position +uint8 RTL_STATUS_TYPE_NONE=0 # pending if evaluation can't pe performed currently e.g. when it is still loading the safe points +uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # chosen to directly go to a safe point or home position +uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # going straight to the beginning of the mission landing +uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # Following the mission from start index to mission landing. Start index is current WP if in Mission mode, and closest WP otherwise. +uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # Following the mission in reverse from start index to the beginning of the mission. Start index is previous WP if in Mission mode, and closest WP otherwise. From dfee9ca4c63de9c0b2ff2949dcba93e415061ab8 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 27 May 2024 18:11:41 +0200 Subject: [PATCH 261/652] MAVLink: remove never used `_mavlink_link_termination_allowed` --- src/modules/mavlink/mavlink_main.cpp | 4 ---- src/modules/mavlink/mavlink_main.h | 2 -- 2 files changed, 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 186bfe793631..3abd4f71a2ae 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1963,10 +1963,6 @@ Mavlink::task_main(int argc, char *argv[]) break; #endif -// case 'e': -// _mavlink_link_termination_allowed = true; -// break; - case 'm': { int mode; diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 9444b8058a48..17925f8ed8e4 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -597,8 +597,6 @@ class Mavlink final : public ModuleParams */ unsigned int _mavlink_param_queue_index{0}; - bool _mavlink_link_termination_allowed{false}; - char *_subscribe_to_stream{nullptr}; float _subscribe_to_stream_rate{0.0f}; ///< rate of stream to subscribe to (0=disable, -1=unlimited, -2=default) bool _udp_initialised{false}; From f8fe7c7aa3c7304191a28639c24fd0a840bbc97b Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 22 May 2024 16:48:28 +0200 Subject: [PATCH 262/652] VTOL Standard: fix transition pusher motor slew rate Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/standard.cpp | 5 ++++- src/modules/vtol_att_control/standard.h | 1 + 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/vtol_att_control/standard.cpp b/src/modules/vtol_att_control/standard.cpp index d74ab45f4225..84606aad4327 100644 --- a/src/modules/vtol_att_control/standard.cpp +++ b/src/modules/vtol_att_control/standard.cpp @@ -200,8 +200,11 @@ void Standard::update_transition_state() } else if (_pusher_throttle <= _param_vt_f_trans_thr.get()) { // ramp up throttle to the target throttle value + const float dt = math::min((now - _last_time_pusher_transition_update) / 1e6f, 0.05f); _pusher_throttle = math::min(_pusher_throttle + - _param_vt_psher_slew.get() * _dt, _param_vt_f_trans_thr.get()); + _param_vt_psher_slew.get() * dt, _param_vt_f_trans_thr.get()); + + _last_time_pusher_transition_update = now; } _airspeed_trans_blend_margin = getTransitionAirspeed() - getBlendAirspeed(); diff --git a/src/modules/vtol_att_control/standard.h b/src/modules/vtol_att_control/standard.h index 280f2e5042ee..6136f872075f 100644 --- a/src/modules/vtol_att_control/standard.h +++ b/src/modules/vtol_att_control/standard.h @@ -76,6 +76,7 @@ class Standard : public VtolType float _pusher_throttle{0.0f}; float _airspeed_trans_blend_margin{0.0f}; + hrt_abstime _last_time_pusher_transition_update{0}; void parameters_update() override; From 032ae69eeef7ec74c238f0de52c1e4c8070081ea Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 22 May 2024 16:53:23 +0200 Subject: [PATCH 263/652] VTOL: remove _dt passing as it's no longer used (and was wrong) Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/vtol_att_control_main.cpp | 9 ++------- src/modules/vtol_att_control/vtol_att_control_main.h | 6 +++--- src/modules/vtol_att_control/vtol_type.h | 8 -------- 3 files changed, 5 insertions(+), 18 deletions(-) diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp index b464793c99ce..199dcac84c56 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -284,10 +284,10 @@ VtolAttitudeControl::Run() return; } - const hrt_abstime now = hrt_absolute_time(); - #if !defined(ENABLE_LOCKSTEP_SCHEDULER) + const hrt_abstime now = hrt_absolute_time(); + // prevent excessive scheduling (> 500 Hz) if (now - _last_run_timestamp < 2_ms) { return; @@ -295,9 +295,6 @@ VtolAttitudeControl::Run() #endif // !ENABLE_LOCKSTEP_SCHEDULER - const float dt = math::min((now - _last_run_timestamp) / 1e6f, kMaxVTOLAttitudeControlTimeStep); - _last_run_timestamp = now; - if (!_initialized) { if (_vtol_type->init()) { @@ -309,8 +306,6 @@ VtolAttitudeControl::Run() } } - _vtol_type->setDt(dt); - perf_begin(_loop_perf); bool updated_fw_in = _vehicle_torque_setpoint_virtual_fw_sub.update(&_vehicle_torque_setpoint_virtual_fw); diff --git a/src/modules/vtol_att_control/vtol_att_control_main.h b/src/modules/vtol_att_control/vtol_att_control_main.h index 132448177f33..6ef046f05f8a 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.h +++ b/src/modules/vtol_att_control/vtol_att_control_main.h @@ -92,8 +92,6 @@ using namespace time_literals; extern "C" __EXPORT int vtol_att_control_main(int argc, char *argv[]); -static constexpr float kMaxVTOLAttitudeControlTimeStep = 0.1f; // max time step [s] - class VtolAttitudeControl : public ModuleBase, public ModuleParams, public px4::WorkItem { public: @@ -211,7 +209,9 @@ class VtolAttitudeControl : public ModuleBase, public Modul float _air_density{atmosphere::kAirDensitySeaLevelStandardAtmos}; // [kg/m^3] - hrt_abstime _last_run_timestamp{0}; +#if !defined(ENABLE_LOCKSTEP_SCHEDULER) + hrt_abstime _last_run_timestamp {0}; +#endif // !ENABLE_LOCKSTEP_SCHEDULER /* For multicopters it is usual to have a non-zero idle speed of the engines * for fixed wings we want to have an idle speed of zero since we do not want diff --git a/src/modules/vtol_att_control/vtol_type.h b/src/modules/vtol_att_control/vtol_type.h index d59887372efb..78d078b5c8d8 100644 --- a/src/modules/vtol_att_control/vtol_type.h +++ b/src/modules/vtol_att_control/vtol_type.h @@ -251,12 +251,6 @@ class VtolType : public ModuleParams virtual void parameters_update() = 0; - /** - * @brief Set current time delta - * - * @param dt Current time delta [s] - */ - void setDt(float dt) {_dt = dt; } /** * @brief Resets the transition timer states. @@ -326,8 +320,6 @@ class VtolType : public ModuleParams bool isFrontTransitionCompleted(); virtual bool isFrontTransitionCompletedBase(); - float _dt{0.0025f}; // time step [s] - float _local_position_z_start_of_transition{0.f}; // altitude at start of transition int _altitude_reset_counter{0}; From d1db0addf9e71acec6b5c364b6991951a3339421 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 28 May 2024 16:16:59 +0200 Subject: [PATCH 264/652] CameraFeedback: shorten line length such that documentation parser works This broke in 4f64acb3524d39967bd7f516ae2ebfe4be5246bc and was also flagged by CI in the pr and since then. --- src/modules/camera_feedback/CameraFeedback.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/camera_feedback/CameraFeedback.cpp b/src/modules/camera_feedback/CameraFeedback.cpp index b38f2f83d7b5..a4c89f59715a 100644 --- a/src/modules/camera_feedback/CameraFeedback.cpp +++ b/src/modules/camera_feedback/CameraFeedback.cpp @@ -196,7 +196,7 @@ CameraFeedback::print_usage(const char *reason) The camera_feedback module publishes `CameraCapture` UORB topics when image capture has been triggered. -If camera capture is enabled, then trigger information from the camera capture pin is published; +If camera capture is enabled, then trigger information from the camera capture pin is published; otherwise trigger information at the point the camera was commanded to trigger is published (from the `camera_trigger` module). @@ -205,8 +205,9 @@ The `CAMERA_IMAGE_CAPTURED` message is then emitted (by streaming code) followin ### Implementation -`CameraTrigger` topics are published by the `camera_trigger` module (`feedback` field set `false`) when image capture is triggered, -and may also be published by the `camera_capture` driver (with `feedback` field set `true`) if the camera capture pin is activated. +`CameraTrigger` topics are published by the `camera_trigger` module (`feedback` field set `false`) +when image capture is triggered, and may also be published by the `camera_capture` driver +(with `feedback` field set `true`) if the camera capture pin is activated. The `camera_feedback` module subscribes to `CameraTrigger`. It discards topics from the `camera_trigger` module if camera capture is enabled. From b5627f487fe285ce6366f3d0dfe33265b376a7e7 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 29 May 2024 19:37:27 +1000 Subject: [PATCH 265/652] camera_trigger: module docs for camera trigger driver (#23104) --- Tools/px4moduledoc/srcparser.py | 2 +- src/drivers/camera_trigger/camera_trigger.cpp | 41 ++++++++++++++++++- .../interfaces/src/camera_interface.h | 3 +- 3 files changed, 42 insertions(+), 4 deletions(-) diff --git a/Tools/px4moduledoc/srcparser.py b/Tools/px4moduledoc/srcparser.py index b9b348252013..3eacbf432548 100644 --- a/Tools/px4moduledoc/srcparser.py +++ b/Tools/px4moduledoc/srcparser.py @@ -15,7 +15,7 @@ class ModuleDocumentation(object): # TOC in https://github.com/PX4/PX4-user_guide/blob/main/en/SUMMARY.md valid_categories = ['driver', 'estimator', 'controller', 'system', 'communication', 'command', 'template', 'simulation', 'autotune'] - valid_subcategories = ['', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor', + valid_subcategories = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor', 'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder'] max_line_length = 80 # wrap lines that are longer than this diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index 4f49e5692baf..33d89f3c0166 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -53,6 +53,7 @@ #include #include #include +#include #include #include @@ -924,7 +925,45 @@ CameraTrigger::status() static int usage() { - PX4_INFO("usage: camera_trigger {start|stop|status|test|test_power}\n"); + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description + +Camera trigger driver. + +This module triggers cameras that are connected to the flight-controller outputs, +or simple MAVLink cameras that implement the MAVLink trigger protocol. + +The driver responds to the following MAVLink trigger commands being found in missions or recieved over MAVLink: + +- `MAV_CMD_DO_TRIGGER_CONTROL` +- `MAV_CMD_DO_DIGICAM_CONTROL` +- `MAV_CMD_DO_SET_CAM_TRIGG_DIST` +- `MAV_CMD_OBLIQUE_SURVEY` + +The commands cause the driver to trigger camera image capture based on time or distance. +Each time an image capture is triggered, the `CAMERA_TRIGGER` MAVLink message is emitted. + +A "simple MAVLink camera" is one that supports the above command set. +When configured for this kind of camera, all the driver does is emit the `CAMERA_TRIGGER` MAVLink message as expected. +The incoming commands must be forwarded to the MAVLink camera, and are automatically emitted to MAVLink channels +when found in missions. + +The driver is configured using [Camera Trigger parameters](../advanced_config/parameter_reference.md#camera-trigger). +In particular: + +- `TRIG_INTERFACE` - How the camera is connected to flight controller (PWM, GPIO, Seagull, MAVLink) +- `TRIG_MODE` - Distance or time based triggering, with values set by `TRIG_DISTANCE` and `TRIG_INTERVAL`. + +[Setup/usage information](../camera/index.md). +)DESCR_STR"); + PRINT_MODULE_USAGE_NAME("camera_trigger", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("camera"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("status","Print driver status information"); + PRINT_MODULE_USAGE_COMMAND_DESCR("test","Trigger one image (not logged or forwarded to GCS)"); + PRINT_MODULE_USAGE_COMMAND_DESCR("test_power","Toggle power"); return 1; } diff --git a/src/drivers/camera_trigger/interfaces/src/camera_interface.h b/src/drivers/camera_trigger/interfaces/src/camera_interface.h index f9079ea2bad2..d3c9a699ff4d 100644 --- a/src/drivers/camera_trigger/interfaces/src/camera_interface.h +++ b/src/drivers/camera_trigger/interfaces/src/camera_interface.h @@ -39,8 +39,7 @@ #include #include - -#define arraySize(a) (sizeof((a))/sizeof(((a)[0]))) +#include class CameraInterface { From a4650fd70dfe3357b7b3edab5af16f6dbe0f13bb Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Wed, 29 May 2024 03:56:50 -0600 Subject: [PATCH 266/652] HealthCheck: added health check for logger to report if it's running (#22781) --- msg/LoggerStatus.msg | 2 + .../HealthAndArmingChecks/CMakeLists.txt | 1 + .../HealthAndArmingChecks.hpp | 3 + .../checks/loggerCheck.cpp | 60 +++++++++++++++++++ .../checks/loggerCheck.hpp | 54 +++++++++++++++++ src/modules/logger/logger.cpp | 15 +++-- src/modules/mavlink/streams/SYS_STATUS.hpp | 1 + 7 files changed, 130 insertions(+), 6 deletions(-) create mode 100644 src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.cpp create mode 100644 src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.hpp diff --git a/msg/LoggerStatus.msg b/msg/LoggerStatus.msg index 9a07871a0f65..c67c88959252 100644 --- a/msg/LoggerStatus.msg +++ b/msg/LoggerStatus.msg @@ -9,6 +9,8 @@ uint8 BACKEND_MAVLINK = 2 uint8 BACKEND_ALL = 3 uint8 backend +bool is_logging + float32 total_written_kb # total written to log in kiloBytes float32 write_rate_kb_s # write rate in kiloBytes/s diff --git a/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt b/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt index a4e1873be9c0..7c78c47c8534 100644 --- a/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt +++ b/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt @@ -50,6 +50,7 @@ px4_add_library(health_and_arming_checks checks/gyroCheck.cpp checks/homePositionCheck.cpp checks/imuConsistencyCheck.cpp + checks/loggerCheck.cpp checks/magnetometerCheck.cpp checks/manualControlCheck.cpp checks/missionCheck.cpp diff --git a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp index b349475593fd..9ea83999ef73 100644 --- a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp +++ b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp @@ -51,6 +51,7 @@ #include "checks/failureDetectorCheck.hpp" #include "checks/gyroCheck.hpp" #include "checks/imuConsistencyCheck.hpp" +#include "checks/loggerCheck.hpp" #include "checks/magnetometerCheck.hpp" #include "checks/manualControlCheck.hpp" #include "checks/homePositionCheck.hpp" @@ -130,6 +131,7 @@ class HealthAndArmingChecks : public ModuleParams FailureDetectorChecks _failure_detector_checks; GyroChecks _gyro_checks; ImuConsistencyChecks _imu_consistency_checks; + LoggerChecks _logger_checks; MagnetometerChecks _magnetometer_checks; ManualControlChecks _manual_control_checks; HomePositionChecks _home_position_checks; @@ -167,6 +169,7 @@ class HealthAndArmingChecks : public ModuleParams &_failure_detector_checks, &_gyro_checks, &_imu_consistency_checks, + &_logger_checks, &_magnetometer_checks, &_manual_control_checks, &_home_position_checks, diff --git a/src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.cpp new file mode 100644 index 000000000000..85bd8909ae3c --- /dev/null +++ b/src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.cpp @@ -0,0 +1,60 @@ +/**************************************************************************** + * + * 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 "loggerCheck.hpp" + +using namespace time_literals; + +LoggerChecks::LoggerChecks() + : _param_sdlog_mode_handle(param_find("SDLOG_MODE")) +{ + param_get(_param_sdlog_mode_handle, &_sdlog_mode); +} + +void LoggerChecks::checkAndReport(const Context &context, Report &reporter) +{ + bool active = false; + + if (_sdlog_mode >= 0) { + if (_logger_status_sub.advertised()) { + logger_status_s status; + _logger_status_sub.copy(&status); + + if (hrt_elapsed_time(&status.timestamp) < 3_s && status.is_logging) { + active = true; + } + } + } + + reporter.setHealth(health_component_t::logging, active, false, false); +} diff --git a/src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.hpp new file mode 100644 index 000000000000..bcc161efcab9 --- /dev/null +++ b/src/modules/commander/HealthAndArmingChecks/checks/loggerCheck.hpp @@ -0,0 +1,54 @@ +/**************************************************************************** + * + * 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 "../Common.hpp" + +#include +#include +#include + +class LoggerChecks : public HealthAndArmingCheckBase +{ +public: + LoggerChecks(); + ~LoggerChecks() = default; + + void checkAndReport(const Context &context, Report &reporter) override; + +private: + uORB::Subscription _logger_status_sub{ORB_ID::logger_status}; + const param_t _param_sdlog_mode_handle; + int32_t _sdlog_mode = -1; +}; diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index f9c3f66800c9..be66d5465c95 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -1037,6 +1037,12 @@ void Logger::publish_logger_status() if (hrt_elapsed_time(&_logger_status_last) >= 1_s) { for (int i = 0; i < (int)LogType::Count; ++i) { + logger_status_s status = {}; + status.type = i; + status.backend = _writer.backend(); + status.num_messages = _num_subscriptions; + status.timestamp = hrt_absolute_time(); + const LogType log_type = static_cast(i); if (_writer.is_started(log_type)) { @@ -1046,19 +1052,16 @@ void Logger::publish_logger_status() const float kb_written = _writer.get_total_written_file(log_type) / 1024.0f; const float seconds = hrt_elapsed_time(&_statistics[i].start_time_file) * 1e-6f; - logger_status_s status; - status.type = i; - status.backend = _writer.backend(); + status.is_logging = true; status.total_written_kb = kb_written; status.write_rate_kb_s = kb_written / seconds; status.dropouts = _statistics[i].write_dropouts; status.message_gaps = _message_gaps; status.buffer_used_bytes = buffer_fill_count_file; status.buffer_size_bytes = _writer.get_buffer_size_file(log_type); - status.num_messages = _num_subscriptions; - status.timestamp = hrt_absolute_time(); - _logger_status_pub[i].publish(status); } + + _logger_status_pub[i].publish(status); } _logger_status_last = hrt_absolute_time(); diff --git a/src/modules/mavlink/streams/SYS_STATUS.hpp b/src/modules/mavlink/streams/SYS_STATUS.hpp index 6859ea7f4be1..9a2b2cb691ec 100644 --- a/src/modules/mavlink/streams/SYS_STATUS.hpp +++ b/src/modules/mavlink/streams/SYS_STATUS.hpp @@ -151,6 +151,7 @@ class MavlinkStreamSysStatus : public MavlinkStream fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_GPS, health_component_t::gps, msg); fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_RC_RECEIVER, health_component_t::remote_control, msg); fillOutComponent(health_report, MAV_SYS_STATUS_AHRS, health_component_t::local_position_estimate, msg); + fillOutComponent(health_report, MAV_SYS_STATUS_LOGGING, health_component_t::logging, msg); fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, health_component_t::absolute_pressure, msg); fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, health_component_t::differential_pressure, msg); From daa89ba30aaa71c1f6a6ee5be0714e7755f2545b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 29 May 2024 15:37:39 +0200 Subject: [PATCH 267/652] Jankinsfile-compile: add missing comma after `ark_pi6x_default` --- .ci/Jenkinsfile-compile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 0431761e98f1..c482b14d459d 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -47,7 +47,7 @@ pipeline { "ark_fmu-v6x_bootloader", "ark_fmu-v6x_default", "ark_pi6x_bootloader", - "ark_pi6x_default" + "ark_pi6x_default", "atl_mantis-edu_default", "av_x-v1_default", "bitcraze_crazyflie21_default", From 04e0d3475f71de3839d11f3f515041fd33a9c9eb Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 23 May 2024 05:29:22 -0700 Subject: [PATCH 268/652] nxp/imxrt_common/main:Fix Breakage from a9962dc --- .../extras/px4_fmu-v6xrt_bootloader.bin | Bin 78640 -> 82728 bytes .../src/bootloader/nxp/imxrt_common/main.c | 8 ++++++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/boards/px4/fmu-v6xrt/extras/px4_fmu-v6xrt_bootloader.bin b/boards/px4/fmu-v6xrt/extras/px4_fmu-v6xrt_bootloader.bin index cb9cbb304e66212006483a59f916c0e837ec2f98..13ee91a2b2e4749ed04b6551972e3cbd4b8b3833 100755 GIT binary patch delta 15970 zcmd_RdstLe_c*@ynKLllbP$m{%$Wfh9MOZI;(Y);fT(!a)N)9z(eh=ymDX#3m(tQV zZC7~7Le0X|WJFR-g3>N#_CjTuX5y`})H*11&RoxT?E&B3_w)Ro=l6X7dOy$e<$2cZ z`#Ni{z4qE`t-Y!Fg{^*GU8O5)%1_qqHz2-k@P7r${#zgJ`fk~OW!8U9y6nHh_J0vj z_Fr1}2L$}TzW(X|SL;vSF=T0$-;i(aErSfH& zZN2;}V_<7+`R3e`+c_AS;w~ZaQ8Fr(!;?r!Y8=iZt5eewx6~hM(}XVmmHirt#{U?H z;IFnRRjVSceR^Uy>FBdMN{|Bzu$brnHOuOPhFcml7KhbtG?l2k_j4mX!%c-sF$amM z#K{lD@uYvovk^bL`dP6~Xh*8Nb~MjqLE?GRkTD|S1J_`v&u>Q&59$w*umQ`M!!ELB zz%$GeSFLYAD1-ZvkbxTuvD08JZhyvR5Opd8pm53ttDzkk3>IyJLBuM58`R&0dYT86 z(1ygD56WHRE|bdx4dG`W)V7!Vdz~WTgQ6Zg)>Uihsyz&4_(tY$4%Enx`NFKNYrH@A zWh9n5Ss~hP;4*<5AIq6VT79vICPiC{#U}GC3qN)TO;EAPUlHmdZ;VO~jev>`OIR4&?j~Q2GKM#m((UW3cN_2>mdp-P9uuRSKKUf>E1Vp$%m%LCq0X+Gs)b&B+!q8H)| z8R+#P^p7o6L+%5}#S{iW&JMY#!fuc|2)SN`p^$qQay<)mup)arqG2tt_|XrtVGY<; z)LMQOwIUtjHFpsy&JEWO$w7Ri8SycY?izvkg#ZHqf&eZLN4$MFS(BU0RJllXu1@>1 z%OvQ>B3*JJdL4-yT;xKoo_WeeJh_Se9&;gGx3RqnkyzsDDKaRmIT(6IK=~opANRx8 zmis9=#A$&MgIuH_Z&sqlWxR`8OQSKbsf)4qC{S5n%2hS5;liPd%SoE@dZ|FF$d7rW zv<|0w=ODm0s1Ut|#8xLUj@C0@JIT1w`m&QwZfsg1%nCNfH5Ge45&HFp@76f?LMawX z1}N=!E`U-LlsG8uaq6HH0i{GJ?Q~vc*z;N_#Y5>;=QYfp4~0?;lr}r}LMaGJQBZo` z`PW=*Tm%q04?D^4qgN*Oc2XV#Ut2-L=^A4&uiW|Mm4{cWKc#7HQ?ii>)8-*w2cW5A zM1`y#Gh;-s7%TH;MY`+^?fYj7N@p(x=;+?@NgEpJzClRAnz~>y#u+RII*UbxSEMV- zNG_ltNPLTg3lRe%PN2qC_?iZ9G$WlYU&SrcY3dZo;6yr2gK|exr{W4gj^dmu&ID4x{PQby9EyaMotN1g104Neyf0Z=XTN~e{AMqC~E6^ z3K}6?V8m*#PS7@J1S}qFRPN-D!-o9vTl8$(@&J= zif=nd7UBI?VdR8(3u7?Zuvq4~{42sLafy#LWLh$<*c5V^x0WN7_z!X=e=sf}Q3VG4 z4jEPur`CAYVi=iSFnG)(iU(9@&mPITqX4&nuAF?theG}|z*hh@08IcFpzR=}`-&02 z!h-lSGZ7zAhmzIe8S+CxN^r(C#AhX8esmHEDC`rwy#VpkJBvdLW0^B9GQCi*USEj# zTV!=%|FBzt>cJ=0llnqKPzm(j1hAakEHnktHjOq}_ZEp6JEr?^PaBZ=pzb(XJhrn3 zCHe^2JvIUxNZr^p{3p3Gb|>yjo-N`c(%fv~?-vg|flO`9Lj)r*`h9Y^C?ntueB5aeQj}R$sY*x9bE=8`iMmW4_U&ufr7Y00oo^Z5`~6b)7q%5s#CI2_-?Re6oYG zpo6TQ5Yzn|C(Uc?qB$0(Rz&tqFff5S^5uls+z>Y_G})0D0O-2Kq3^6>{sOPJpq1I;x5-M zM}HmFGHb1I^|_#n73o(Om3Jh5{vm42(~%>^y%Q|Z1sT|}Y+Fq|k z=<7*GaT=UJNfRUSYBF%*;Fw}Kb`@!nLO+lOx{vODztoZS6H{>mIW+MJe44~e8ixNy zrcE+IzG6~FT$zV$)d|VgHit@F>*+iIbpjn*NzP4*Vg`6fw>kP4m1wD-8Jnz|2tZFU zoXmkNsKgk;O-=|K;+a^_woO&jnoLqOIVD8rG1lv{C@FE|*~$I!cjUliF6NZSX4mM` zfLn8rA_+1w=!CuV8L^n$oIE5CRD^uZfvkTxCKtt7uiGaVsKiEC16}<@$enA>o`dqgEJCnZy&!ry?NFTf##j6b(%bt-W`**Iky=aWt;Fy{Hr zF>Kp7YzFH3xb+~Ie;#4PSBNsj5ayG1E1gtf@jcRiYEIH|x=yfz9?X9HRK%zMDi*J= zVPX7N#AQ(n~5)rNSnr1p$q7T^Lj$k~`a@?d4XDJt>X-vAF%aCF%m7bXPI*DsiS88NX{p zFkKBS(AUI1EfwD&KTgZRAtY{kLiiu9zZURop!)_XoSug7kY&>iQB5v9P%|hb{a5&& zx&}7i+Rh$_rYB$xIXitsm=m@aZ^wGXsl*W^az+w9O9sv`=!dxV0x|?}Sf>^<-N>L9 z0yqZp>29Rc0v*FS^305}%nXivHe;x|bK|RL=Bsyl?mM0(lV)-u8@xA;tb-NNHf$xU zXAT2i)Xy9oR_N`dmI_-F@y<-kzvxv1|Hd?s-Y!LIV#FePAz@c+~)g;3AvPt3Wftqo0vh|*W)syFE5196MrKUa%{0=P~i%&KFrP%@tZh!zU zRwy~f`e;D?caO%74XPDz9)jpTn2xqiwR(2_U*m!c88MNB%}EIychcX744E?!n@H)L zsOU)L9w@R%)aIDWF~B&R#{vwA(UUjlBr<*UMDG#rRYj@T;^#~bnHk)&=`=>_f`8%{9C3O#T*hqeOxWu%tOKg$unj_hI+yC9m zfcb)7Gb_@k3Y)0DI6s#WuaS9=q=4qy_{a!26Fz@rFs>uYBZi1w-h&q9h=0?AwIWua zMhh7@Hw7Ocv**TO3t2ID2Hr}}%}vEIq+{+A>i2;HD_LOS22Xc^La~4&wUh@T_ec|5 zsv@JX$E`9vYOyugs4(PqM@XFcAu~3@iZdfDwtUoRBMp|Qkfu?|IwWW6%H=9@#bQWl zmS2UQ(|o#m9h`1jIM04Qp>5#7ui02b+i(gJdk{lO>a0C3y#G6Y?=zmNCuZ8YC-Ig; zvQ~>nd!<+Z)kf`WRbgkpkG(-PJZzL{C5S)!ghmK{GGes0E>tL*&x)V9I=`n#2O3Fr zi4DVP|L8RQ1}S~?KJ$r}%%9h%tjTKxt^VTz#PfA{)kaWWC@rt~J9!JN&fimL1ktUp$-=3)DPs`O4z0$%m8LGu=kERLHyjOZu)(bpL3{Z=I^B9Gp zt!jN(TL>6gifeBv-ftkHl7G>Zp3f^(2s7FtKh?-LZ)2M5S|J+4wC+lJq*IR`LU?+KP%Xf#sr+dR@#G6ou}r) zTTp{X;$~#3hl5H6iKqCLQLUrYg#iWNJBV(ts*v@EWWb(;_E40p`w99uNZVtnOoL2f zAI~m2=%s^48$gc&@Qt>7O&u%lRUWt?nz7w=nj%eMtOe<3S$xtBIiM&|-(44Lp;nkz z`s~BE26RU~!9h(RyB?1zo8+W6TAaI6Tm4Ndx6o2jRnltFl~ma_!^x@>4hkwbdwH`Ze~%TD9)VLE*DpjViu9R+ zcN&Eo4wZkCN25Sy$CFg9F&|u(ygiZ7@20x3>?h$04A;^FI$uFi{!91rEDzB zFsW-qJfvE|R;RBw-+LZhTdySeB3CA*2VVH}_NQ#vgtw6)A#?POT&B6WUBBdahjySM z9a56gnIFyfwsOBX*p6#9ezYP{PEmJ{;%6YR_BrSDH&rCmr)R5HHhCssHKN0 zLIc{fWT{HDk=YAlMua5oai1#B67lWw`}s8HEf%H;@r$%jUjP zOX7HKa^eIX*z#8c+>q%7+h zXikRIRu>?|!U8us5y@L*2z)t%vTh?;yeK99AlTKm2Aml`KxaDNf|A=ED7nKyv5z&7 z_ZRgF{3Ig?I?p0!7jX z#H4yV#gX>V_*+9JQBs^_^I}7PT1)5I3!r=@%BH*3oNLP$VQ+^CJtl0dNd^^^A||P| z#VYYj^6lcxNzHCu)^&$31@m)Ybo#GyUYO8RNEDdcDotFWN{9pV2I+Rmx-DMmgxe(0 z=tWeaS32r82t6Sm3HkTknL;?^BOqT*X8bK_%rAOzeMoiiRz^HQKK$DXJd9+N4(1}0F`qyIM#ex2 zz4O=AEFK>qY!KMPD)1RMmL@TZi@aAl2wx{xOQT|baP3`qZ6UYFvIuWwwm@j+l}UvY z#(Jf*B-|DU&QZE8D$MTMyJ!>;o(F^1DK%S7m%*_8{$us)k|XHes|)nta#apw}YuJ_@o!T z-RMW{EX>)yq|=$745N;dn@bjioOBti(WOXaf@Wc~H#nK4IX(g{O9U2zs z>TqP&1&>Ryvf@MJ@=^nsR(RPo{3MyNY*fhavQK*7@3kHvyO$Z%)Hhj3&Mb4_Mq*!{ z0YQ-K%ZEgq2Gwf=kwW&E`srLEh@YPHUy-WvNNV!XigeZ^-Sv?dSHy;`0lNI|4REA_ z*jGg2@5$#YQv7K5)V8g_OqN@kpp?YWZJcd(O9hP(ZW0xR9!A{?(Cu{*+bz+;MXRdK zjP+s@bJ60K1}U|@SI){t?LokOJ=mGYxs*_e#Nl zL3Qzc2vE4C*A?n?KIlX38;vzo=x$V97|3;p_UDx%>!m<^eh?=)kQgQBlBb_fV@9Tu zJ5sJ3s9f-pa zt$S%>I=)QmH$I;7s-G@;d8D!Tp_i&$i|nJM4j|x*zpi1EvvCqT#v!e!5Tr+@CgauG%w+> zFXX-8?MyX(1wub^P|d?Kdz*m^CZ-yRAJ=Z(^ee`5$+Q13VWIZje+*=TegVpU2Dnyx zb4v`%M9Z(d#kuNd>j> zp$`cY1@y{xAy|(L8X2FJC5u9ye0^%raUwUa!X!$lA&grbYf`Q6!TSSqL%8I?rfw|| zDQnXp!x~D!b&E$@4uq@W(^~lS%;R{NVGRvdP<)-N=*xuwmiyi&>%4^tv9IMC8zTjj z9(>ubu#XVkYqU%H*>l~hUx+x<=wClYa7iC{ zPl0=Q%A#r53ZGCFsVu6ZwH9PJ<#!m*`1{xP-jRiIFqyq`M9e|xbsB(TI0r7aOSR?rz401E%8PbQ0_S+wuEqEk33>BdtRq+6oPpcP;I~HLOtRvwC&GUB;+@FE{G?mx zmLzibtrYw`iKt2k3p1yR<4*btK>6+UJ-T`C<^rL|k+>r}auXYuSydudCFHrmfL~jc ziC-bds)leMg7o~^qHc>1o(N;KJ~pxErQ0jPkHfQTY0Ux>zWWO9AZ@#&@Jl3U&p`Y& z8MViNA0hMhOu{x&w-xKl$9;DBPSYdQPI7ns=lz0gA`=sGr zePW@{AP?fQp>95;^gy(D3=o&>uHs!APj|lw6V)aTz zK6={8W|x#q23IEp4EEi0#GA;hYMuHSpIh2S%Bs_GB{@_*1)}VD|J;mDWNM+iz=7<~ z4(|mBy&lm;Tf;=3z_m>TF`FT^MMz=(mAsJy)>=Giw7WGY=y1iBsgll(#S{eMdNYg zhxZaj9Dt5N&~dAxvLX|E`C(w*4F?_?TcPRd47Q#BBPs!umk=RiQ=fVi7Y{!ARg!UF zaNIj!D~^LxfVxS&gbg*w9$R0-nSdvMlC=j4@w4RIfw{~`6X|!5hjVxC!9xkt0U;f> z7*aaa1_xPm{RmJ7PRT&h4w>*WGVM?a&LYPk5Bu=Yn3x3+QLd>CYRdvCcS*|?b)pLH z1H4iW$$38lj2Dey< zayPz5R@BVK@7A`|#No&%{60n%1br20BZve__DUtS_z1>WCaPKve?d}eP2t_0J2v70 zJ1XG9+f9S?7f4BM0^UQ)YUA>LlRI8giz+ov$IS&?hXd*HewEHCJ?C>tGrb(F*+7{U zw00w`=|!0lFc^?7(9hJ+>8DV`>@K-nn-Ve7$F_wcr!>?rnbe({K_ZW)4&E-KwqQ`y zF6pR;#{MA?0{HlPT9f1frOT^o#D>5UY(QK}X&8Sgdgpk=j(V)-57$zMCzzMVU1IH!gcnJ70|wf41e4~tqr>se)o0ooZb zPqtZ+y)SReKTX<>CWZI+!gqCsr?VSEAfE4%QVCZVF)cw>>Ge-D`q-y$I~WK}-U7bU znH~qo1w7exc~(|fTd#s!m|{)?-(z6}PKkXQE(^g6_!0slMuB2QDZtUjM_>#DAM0j^ zeX5{FiiKiZP1@>4g+I99!$r|n8X`PRaz2O*+@#p-F3CYQK^gdLBXdJfF2 zyGL5>sxp-cHwT(jKd#`y3S?=!FAN@6WNJbDob)XO-T4DRV$zh|W#DRyDokB$r*!i} z+FAb8b2VNUIEtx0T;M1upd^>_k)j2u25mp|F}m-icJrOT4(%r?(;ZIJMmW;?ES zN-ujb7#U6}&qD+I_qpqi6gy7P=;4}8GQoXr?^RA|HVLmE#oYCh$@ThaFMvxEQD5A? zd&wS$4(=h`lFMxd#8aHF%5${Hkd(G}e)I(%WNf$kr zMC$C?{FhhW4vb4`#;>fi!B4#4;@+@~8v=@ebPSXas@j%8=?UN1<5$Fh6`iGl-J04`X zk&Hh%48Kb@p3Ivz$-`EwUhzu1e0l+H<*Gf>1to9?9-tNQD;}vGwB9y57Vr*DwO4w= zr`nMwXrRw$@HU3M6u4teE^e;iE;_O--D+$NR0GiKfbR&`U`XEw_8rxbe?Zuo23a+A z8arATT|XXFyetKHFh}LyD_uE>8h;~88Y0#0ZjUsUyws2Y7R>$zQ_PqK#HRpID+^o$ z2smu^Q7dy9x!dqCwQ@d+0oP!`M~}0zRNx}bA5Dyur9{{Lg+-(9mq1_(4qP6VX9XG9 zSb|5B%0?4-9H$yHW8eG`r{NYP`aYyVK_oW0DJe)Cev)XLdO|E9r70;Po!T{*m?EtI z-7yVLi8&*Z;gVQ0&SJshbyCul*K@C%nhNTc4A6z0kBfp&lH*P0jAnS|)}Sa-IizO* zwkjGh(%O|kf6S5*w}TmsbPUe|C<^B9khG5n;~AvnV?)`=@u>I7;&NeY%@vug9ck

      E004=1vj6SQMsK)!v>#~HJ0r{q76exJY1%& zZ1W`<@yLY4)oT!3FAh}#wgiCU6)#~O7XMHJc5=g#Out;fd*D5lIO!8q#y|cE;^&@1 z{PvIkf{L#4z|)9Ve~S1*fVTh)pMiS|X&b+AH!h0f?D}^ZA zO&=Z2sIE9z&RXy%{60}|AAT1Vh>rN)yuc2^V!Fa|nk|}YMf%#;w_kh9O$YAHj0EJ3 ze&ntS^-g*}t1_9z_6lr(cW=RrZX>W0i&J4ykNYNqHvAQCOsyaK>k$@b66KSqGQ$P+ zPL!NST|OC^)dZHsjCaPZjH}Nt!aL$tM%Z%h^-wXKrW$Z+4#_%rK(o#VJG1u(j)|ZL zg4=K~BMxzW3i=I;EgvP8dpl*_n0XFQZ=pm{C%;K9B)@Q$%#NFJQFbpIb#mZy4Qs^wC@pn*ot6lvx_p zNC#!KYAf@KBE|baP_`js)4eAu0=D5ns_hK<^;E*_r@$t_;ws-Pc)PhF*DP{C*FPO} zNy7Y?3o20W8X>P09$IUV)=DwhWp71hTOpreAHH~FLKVL@)l8=vVR=+XFD!juD`lGT@t7M-;-Jh=a(>;`JcF9&hbL0223 zH$cQd^N-V6ebPhpby}tYp3S00S|3r@eVhUOjP4h^73Fc!&|?kh|9Rx-)!?j!wFP3G z6^q-P*!X+PE;$h0bl2G?b;zh`j0T@Wk$!WL4WH}bkU8)< zH@?id2*TDzK&E!{f(962gIH$2kBZx`W~s+tf?aks>jIpUlypk=EkH-FuO5*7qx=`y zw@Azvrh&8v^&f?3VEu}q;-k5m7P$fIIUySevbeC3ZN?)|dPfV+66r2p;d0y}tG+O# zu7zF63Vq?~+#{`$S$M6hWTmuXF~)b#LEXn?aF--WJ;|vr#xVMRB>2pl$irT+*}5Lq zG|O8oHE`tSlHF%Yne=|7$Cul1EIIIHKD=7E|K)f*lH{B%?LOzEEnjDkfeX-b@Mx!z z#@r16{9hP+L`CHrO&-$!6#mNk0B+M##6W zX=8L3%wU&Q5W~6I*i6dKMF!B(2`#ld&S^0#Nl`BH{@3wXOU{11m^tIE9s18cIF5G7 zu9NNStat2J?V5!;FcV1$o!}r+)|`Z2CT}&TB+_1;cO?>pZ6qng|LjVU&VrP{46ikR zh2JEHTZTo9a#nx_RwRdKHLMmL)1uff+1GI{+Q9x_2P`SP2u*gxUT5ZUo^fN=nP z-TIpK){wDU?lt*Y9?m7;;9wW^)n5f4&n4yf)NNHr2HsJRVvdjc_#^s}fBX;&cG3PH ziX%S-B=h=Xz8ca)0I0y0f1x()!V5U^Hz?ZRt}~Ll;q@aS+zWFi`+poZqa9k3;Nn-c zpIVGhfn^wUNwp2{h_2rN?EO<(1{Nv3-DGRD4YV(f7dX1&1up5N(kYYl+FZEYP4(?6ZVcnTTw^Re_CK;P}?({+J|@cwBs`viK;1LDRe z23(>J0p6xaFaC>FLrB_{8DSG)1f6y$EbdCO`3k3b-xF5QAsz6L53UUAzZ{xv`N|yx zH`(EWrVcm>Q8N~zi`2yJkPP5uYT-`XmJc2(yj_cH%?y3rT@r)0=!6al{vBafYu1FC zj`Gq?@U#G4c1)R>ry9L27p!F+3}`b?X89ggJfNc)6bXC?Y9^u%urS5fPpl18xBON9 z=7fI)j3P%{Co&#H0yuipBD!oX{I;6W}sAr2vU0ms&`MG?n0MnT3D&Xpc0Z2lVKW z`wHEQGA)>kg!`yxd<;ary%M!vXkcZi;*~DIBhZ|C8?tcfC$P>N;E{AW3Nwe|Gv+&F z^)*8PJXz!y^e69J>oy1v-m_Ee%(L+Zl6W(knVCR_-t5zDW&-Am+t)2sz~gq;lchI# z9ACTlW*lbz^pU1t%ujYmUwP|tRf4KbtGf5&LbxTCB*~3-egOt9hTmkq(H{Ui3G6-& z@1{<}G`2uW-=fb2f(J6mI+{+xo$0==G^nfoW>+~J(n@=OTwK}IADjPI{$v~xuche= z5kg}DiU7s|j0Y$Nml`|#NtG(Ls3;x&;vC^n=wuQ z<1eNvrZPPq$Ef0};wp0>Gc2Ggz~3Y0|D(62O4HTG{0A0V2(AjQTpf?2SrkzfQMnaz zp(vp$fi{@|7vb3G%7%E{lklvjvgJYMW;~9dHOJ(5{3H$=0`J@@&{1iXOA@gugT}=u z-87=2{alQO1(4+!lvRduBSfG85mfl#KY2FekT26wdw zL7Das=_-eIrC~HZ_M;BJgmF{l0zK}ZQ!)?nBNhNa$^k4XLHwul5x);!;a5QYA;@2a zJdE`JeGd5p0Cs>{fQDn|^?0Xh#Db?FDDe#ZN6ORiUn&420Hy)ZK@YD&{Ay^+fwVus zFn~0G-768_0`=-+hkD~5R2k#nK>Q?t&M$#LbmgTtVaz_jw+qHpb+%92i}=qg>-ylm zkBzrIuHF0KE?zpEi`eh94$3LF+*r2SEd5>le98kG89cK(* zavuKM;5)$k4dRQx0@?vO&LaLbutV$swE+9R2bcfrPQ(kk(zbK(L5}SibPPIEVvijI zODF>4la+9IHU6*Me*Zg_!vCO36K1>VE2Fza0XSV5#^b^4a(Hb@wz5XtUb%$F!*CR^ zKBBUT$86;npl|WICFqGUO^$N<+pkI0;Wb@1d;roaEJ%*nu(V*f=Utd)rPaunE9 z)uvO`cC0KL4E{sJh46a#CnR~L{Vx-r9`bsXx{zWhl<}6%7ulV!&_dxvs;tSt(SuHc zqK-!#ibpzx>4Ot%bUv-4arjHt*^8p{QRBarp_P^^eHpk{EUnibWyd93Z&>Fqd|QC) z^dd`Vd%pp=*Q~$B?ff5jF8$AP7v2Zoy|nPbcOT$SUi2UM-yDDkMN|9;{^;S7kq6N& KNUygd{{H~C;%giL delta 15380 zcmd^mdt6l2_W0iCoPj|=1`&C~oEgwTL=S?B?-BF>qT(|(wZ^m>Gy_equWNvhwA7+@ zhDxPrU9qwliF8uJu06D}pscHs`EE2H9TYrgp69prfVaN)_xF1-l@1F_O)hqi}J} zj>!raoD1;R+)@YD@F#gcKc1QaK$lo4Vtl$TZWMC_xFx$5Oigx3{9nZ@8{CV=1NX zhH0)QY@iz%7=9{LN~4g}kId{l04I}|`mT=n&DGb6^lZ1Z5BR+Kv zg8IBR6!Da2$Pda#(pGg)q0Uewp-Ise_%%Ol$r`&8a-)|Z zsnJPO+EyeTGb8DcQ!jSZlmm-u{iU2GMQ!CglJ+}`>g3G*3=`oadj^hXBrmx>@E^?U zUQ#*8LdIoRl}!psEv@IoqTeSzbnG5y=FS(j?OL1wBt&=<3bA2|!cSalUT8J`&aewD zF@;bThSnv_K9HV##w4opLAAS7o*Ug5An8~xHCNKGtR=YVbYrksm=u=(b7Q!Ocw{jD zz7DDKIj>1Xl0&IA1)Ndk_tduzHe63Eg&EvBTp~rH(gxHx>n;*>ZAcgmU^RC&6U*S_ z&^OfE2RGac-&ES5%2nj$!3oT}9#T8FHx^0DU>+9|@8ERiDG%v0WGo|k$ciBom_!db zF(kjQ)6En{&(=0%MPgw*Kz6-G3=uQ*EU(ICzJkIxa=0@^ZCe)S!F;c{>qZQnjhSpO zd3~5EWU#xa?bXFBG{m||(=dIA5h^PE6`Y%RhUvpYp<;`_;*M)_4=e-{JUoJ!hlhl; zyNcR2E#_eC&n_}!xGAK?Wxg92PAiVO$d=*BU5>kaJjMNvi+nOXk=f>|J2!kSo?q`a zh{gg|56kFIvl>Lcz$lgFa{650F_rLl+?-yO-&GA_d;tT!-hlqG1sce0hg?iS0OSbd zq6)e~?nTJ;CC_tBayHlU=6?|fRvG> zt2voj>m*rby>78HO*D)}`s4!i8j=<`$$Ybcnc*ax%!z&Tok-txY>xsY7fP{EGD2yy@;H>Dpu|IIy`qOw1e6k?v_`qaa6jpw6c44pDVH(#QwWq| zpj4vlg;EfdqM&3|{+vfC9|7|igB7wWXGN4&$p)F#-bNQeZ|WOku%NA{TWrjj>63$` zk5s{|%5GOkpZm=yoofluH(W1;n$HhYNk>S<+WIciJ4zR6pHd{Lf+}B7NALmpLDCo% zNnr|-A{7i$LiM34XB;7S#`K8Ia3Q_6LA|A|XZd`Pg;W>Ir$L(HB8g)Em_f=Ae$?GO z#7O=9xgtbIGg2BU7I}P~Y!=6K$xg(=Nf8ODJIOh5Y)lapb@kmvtr#vc(m%XM2)a;(jKxpFD9bI#~Cv% znO2+@d|t4YBUai%_T>$NO?n~E$nR14!XtLRFxUo%jYscKXTT9Q(8EXpUX2t)jQNAc zJfV6(DMoio)*lAg1eC4J1BC$j697#B9|3$0umaj@Aw6G&gaZ~N;F(B>s7J{f=?k(e zKc!3kB_y1NK35aTclo`0Hs>SZzQ2ft8>Ujf8t8ro*7dm#`HZovvcpXh3k;fu0wmlb zV+#6(-U9p&zS}@53XDNG2@8Dyx|0J1X+gA2t4r38B$o=tgbneu0__j#j*8gt8s6VTgXTBa&w7y&b_w~rL{H<7EQ1k z?~~<)83DyGI$;9&pl}FYNNyC)!#o*3E-jQ!e-$)Qc6>xOjLS>--mS_dJ`F4jE8T+!&XXaNTDXH!54qoYdkIB-^G2iIXS75?hfC5T|t{%9#zJr^L z^f74}KR08!PjOHdY=d@AL*}L<4oU@N(FEfo`=GZ{ zA0TRN8?8yU4SctJRUQwz_LWjr3UYJeF&mPCJeoxA9G&NNmq}C_xYj=CBa22_30Q$P z4>k-Ixz;XdIP@6oyX`2Ef;IHK{UnLpnUKgp(zR$rw>*FEvGB`E)voJ~?~}+QMX}74 zB(kcgCr0G0qKF_>{^wyT2o0p6C^c%T>zWm%|ItiwH(bv)BPs1LYD^&BqCqj^;pA22 z1uDhX3$`iM4SsPY<0tmQN64~?3-JkZY2r})6iJwr2Kj>xemD!Y1?{ZGzzDPSdm9GH|6^@x3TY_fhT06o-jG7kd7N>Sv-q=e8xo{4s@ zb*hHeWRQr-DZz;zlU<)hDT^Vwll$Qx$TO4qn9n?=HmxBQI5iu2WyXn&dU5Z3MjB5J zOdh<@D_>A9JCOAc$K=8|>lNGNd{$}z{_E`%A$J&Z<~llBpWv0hraE#%$La^P>cK9% zeUO!wxaqNd%mHm1JK9F&t5Cla#%_cbWcsyPr)Q;oWYUyryjL!xSUPtk*E$ZHfnJl_ z0P=kQAR|?hucjD7z49ETgH9~f5P8a|q#3{`x(y%jW5ZM=q~DN=Hq>%3{%bOQYDSdJ zg{xT$Q$26JrWSU?OA|%*6;`@Qc1?}K?~y}O$KZbu@6>*yV`u4&a{&YtaRJ;=W0F; zG_EJ%52fPY$VFTh>X(&1WP!c{#ybl=-1K@~9#sD7cHBvt}G8)7Ho`HO-8|igG z_b+;qGkq*0>&c7LhiE!<#;NIfnjM~djyMuCgAabrd-WilkFFtujF~YM=aY&VgF^GX z9kZYkX(3 zhzY%(fkP!L16Jb^<^9fHd&sPrNx237QA)%2{B78s!$6ux1B?TBu$n9Q|EXKp0?;Ag zEp$){V@Siy5Ahwc=;5@yJ1Qr>05iCtJhgkaP1_m`a@cDrBYmJgZh6MK*HUM_V%h7M z2sGaDaAKtmR%`R~bOl={vU+inh)MS>Myetg9!`ol0=PCq+bO>Ws{|^Bk?>gqv}2WI z>s`m&Jee@7|L|36tvwVDXdN7}OB(@QrvePjzX}4oP^Cng?9uSSRUWMk8`))Wwt}eo zCrKJ+MKSRz`CyVEh>^w~?Wn}F2MDPu(pxMK_#Q1rh&LRXd`5~;?}8?aM6HfTc_!Z{ zmwM&{r|dj=Vs;|)HBX+KEd)D#F5sjC=zW!ZHajWQV(uA0}(&@VF=0HD@l~OYkF65x@Agvnqd~a*3LA^K%&KB1wBB1@_6L zM~34@^3o%Na2@&T5o1KP_kD|c(7&s}&XFom<9y zW7h3?H-X0aWcZ`gaR%A;XfGT^8XjG!nE*6AMba(&%=K>2D;Ds+mIxr#9{KNXw$LQ* zakIw9ETs)gVb3n)P7jO8^(>`PwGsRfJQ(P9=X>dJVnk#`{l04U)e1 z>|Qv-#y^EC4=6ev9_^KX_;=f99)rjhboBem8&oU6K6#!@nj4|}+{LwShf_ia)?3o2 z>Mc?_w-i^COLM2;?PSnn_n3=5(q~@pvR~nZ&TinJK!Q+@S8fKag;GZ~omMJgjaD_E zR$hm6DU^5XP^wvawcHH;Ad&{VKUa1`%d)0zDL%Kyceh)EQm2Udu_sSuS)Sp(?gT$M2 z4z{8quJQOiGrLuZfS&7UPsn!{Jn|Ozyprl-qg0wpX3W>kT-y{3oC7ZEY<4<7{4$b` zyYP9r1vd#v>$4E zc&-lI2L%j%gWY`JhkF6Kw~6ENIgjr~s$8c=Lf|B@=}Jiiq-+zl7=BQ(F_j7U>2gUo zhW&}w5U9Z;a1% z7jxW6et04~YLAx=z6#Z60EEWUJZ(J(>X&~qrtB9bpfJ!7rjNBy2gWP^a&%Y!Fx34b zy7>5$;1NLjSA&y-LxGX4SdB}LhVw}4-u9O9N++)S0Tj12j4aF!$mA_JP zwMo3@Aiq4B4dz^=H8Ze37^hx&DJilh;TK7XHKpu#m`M@}G{@@zAk~Sb^}y)672p7S z{O)UoI6! ztMXnr4nWWvDej9fBh2^Em)3jb50#9uh|kE6uo|VG*<7g`8=(cAId=&wSxH=R%T^jPptGomL%T3(*37r}}IjCv)0CMzW?ALX<+cPoVU{<`E?3mxs1_q+9d zoXu3bmcqjAIf8%7URoyAex(Aw*AuR>lKNc49h!YWZfiduf z49dC0r)HGg=0M5q4vPJE19^HukHChEAn5!M*}Q;fpz4DK ziAm0k6;RdRyUqd!^rj9wbSdC3a4vide9sb}h;b`N6Hvy5e{<1q&Vn`E?Q8*0|F| z8o-Du@X8;%jbeAmM?${VohgPxJ_7RZy5G+UJX149b9NLs0S(ucTve`V94ZEl4S^7e zSKjHix1z9sCRlDzjt#C+qBi!X1NyDYHe%r{d@K*rhXED=lmmeIoLfx~BC_V`Abgl? ze0mukPP|VK;_IQcfdY)Ocl69#U%P00fVfHIJ_MteOe;xZu$%m?WFWpq4wOX2oOSIj zzFf>Nuq?nYGnEjtd1X?;gt1=v6ggiKm(u7ut!xq=v;J|fdj;6oFQZq)f>F>~=i0kq zBup?DCU}4(lor9-EGkVO__Pc0srj7rqKlPALy#<646chTjIs6?bHzaEk^=so+hmP~ zP(z$G&ibAm=>w%-ousL>Z`qf2YUt1?!gZkj9#G#i84K@2ek!DE0crt$1qg*Ytu|So z45X#m)f-zL$$?JS+_b$CA?U$EOE= z9b8NvTQVdx+|};LuJ1A~#mY(3$^Ioqu)|I*nT8h-<1-_JCB-M#`aRnHWYIH54J9&& zY<{sYKyos1FYU#;1$8N+4K3}e2;vFkYy?U zZ|BrCEW?Zr&U$5T3{?l&W{>>bVe;K_J?D{^Ds^|4&&PNonZ7awUm-w1Q1DheDs{_dFPZUdf2OCmZp*VDW5(biqs!mUm{fs;0c(*k57LF5 z>0U^`>4cvkZ3j4C-U0jSVk(+3evaH+J5x*CSnrlSPBL!Y0&R_JI}{H1$fxTJnk~Sc zQgUrw5))ZQ0@e>?7Wv4C^(JPtk670yGqpX*i|ap+QdGo8i+kGlEG=r=vm`-e+xPqp zOL?StLqDdzC)v57ckoaTGKIC6Kn-6e-*1R1JODujhXd=cfmuUYe+oXNtq%an8fy2- zA<&yW_W^_o-ST#oI;ju((9nR^8X|_7*fRt8FlgUIGM^jF{MwT|{oD*Zf_(LyjZu1% zRU1d(FNl5PF5HF8+_VArCl@x&#ffCp^O1Cco=?XY$cE>iOv&m+zl)_W6s@hh0AI@Y zI7VkD>jUd?C6>Na@ODPpRTut35N4WStu`B?81JbYh{4i0<@^nVcjvif)q@(xlWCh5 zM}6wau;IZ>YF1;3v;l)-gSDcz;W2W4^E`ZjjM@^18|&t5xqS)3)J?FFJ! zep5lMLdZ;UqKIDEA$Bn!qgKJ+IOSIqGVHafK{HHPs07S9vg0*7%zH}J@U*A>yjA6N zC$gGzv<=y?b)xMf;WT&2r+m~6&l2GHgOj_39I48P+6_25`aI5ehd%H4vIMt0fUw&K zl*Ixrd`^|mDkjhjCf@~EP1>JYd3wjGMJ#y10+IqypcQdg;E8vP;iz+X2QYoOi1GN8P8Y8CL982G-8u5yCdrr4*OAf!sygdxDI+ zERJ}$9)%gq(6q=LSrHO1u8?hDvSK6@()zeLWy zH2{KqVS9}DF_O7w5?)F+>`9&X5CldM&$XJ6PoCJB?+*E~9%RUdFko~*I7ntLlmxg9 z@W~@O`@}+@Y!BkIq3#Jt>B;t(#|YL&2X8uVXAi-mzfQvUCc!mu2K;8!P1;+9!yotT zU6E#^G82vVf=Zr4oNrGGPxKg9;Ix3VAT6Z=kl&|n);kGIki+-EigK`7_L7Qy5n&a+ z5~&AL8m22fkylc9N;Z_9)Us|x{mtWHap&A}1ev?v7#ro%Lp-`f(sK79 zR?~%(;aAJG(NDd(KU#Cb>z02bNA{J{**RQ|?8a@2BAil5$`!T*YrZkVg06fiW>pLTI?QE~qsNq}(O1 zP&J7xg!#R4E(!l20)ItPKA3_HWaS4d;m+jV2ZQ0HO8;;J9sA)>JeB)mb#b|Ol=jUUiPhkA+?3C^J0P^SpVd3%wLTZD zArEUdK;cB4%>+lzuL>h#umoLl34GWs3o13swvq#NDG@n7t~CTX|#q|VYza;>h{ zpf}){>H><|B_HM{+;n=d5;T zLodb?ZO8j*?Tc=zfABeEx(m*{ORn%xEO#L&{GH=%SQomJhVdF$k*UfttIoF0x;Y0m zgVwVuj^ohIfQ_-;ifny^(!3MovyYO(GrjO#y>WSVLofv9U2+;}{U~A@udoKga>fw5 z{HB9}fa7)GJDurKfXjdQ8NURZy&s9W6Rhy+!P3&!ZJQIUyctob;N6?)?5BG3n}C zW#C9lET#^$Q@(M8ww6c?Jdjubb9xo7F*PuAp#x*{G2nr})z68!hZC@slpT)Cd&u{v zyBlbwD>cZOZGP0XNye2;HeBPBi3fw-;gs_r7_PP7#&0QXCnBHiYF-$5~$?@kG?a0I}F-C#EDu*XGGww1%=(APVM(#Y;e0I*K% znYb76+LJ=7pzRZYYXHe4^^;z+sy^*z_sH=+(?zB=N|PdmY2M9Y&(7zc0@g0_z6F+! zN8aI`u5iQ72IAAD@UmdAm=CtkQ>xa!n7`?mu4vz%HYVf@_XCZ0(3S=2Fn{_kdGC{b zz{Dv>R!&Ou(v}|Hqd6nnia&g}Rm%(pmfe>h_sn(VSQ!a35xKdRTMpWbg{@E1M!5e# zrjc!vJ{&C45%=W@9{TNg5bH-t!qK7laWeC0?zCwhu7-WZ3xZ$};SR3GBcD?PcjEp! z5x?S*?}H-TZo?wpsjczK3w`X)R8b3kPN>MlwFK^5n}eGw_;ZddOV`@c2C5Wj+#=TeG>Z69|GSbj62aKJ#Ph-F(81U(n+?1f8H^V!aBQ)AagVK}~B)N`| zi;dm!YSP}AlyDO^;r$i{o*&(DOoKCL_V8qgt!l?vELeJrWE{)wKG#jH2TgN^Kj1;% z5S=(eHXSo(yr^PnwW`YHkZuGhQng^W9aIDT!AM5R1(RV+xvd2A5IB;zw< z*}LOW&v%Q;#jUj$l%oenl=fM*a8=E!(Z93F+-swMN29Mp9?i!Rui~o15K+NR-zcbj z7Y%<6`bN=Oc8H0kSdXP6DsAPOS`;LpG$f5!i}b2IMAcMkKo?6bw9gJzQ_T<6rTumW z@0qL^r7{0RWx}j~BH=i|$J9cBBFHE-EJ(y2iCv?IPC!?96Y#(|8~ z>O2XG2}^H+u$m=H1()@Wqd!o!%*VjwH&%3$*Z{M%uEM%1JSJ^b?(fK0Lw|Fx)8BbJ za?sSf%PJ1GmzSZtiz_ZD@9&-@zLukFJ^?5e_$T&6MNdG{bM!|!u;~3Gn<<;L>}Ut& zG5ZShvMQT>u*}<$>Db+g6`Jip)DD*5&l5)G!Xb|((f2UC(%h6|mI8pd@BJ*x@MBJ| zKs{^4+>5AD0^^NJ{ZxRr)3MM7WrfW7JcbRd+DcY_J_rXA+vkJI0&7kw@#U&~-b<;_ zvG(66ThDp}EA5WJ_fXHB;(R?rRQW?MrRKA8prxAY%PKhdZgXHY<8M0zZD7roGu6>B z_6u)@7+5(Gt`6$Fp5Ok8W2+y>uD{|a`!|wpek3mglARFU+*+&rwG6PH^R++ zBF*fRzfmdqJB(P-gr!RF0~uQFZ!c%3``e#_c574M{_e0-)`O|d@d1?qAZb>L57PP2 zyDYb@{2B9a^8wvR=sv0C%Y%u1C!C?^$3wZGDGfIM6faZR8`2_g>R6_liTN z+H5K?=4a$GFJoz#mxuO|US`K8(DCa&0P%{T;?*Hqg7?I=j{RfwqPo@bq0LnM0&5ul zK#^be^j=E9W^btfSpk*$I5sXVxOp&mMrb0ILTP*o(lGDFoJ&nj4j7*KCwlA!w}@0- zn+;1%q%RF+mG002y#-5?-64g@M&Ev_{e#En^3m4b7N2|@TtH2W$)dN?V47RL{b_as zHL#b0egx-5D24PoNDHXnaeAvyu7;PQYNpXby>VI}Q6DzW2=;&2xvqs2r%(PIFtX>M zm%!BO8iMqNdP}s`Eq?}HRcLD<)?2Z(-HA2sC2D|4Avi#Jn z_~(@S2cHA;&i_VhBiwUp=sO6C?POEkol`o@x63i^dk%Vx{8;{~@^`opyXEkuac9l< z!^5A189qdkzF))y`|4i&zBe99M`qV6w)NIqwo5i`u^y~7GM94V?=GOM^KFXF*+qzG zeL5_pX|tWJ;93u3xBMfy*OZb-$9LRb$Pj9gh}l zASX{hj&G2DKMkkL@$^q^Oq`3%|2ZpYiBKS zYFJDwEWv6Q^{-zAzsx0X@M&6iBSoGA&&gc!ZXfl_>G)E(P325!XXp_b$+HPbC~`c= zokxD3c>h%tIleCzZUP7Z0{~EdX`ZES?wO4^atRbm;qEb#I@IWk8 zr*rl(d>0t?CVA;xO4#QAfqNA>evVH*ss1^FMua_ZGYro;Aimt;se0uAg=kxnN7$9! zIUy~~>+$vp;H2M|^So^JEZbw&hatE&&tkL$Y}bM_brtRyv_KkH9c-V&|L%Cqy3=yU zv7;|p&|=Dp_j+X=bZ7(b8^c2t)VKpEqJ9|lBcts@{4)&lX3^-e-&?BfOTKI|GubN9 z{u0lms-)*Hld(!x{xS*wT=&f{r!d|@cKmuM{UqS&`qA?Gzyo;yG=*D;wt3`KFP9k5 zLJfGlU6o(xP3_XZfp7z^BZk08c-JOA{G{$=XYOXY6l4G?wcqN1^6&wAPGGSY(XrMd7%PJL&sy*My`1B^#YIhv1Xuz}moCu0T`R#mcl@d@Le2*wT2f z=p~;c1m1CT$fXH0g{7Sd8r$8-LX;$D^;jFTdP;7<*dJ%0v=F$dh=ix!)Z>msH1?px zlkcwe?yAINp{Q;B5*2*nIiHY#-vm6YZqRRWn3=7TsSb0Gd-5G$eGV(KtvdGZ*Rn3VwErZ5zD01rR zYyOhfKpBdNJ~gB5S3Aq652YvJBY0BrG;nO7o~CSP8UP)~Lpc!2G}S`65YjH4?UX;X ze{g3xq%#er=^^-^k3;z)T<@4~U{3N8#`ACR_ zIvDByQ=$F}zzu+#0PTkc7~yT{@Ew1HSEs9yFnl=@#se${cpiWbdU+)hY^&fKkj?`r z0hj~u(+VVLV9ek{p}p|G*o-x=BcTGo{~`F<(3$VG3$7{OLBfVNkkGulqkY3(B*;~f zX?SmBY8|+ZHt?#{9hUGD68O{5;RhtRzd=Ghz*_*L;GCTU z@F>8fpOG-;yAA~5o#`8=;Ge&Eu6xit=u9!sJM>Op9D(uZDtkZN7>X2M8C^0JV18Ao z84u!Cz!N<3GH1fCRxLK;p>&~9RF%z)BX|}5{JkNi)qnk?^)sq2nemt?pVFn!2qE?n z3NKe;&X6=f0iUCuBp(`uf=wwF(ew!*9WW-fC_ vj Date: Thu, 23 May 2024 09:16:58 -0700 Subject: [PATCH 269/652] bootloader/common/bl.c:Fixed Wrong vec_base caculation - only effects imxrt --- platforms/nuttx/src/bootloader/common/bl.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 1b86adbde350..28b8485a12aa 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -306,7 +306,7 @@ void jump_to_app() { const uint32_t *app_base = (const uint32_t *)APP_LOAD_ADDRESS; - const uint32_t *vec_base = (const uint32_t *)app_base + APP_VECTOR_OFFSET; + const uint32_t *vec_base = (const uint32_t *)((const uint32_t)app_base + APP_VECTOR_OFFSET); /* * We refuse to program the first word of the app until the upload is marked From 3beb57aae1d660d1b211348c4ec52e0b92314fe4 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Sat, 25 May 2024 00:59:09 -0700 Subject: [PATCH 270/652] px4_fmu-v6xrt & bootloader:Bootloader enusres that ITCM memory is writable before jump to APP --- .../fmu-v6xrt/nuttx-config/bootloader/defconfig | 1 + boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig | 1 + platforms/nuttx/NuttX/nuttx | 2 +- .../nuttx/src/bootloader/nxp/imxrt_common/main.c | 16 ++++++++++++++++ 4 files changed, 19 insertions(+), 1 deletion(-) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/bootloader/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/bootloader/defconfig index 8ed0ed82d4c0..6495d6ba6226 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/bootloader/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/bootloader/defconfig @@ -28,6 +28,7 @@ CONFIG_ARMV7M_ITCM=y CONFIG_ARMV7M_MEMCPY=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARM_MPU=y +CONFIG_ARM_MPU_RESET=y CONFIG_BOARDCTL=y CONFIG_BOARDCTL_RESET=y CONFIG_BOARD_ASSERT_RESET_VALUE=0 diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index e541c5effe90..ff0a42fdfdec 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -29,6 +29,7 @@ CONFIG_ARMV7M_ITCM=y CONFIG_ARMV7M_MEMCPY=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARM_MPU=y +CONFIG_ARM_MPU_RESET=y CONFIG_BOARDCTL_RESET=y CONFIG_BOARD_ASSERT_RESET_VALUE=0 CONFIG_BOARD_BOOTLOADER_FIXUP=y diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 0f401a606265..6fbb26eb5219 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 0f401a6062653795b6355c420ea8b0e72578c204 +Subproject commit 6fbb26eb521999844f099ac93974fdc7ccca6016 diff --git a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c index 8a4603414ee2..dcdc50a91168 100644 --- a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c +++ b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c @@ -16,6 +16,7 @@ #include "imxrt_clockconfig.h" #include +#include #include #include @@ -581,6 +582,21 @@ led_toggle(unsigned led) void arch_do_jump(const uint32_t *app_base) { + /* The MPU configuration after booting has ITCM set to MPU_RASR_AP_RORO + * We add this overlaping region to allow the Application to copy code into + * the ITCM when it is booted. With CONFIG_ARM_MPU_RESET defined. The mpu + * init will clear any added regions (after the copy) + */ + + mpu_configure_region(IMXRT_ITCM_BASE, 256 * 1024, + /* Instruction access Enabled */ + MPU_RASR_AP_RWRW | /* P:RW U:RW */ + MPU_RASR_TEX_NOR /* Normal */ + /* Not Cacheable */ + /* Not Bufferable */ + /* Not Shareable */ + /* No Subregion disable */ + ); /* extract the stack and entrypoint from the app vector table and go */ uint32_t stacktop = app_base[APP_VECTOR_OFFSET_WORDS]; From f655d1be9b939fd652acfa32d533d17fc219b203 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Sat, 25 May 2024 00:59:56 -0700 Subject: [PATCH 271/652] Update px4_fmu-v6xrt Bootloader --- .../extras/px4_fmu-v6xrt_bootloader.bin | Bin 82728 -> 82728 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/boards/px4/fmu-v6xrt/extras/px4_fmu-v6xrt_bootloader.bin b/boards/px4/fmu-v6xrt/extras/px4_fmu-v6xrt_bootloader.bin index 13ee91a2b2e4749ed04b6551972e3cbd4b8b3833..a90fd47f8003c8a6d935f5497c53fd7e23e6cef9 100755 GIT binary patch delta 4563 zcmeHJdstLu8vouiGt2<843YsNa1J8^l5lYHLPl{tKzPmEykrfcHKYdU<|Q)*Z`ry& znxCeKZK#i%KCLC5B_tyvucU^Umvn4_OeQzY!_6}=Gn{<~rrnBw>E8_F zA%iv>q5@oYA~h-?RoOvmurpGXIAnOTS`AX@G5W`tH-lcbdu4-^-~Vs2YqD#9(xrej zN4yi0r}5_LnbHy32Y+}4_n+YFf7TXG*U>LE&-z-zFF@c$`?&T;05hd^#*jV7Ar_j5 zfCVR23p^T5jFLgX*D8RLhuFC-6V^;NowCKE`l zH1W%HZm+|z0^&4Hi9!sXM-j&BK6hVzx3|9P(TN7S<4fb?-(WpEt|+nv`3z! zZG#bROFg~v)%w5I#HY5YLZaZ)4nB;OOBbIAg6VYqiB!m@XHG<86~BKX2mEQ$ z$!a{D_LC8?nFgE+g&lO%si0Bsy6kPbkI0DK!hDvYioDQ8V!rJ7%mQPXa&^4Q4!#{t zx^kx9wv-m1GL#g!+$&B|<+ZujF&q7fL@glIyVRU+tL~s8&+PZGsHXONO_PHgZBv&FK!BIb5gno!bLj+U6wUs$qUjsU3q= zx`PaN*v?`>y+!w)PKJ}T`Lr=%s>3gb#k={eV^A)s3^rlO9ql_QoeMUPH1)}c@iuF$ zF(%eLP&q!Lsb?Z!4$V8m1+7Dy>V~^SGe`8b-npzP*zAx?XxW)jLvDQbBi_gG+@dNH zqpJ%RHXc#ryVQEd00LFca9E?cvqSJ3IqqyMSZUtb88DAlpG}Hh-$!E9!eck)r#aviv9wYG{B;+S(8Z8De*XH^4Bee4Pd5H0#_XNTEB< z6-K@Ic~KTy8B$3&i`gYVkCMJ>t9=Ep7Cv(8>?`yxc_NKHp9!(F@VpVG(*5U?fznnS z2hkxHp7*`dJ0p|*E=6$2Yw7X}b3)VX4~}l=4A|&?ZKbyhC4bF5{KSrm2Y!}#??NCz z2!+Nl7)&D?7sEMmb7LlO<9qLS2CTOj)?!>`j}IT%{+j=wi<@dxrRw%$;E>;?ofpS| zAB}Cgj#W{0X+mIXPpOR+6xrrn?aAIlr(N0!QS{CwBlyy=ZyRAhz4t8#+o=ELQgyf7 zr_k+}ABSYxaCrfIC?;Gn0)GDTua5C1Nn72>qc0}7s|j{vVy)=xvQ@V zuF2$l&^nuLxnYDS=!qMg;qBk}jIYw*vMLmHINm;-evDm>@@cBIMn$i*SELQHGJA&A zOy+zshsvcYpHn%{JljMJ`6h$OYnQIFSKddbTc6f^=XA*z=}s$$oj{Fs5;i#6n_*a1 zqHa!yTDtP)G}tblyLka%1}*#NxsW?fb-0&xB-RwzrO1DFPmfozSDrvuH|N6}w6&Sj z9&!3*cgu&VcS}y#Y$u6Sb4-6j*)3~7BX#-~(o&RFltrYgw6MkKd(e>=0$W+3Tc-4I zOF=-zXKS^ZCeofVm2?xHNH=M8>pNhim8}tApiQk2&m}o65|H|%?n19i>6U#z*Wi5d z9xapIiMPT+{8B7r4Yqb_VTzQtWJ;HXBW$-^+^g;;)6+WCOsIL^%(b1mjry!Un{t=( zKd|8?j**z?O~+_+Z0_!~l%{A5wJhO;5vY~z^tB(-5^Q~LRje==RgLz?1pi#43AiEI zE_q2G!##rhS|2Nr;Vzk1+#B2cL$Ti^$4R@+@>V5}@5xa*_g2V|!;Tjw2S;k!{{-sp zzZ4nG`6h?FpKiJ}7vIl2w>tfr?PqMm__IwMYnQLnJ3nTEo+jLmFl=`dR52u z0)enHen1Y{;vVy6hO;kWssI?^F&_E0M?T=;X~@-yJRH#;l}^U{t;{048w7s^)lK0L z#7rxmfnP6_-K_Gk7Z5T7Wi85X)}cHd*~eq|M%nG}>yZa}*w4+?NgN!9)V=wHU%dc< zoQJ5)BfJLX+t|_8Bj1}(cn)M;f=S0x`y22A z*nw~dy}y$1wQmr<6uA(w3Q>S)T|xK&jLEF_i-v2e(VO=W{$0etOoZ(4jK_U|F$XZ; z`xsL(VBfJHpSxn`qj9irNRmkSZ!0ku!W|oOl6 d49=a=sjw6NUR{?8b74?KE4D3or3R1-ltpw~x>|G^M7GhkBb05cb*%yG zR>$2@d#YA#eYC^Yj_X#uLn$gnd?AZ3s`#Q-tYZ4^MWHt#33pE*-QC%LcK`FA&CD;q z?>xWP$;r3(kGj2o)E&?pR`pC{!UM#r2RS*-z3PGPUg%l%V2@w;|NTGM0*v{e?jQeR zoDP|I(-;$S!@=b9D#(%p;@(;b!x@%S|e|wvuKu@O}9BH#G0wuFcH6-`XO9JoK_+U)7}1j zY6cTR%}j_OelMK~iwP-&0K$#Om{2Pfm=kom;4CH>aAkH0jK-VUVaByh<&CU~F%|T6 zfpUa1Q1*8g%Br9$H`T{^zuW+M7es-8? zn+VCM%QL|?OwG%IHCUB51J+2*c?lfXT_F9K|0^wtp2GE7D3I1Yr5hgdbbq{Pu+Z_n zB#6xDR%YQYOMTk={qWHx$J>m_t?u2=&#mQOfQ|bd!ND-oqrCl3+hO-OQIj|1*X#*6 zAkYqqq)jEmIPO{*?ks&}#A1hKX`%ep!gw)U@F)w>xafI!8aFIT(t4Cp4m`GK0@UI+ zixxn&lv7r~L6o%lx%Hf1jg<-A&q))OJj!uV9$ff>6~30*UYMi}OLc1GG*_H8yn)Y; zv_@L@H86v}JQYV&B*9pmQIQQVOKU13fpc1=_g@;Vfhwu-El(5~aSO$;2zjCu#OITVYuVoQ}KaNRa06cC)-&~N)AeyxK;Y3g>7gHmbbyIG@Q zxzzm0E)IUcl7zMq04%|aO{R#Qhan!? znLKc~JV#&0mJUJ#Ezq;=@+OYHL9v&BW@*ZQuXx9 z>s9>+`wu5?`&8e^44j}Ps458Gv+)LI;{<%H`5-)sKQ%|KnsbZ^&k>$I&V+5v|3Z~d zPC3B@-AN|o5q1%br|7bXdkAZ2oc14a|DNN&jn5xrj|iMWRn!3%$K*$=bvv@CW9e{l zm$y@?%8dcPu}AMER(pMZz`A46(2X6(CXF~ZFfp;Wz1t2Gyp|>mIld<0je#+CHsKTd zY%y63?14Z|PVGNwH;5p&4}f5nS5#@IwAd$;{~T;So&h3iPQ+3hPB@VVLHP2CdT78& zC!=9K7MzTXM~`)*AbTSeuaQ{hT z@^c>V`pue>yWUmJ9n63>>VzIGuivQOt13?qde}6x2R(8SPDRYi^yVhp<6c{@t#bOH zEs3I+TriAF%L|(j^c}}M%8UJ4-hZ$E7FCJ&MZ^q7u*&GWi)cPZ5pz0E9UPlD>#BGD zUt#5`Jif=hu6yV#@3@(?VoXqb#=Vgm{a%jW?=Vo?yoEPTrNc3dY%#$sENqDi*+;dh z>x{D)tV4a^BV5@M4fF8579OgxsU;LvVn@rQ(5r{;P&JLsFRx>9`lfJk?EzK!7Q;>( zVJ4=X=EGJwmxzpyvx2O138Mahw~Ad#B37P`himxW=_0V;{nM$jtLg5w;>7EVGTq8@ zht@*vd`e6g$Pokg?0kdyUL`*=S5Y3qCtF)XKlc1|KV*%~xcYv`+6#`2mIH!Y$&`}+ z9suoZC_I5>XR;v{_nq->_vV>& z*o0AMO%RH6&i;1T#r~pf!&S5BQmRloTMT9#aV~@d`235|Dz%=^ z2B3!89t|5XsXYaTVOje%*oiYfPa8GESw)4XDt7lu`h%R52tp(N`SYz{#F&dF2*7z4 z&%+*!zr@2v%)eBn{aG39zzdhAKpN^g%AiJizQY7?1$SLe3BXn+G+tmrCEmCk0lQJT z98GOC>`Dw>L;98F(a-erqE&P&)gIkg?RA4VMeJ9q2lm?Mit}kS4Lh#HMo#OuicEgn zX&_C;fUajZb0}f`aU{*hu&X>Qky5X!Kub!!o|pHE%Hje#HSfUo@P@U#CiiEh(!Bf>To`l0#_r)A|OY*;Q7T`(j__7V`xaVdVq+-L(QdovjUA+I_+(Eg0%0A5Q%8Q!o zX5+LxH`q@56yqV*6x_wS%5%zdn0yBJb(w~3ag{{CMuXU=e2m|8Ee_doXtlqto%NV! zvpyy;`ExA2wT_+}KirB29)rG$HcxZgWMIt){d`#ij_7EYe*Rc1MeSjBvW0H#n%7 zq;_XRIIilBHvUx&$PavCw8bELtDDIq9bBBF-7g=I$(c^r%j7g{?nZE7(cNSiBfWVy z65wb2z@9bgjHfPBBWikrHTSM97MVd&6m;4XCZ=%X4bM`lIWWXEJ`V8dyM1y9@rTI* z=nu*#5`$86nBWDYPkep*SP0|hBo{G(BiYLuANv7gp(Oj0>}5U4qlg22_5hN-{=y_c#U4euhI*dkWMHfc!L%!XTnOdWe_J3(g^W{J0OfGnr z33CWTGci`=8!J00riSvpM=`sH>_s0ip=H`Btp$)dQ_Yn%2np$ wp0hLuuYD+>o}9f4tgo+0gsPF?*czJwTj4-`QwA)6;mKL_Frgd2-Nl4|0Hc%HqW}N^ From 267cb9906e90dfea4b1aebccc3a549ec60fc5a2d Mon Sep 17 00:00:00 2001 From: Per Frivik <94360401+PerFrivik@users.noreply.github.com> Date: Wed, 29 May 2024 17:11:09 +0200 Subject: [PATCH 272/652] integrationtests: mavros increase threshold for yaw_error_std --- integrationtests/python_src/px4_it/mavros/mission_test.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/integrationtests/python_src/px4_it/mavros/mission_test.py b/integrationtests/python_src/px4_it/mavros/mission_test.py index a9dccf728430..0692f11ec1ec 100755 --- a/integrationtests/python_src/px4_it/mavros/mission_test.py +++ b/integrationtests/python_src/px4_it/mavros/mission_test.py @@ -308,7 +308,7 @@ def test_mission(self): self.assertTrue(res['pitch_error_std'] < 5.0, str(res)) # TODO: fix by excluding initial heading init and reset preflight - self.assertTrue(res['yaw_error_std'] < 13.0, str(res)) + self.assertTrue(res['yaw_error_std'] < 15.0, str(res)) if __name__ == '__main__': From a80c96e57520bb51557cc2c60d758c8ef0539e34 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 29 May 2024 11:45:46 -0400 Subject: [PATCH 273/652] boards: px4_fmu-v5x_test disable payload_deliverer module to save flash --- boards/px4/fmu-v5x/test.px4board | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/px4/fmu-v5x/test.px4board b/boards/px4/fmu-v5x/test.px4board index 278cc285a1ae..083f7e7e118e 100644 --- a/boards/px4/fmu-v5x/test.px4board +++ b/boards/px4/fmu-v5x/test.px4board @@ -8,7 +8,7 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n CONFIG_DRIVERS_IRLOCK=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_ROVER_POS_CONTROL=n +CONFIG_MODULES_PAYLOAD_DELIVERER=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_BOARD_TESTING=y CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y From b36f47535e7f2404499ab529933994776549c5a7 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 29 May 2024 12:48:38 -0400 Subject: [PATCH 274/652] boards: px4_fmu-v6c_default disable gyro_fft module to save flash --- boards/px4/fmu-v6c/default.px4board | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/px4/fmu-v6c/default.px4board b/boards/px4/fmu-v6c/default.px4board index 51484f7903db..adae635537e7 100644 --- a/boards/px4/fmu-v6c/default.px4board +++ b/boards/px4/fmu-v6c/default.px4board @@ -48,7 +48,6 @@ CONFIG_MODULES_FW_POS_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y -CONFIG_MODULES_GYRO_FFT=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y From f3d152741c6b616492ffaf5f9203756ff33f6100 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 29 May 2024 12:51:03 -0400 Subject: [PATCH 275/652] boards: sky-drones_smartap-airlink_default disable gyro_fft module to save flash --- boards/sky-drones/smartap-airlink/default.px4board | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index 7613792e2ce7..fdfdcdea6a1b 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -50,7 +50,6 @@ CONFIG_MODULES_FW_POS_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y -CONFIG_MODULES_GYRO_FFT=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y From ae34e39b7e8a4775837e4955477bad9cad5d82c5 Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Wed, 29 May 2024 17:44:40 -0700 Subject: [PATCH 276/652] QuRT: Increased the size of the memory heap available to qurt platform (#23194) * Increased the size of the memory heap available to qurt platform --- platforms/qurt/CMakeLists.txt | 1 + platforms/qurt/new_delete.cpp | 92 +++++++++++++++++++++++++++++++++++ 2 files changed, 93 insertions(+) create mode 100644 platforms/qurt/new_delete.cpp diff --git a/platforms/qurt/CMakeLists.txt b/platforms/qurt/CMakeLists.txt index 0e9757a5d1a9..0bb5f5d712b7 100644 --- a/platforms/qurt/CMakeLists.txt +++ b/platforms/qurt/CMakeLists.txt @@ -44,6 +44,7 @@ include_directories( add_library(px4 SHARED ${PX4_SOURCE_DIR}/platforms/qurt/unresolved_symbols.c + ${PX4_SOURCE_DIR}/platforms/qurt/new_delete.cpp ${PX4_BINARY_DIR}/apps.cpp ) diff --git a/platforms/qurt/new_delete.cpp b/platforms/qurt/new_delete.cpp new file mode 100644 index 000000000000..1e8b004950cf --- /dev/null +++ b/platforms/qurt/new_delete.cpp @@ -0,0 +1,92 @@ +#include +#include + +/* + These are the heap access function exported by the SLPI DSP image. +*/ +extern "C" { + void *fc_heap_alloc(size_t size); + void fc_heap_free(void *ptr); +} + +/* + Globally override new and delete so that it can use the correct + heap manager for the Qurt platform. + + Note that new comes in multiple different variants. When new is used + without std::nothrow the compiler is free to assume it will not fail + as it assumes exceptions are enabled. This makes code like this + unsafe when using -fno-exceptions: + + a = new b; + if (a == nullptr) { + handle_error() + } + + The compiler may remove the error handling. With g++ you can use + -fcheck-new to avoid this, but on clang++ the compiler accepts + -fcheck-new as a valid flag, but doesn't implement it, and may remove + the error checking. That makes using clang++ unsafe with + -fno-exceptions if you ever call new without std::nothrow. +..It has been verified that hexagon-clang++ will remove the nullptr checks + after new if any optimization is selected for the compiler. +*/ + +/* + variant for new(std::nothrow), which is all that should be used in + PX4 + */ +void *operator new (size_t size, std::nothrow_t const ¬hrow) noexcept +{ + if (size < 1) { + size = 1; + } + + return (fc_heap_alloc(size)); +} + +void *operator new[](size_t size, std::nothrow_t const ¬hrow) noexcept +{ + if (size < 1) { + size = 1; + } + + return (fc_heap_alloc(size)); +} + +/* + These variants are for new without std::nothrow. We don't want to ever + use these from PX4 code + */ +void *operator new (size_t size) +{ + if (size < 1) { + size = 1; + } + + return (fc_heap_alloc(size)); +} + + +void *operator new[](size_t size) +{ + if (size < 1) { + size = 1; + } + + return (fc_heap_alloc(size)); +} + +/* + Override delete to free up memory to correct heap +*/ + +void operator delete (void *p) noexcept +{ + if (p) { fc_heap_free(p); } +} + +void operator delete[](void *ptr) noexcept +{ + if (ptr) { fc_heap_free(ptr); } +} From 0379048ad268a6879874550958b727a0645a8266 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 28 May 2024 11:51:18 +0200 Subject: [PATCH 277/652] mavsdk_tests: increase acceptance radius for position check on offboard landing Signed-off-by: Silvan Fuhrer --- test/mavsdk_tests/test_multicopter_offboard.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/test/mavsdk_tests/test_multicopter_offboard.cpp b/test/mavsdk_tests/test_multicopter_offboard.cpp index 7160c0db382c..84d75ad049c8 100644 --- a/test/mavsdk_tests/test_multicopter_offboard.cpp +++ b/test/mavsdk_tests/test_multicopter_offboard.cpp @@ -49,7 +49,7 @@ TEST_CASE("Offboard takeoff and land", "[multicopter][offboard]") tester.offboard_goto(takeoff_position, acceptance_radius, goto_timeout); tester.offboard_land(); tester.wait_until_disarmed(std::chrono::seconds(120)); - tester.check_home_within(1.0f); + tester.check_home_within(2.0f); } TEST_CASE("Offboard position control", "[multicopter][offboard]") @@ -72,7 +72,7 @@ TEST_CASE("Offboard position control", "[multicopter][offboard]") tester.offboard_goto(takeoff_position, acceptance_radius, goto_timeout); tester.offboard_land(); tester.wait_until_disarmed(std::chrono::seconds(120)); - tester.check_home_within(1.0f); + tester.check_home_within(2.0f); } TEST_CASE("Offboard attitude control", "[multicopter][offboard_attitude]") From 993782cffa124de49b575610994d67002aea5caf Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 27 May 2024 15:49:50 +0200 Subject: [PATCH 278/652] ekf2: only trigger position timeout reset when hpos fusion is active --- src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index f0d2c24270a3..ffa85706767b 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -320,7 +320,8 @@ bool Ekf::shouldResetGpsFusion() const #endif // CONFIG_EKF2_OPTICAL_FLOW const bool is_reset_required = has_horizontal_aiding_timed_out - || isTimedOut(_time_last_hor_pos_fuse, 2 * _params.reset_timeout_max); + || (isTimedOut(_time_last_hor_pos_fuse, 2 * _params.reset_timeout_max) + && (_params.gnss_ctrl & static_cast(GnssCtrl::HPOS))); const bool is_inflight_nav_failure = _control_status.flags.in_air && isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max) From 752051470ff4277ffd9d7184df72a542b9bbb5de Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 28 May 2024 16:51:47 +0200 Subject: [PATCH 279/652] Navigator: increase default of MIS_DIST_1WP to 10km The previous default of 900m leads to many warnings if left unchanged, especially if the vehicle is already in-air when the Mission is started. Signed-off-by: Silvan Fuhrer --- src/modules/navigator/mission_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 3a824bb8a080..1c637b8a50d9 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -87,7 +87,7 @@ PARAM_DEFINE_INT32(MIS_TKO_LAND_REQ, 0); * @increment 100 * @group Mission */ -PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 900); +PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 10000); /** * Enable yaw control of the mount. (Only affects multicopters and ROI mission items) From efe2a52eb4dd5c6c8040a8523c936d82b52951b0 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 28 May 2024 16:53:22 +0200 Subject: [PATCH 280/652] ROMFS: remove MIS_DIST_1WP customizations in airframes Signed-off-by: Silvan Fuhrer --- ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal | 1 - .../init.d-posix/airframes/1034_flightgear_rascal-electric | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo | 1 - .../px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal | 1 - ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad | 1 - 5 files changed, 5 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal b/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal index 06a845be30a3..f4d9ce42e096 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal @@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085 param set-default FW_W_EN 1 param set-default MIS_TAKEOFF_ALT 20 -param set-default MIS_DIST_1WP 2500 param set-default NAV_ACC_RAD 15 param set-default NAV_DLL_ACT 2 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1034_flightgear_rascal-electric b/ROMFS/px4fmu_common/init.d-posix/airframes/1034_flightgear_rascal-electric index 7cb6a3bf811e..ef9df5af984e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1034_flightgear_rascal-electric +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1034_flightgear_rascal-electric @@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085 param set-default FW_W_EN 1 param set-default MIS_TAKEOFF_ALT 20 -param set-default MIS_DIST_1WP 2500 param set-default NAV_ACC_RAD 15 param set-default NAV_DLL_ACT 2 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo b/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo index 06a845be30a3..f4d9ce42e096 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo @@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085 param set-default FW_W_EN 1 param set-default MIS_TAKEOFF_ALT 20 -param set-default MIS_DIST_1WP 2500 param set-default NAV_ACC_RAD 15 param set-default NAV_DLL_ACT 2 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal b/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal index 836615e635a2..487a1729c801 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal @@ -25,7 +25,6 @@ param set-default FW_W_EN 1 param set-default MIS_LTRMIN_ALT 30 param set-default MIS_TAKEOFF_ALT 20 -param set-default MIS_DIST_1WP 2500 param set-default NAV_ACC_RAD 15 param set-default NAV_DLL_ACT 2 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 0b2ea2596637..6456ccc74418 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -66,7 +66,6 @@ param set-default MC_PITCHRATE_I 0.05 param set-default MC_YAWRATE_MAX 20 param set-default MC_AIRMODE 1 -param set-default MIS_DIST_1WP 100 param set-default MIS_TAKEOFF_ALT 15 param set-default MPC_XY_P 0.8 From 2f4d6b6facd3884163d2df6f9862dab00d1d39c6 Mon Sep 17 00:00:00 2001 From: Peize-Liu Date: Thu, 30 May 2024 16:35:04 +0800 Subject: [PATCH 281/652] [Fix][hkust_nxt-dual]:board hkust_nxt-dual fix hw_config.h missing APP_RESERVATION_SIZE param (#23204) --- boards/hkust/nxt-dual/src/hw_config.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/boards/hkust/nxt-dual/src/hw_config.h b/boards/hkust/nxt-dual/src/hw_config.h index 7c2676f4ff4a..352f29436a06 100644 --- a/boards/hkust/nxt-dual/src/hw_config.h +++ b/boards/hkust/nxt-dual/src/hw_config.h @@ -97,9 +97,9 @@ #define INTERFACE_USART_CONFIG "/dev/ttyS5,57600" #define BOOT_DELAY_ADDRESS 0x000001a0 #define BOARD_TYPE 1013 -#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) -#define BOARD_FLASH_SECTORS (15) -#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (16 * 128 * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) #define OSC_FREQ 16 From 2de0af52e88b0260f888f37f5c1dfc3c136f21aa Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Tue, 19 Dec 2023 17:36:11 +0100 Subject: [PATCH 282/652] px4_fmuv6xrt: bidirectional dshot driver --- .../px4/fmu-v6xrt/nuttx-config/nsh/defconfig | 1 - .../nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 435 ++++++++++++++---- 2 files changed, 357 insertions(+), 79 deletions(-) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index ff0a42fdfdec..28df156d1bb2 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -87,7 +87,6 @@ CONFIG_IMXRT_ENET=y CONFIG_IMXRT_FLEXCAN1=y CONFIG_IMXRT_FLEXCAN2=y CONFIG_IMXRT_FLEXCAN3=y -CONFIG_IMXRT_FLEXIO1=y CONFIG_IMXRT_FLEXSPI2=y CONFIG_IMXRT_GPIO13_IRQ=y CONFIG_IMXRT_GPIO1_0_15_IRQ=y diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index ab3408c12ca8..e0fad4bb9e79 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -33,78 +33,295 @@ ****************************************************************************/ #include #include +#include #include +#include +#include #include #include #include #include +#include "barriers.h" #include "arm_internal.h" +#define FLEXIO_BASE IMXRT_FLEXIO1_BASE +#define FLEXIO_PREQ 120000000 #define DSHOT_TIMERS FLEXIO_SHIFTBUFNIS_COUNT #define DSHOT_THROTTLE_POSITION 5u #define DSHOT_TELEMETRY_POSITION 4u #define NIBBLES_SIZE 4u #define DSHOT_NUMBER_OF_NIBBLES 3u +static const uint32_t gcr_decode[32] = { + 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, + 0x0, 0x9, 0xA, 0xB, 0x0, 0xD, 0xE, 0xF, + 0x0, 0x0, 0x2, 0x3, 0x0, 0x5, 0x6, 0x7, + 0x0, 0x0, 0x8, 0x1, 0x0, 0x4, 0xC, 0x0 +}; + +uint32_t erpms[DSHOT_TIMERS]; + +typedef enum { + DSHOT_START = 0, + DSHOT_12BIT_TRANSFERRED, + DSHOT_TRANSMIT_COMPLETE, + BDSHOT_RECEIVE, + BDSHOT_RECEIVE_COMPLETE, +} dshot_state; + typedef struct dshot_handler_t { bool init; uint32_t data_seg1; uint32_t irq_data; + dshot_state state; + bool bdshot; + uint32_t raw_response; + uint16_t erpm; + uint32_t crc_error_cnt; + uint32_t frame_error_cnt; + uint32_t no_response_cnt; } dshot_handler_t; static dshot_handler_t dshot_inst[DSHOT_TIMERS] = {}; -struct flexio_dev_s *flexio_s; +static uint32_t dshot_tcmp; +static uint32_t bdshot_tcmp; +static uint32_t dshot_mask; +static uint32_t bdshot_recv_mask; -static int flexio_irq_handler(int irq, void *context, void *arg) +static inline uint32_t flexio_getreg32(uint32_t offset) { + return getreg32(FLEXIO_BASE + offset); +} - uint32_t flags = flexio_s->ops->get_shifter_status_flags(flexio_s); - uint32_t instance; +static inline void flexio_modifyreg32(unsigned int offset, + uint32_t clearbits, + uint32_t setbits) +{ + modifyreg32(FLEXIO_BASE + offset, clearbits, setbits); +} - for (instance = 0; flags && instance < DSHOT_TIMERS; instance++) { - if (flags & (1 << instance)) { - flexio_s->ops->disable_shifter_status_interrupts(flexio_s, (1 << instance)); - flexio_s->ops->disable_timer_status_interrupts(flexio_s, (1 << instance)); +static inline void flexio_putreg32(uint32_t value, uint32_t offset) +{ + putreg32(value, FLEXIO_BASE + offset); +} - if (dshot_inst[instance].irq_data != 0) { - uint32_t buf_adr = flexio_s->ops->get_shifter_buffer_address(flexio_s, FLEXIO_SHIFTER_BUFFER, instance); - putreg32(dshot_inst[instance].irq_data, IMXRT_FLEXIO1_BASE + buf_adr); - dshot_inst[instance].irq_data = 0; - } - } - } +static inline void enable_shifter_status_interrupts(uint32_t mask) +{ + flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, 0, mask); +} - return OK; +static inline void disable_shifter_status_interrupts(uint32_t mask) +{ + flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, mask, 0); } -int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq) +static inline uint32_t get_shifter_status_flags(void) { - uint32_t timer_compare; + return flexio_getreg32(IMXRT_FLEXIO_SHIFTSTAT_OFFSET); +} - if (dshot_pwm_freq == 150000) { - timer_compare = 0x2F8A; +static inline void clear_shifter_status_flags(uint32_t mask) +{ + flexio_putreg32(mask, IMXRT_FLEXIO_SHIFTSTAT_OFFSET); +} - } else if (dshot_pwm_freq == 300000) { - timer_compare = 0x2F45; +static inline void enable_timer_status_interrupts(uint32_t mask) +{ + flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, 0, mask); +} - } else if (dshot_pwm_freq == 600000) { - timer_compare = 0x2F22; +static inline void disable_timer_status_interrupts(uint32_t mask) +{ + flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, mask, 0); +} + +static inline uint32_t get_timer_status_flags(void) +{ + return flexio_getreg32(IMXRT_FLEXIO_TIMSTAT_OFFSET); +} + +static inline void clear_timer_status_flags(uint32_t mask) +{ + flexio_putreg32(mask, IMXRT_FLEXIO_TIMSTAT_OFFSET); +} + +static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp, bool inverted) +{ + /* Disable Shifter */ + flexio_putreg32(0, IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4); + + /* No start bit, stop bit low */ + flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) | + FLEXIO_SHIFTCFG_PWIDTH(0) | + FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_LOW) | + FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_ENABLE), + IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4); + + /* Transmit mode, output to FXIO pin, inverted output for bdshot */ + flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) | + FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) | + FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT) | + FLEXIO_SHIFTCTL_PINSEL(pin) | + FLEXIO_SHIFTCTL_PINPOL(inverted) | + FLEXIO_SHIFTCTL_SMOD(FLEXIO_SHIFTER_MODE_TRANSMIT), + IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4); + + /* Start transmitting on trigger, disable on compare */ + flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET) | + FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) | + FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_NEVER) | + FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) | + FLEXIO_TIMCFG_TIMENA(FLEXIO_TIMER_ENABLE_ON_TRIGGER_HIGH) | + FLEXIO_TIMCFG_TSTOP(FLEXIO_TIMER_STOP_BIT_DISABLED) | + FLEXIO_TIMCFG_TSTART(FLEXIO_TIMER_START_BIT_DISABLED), + IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4); + + flexio_putreg32(timcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4); + + /* Baud mode, Trigger on shifter write */ + flexio_putreg32(FLEXIO_TIMCTL_TRGSEL((4 * channel) + 1) | + FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_LOW) | + FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) | + FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) | + FLEXIO_TIMCTL_PINSEL(0) | + FLEXIO_TIMCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) | + FLEXIO_TIMCTL_TIMOD(FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT), + IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4); - } else if (dshot_pwm_freq == 1200000) { - timer_compare = 0x2F11; +} + +static int flexio_irq_handler(int irq, void *context, void *arg) +{ + + uint32_t flags = get_shifter_status_flags(); + uint32_t channel; + + for (channel = 0; flags && channel < DSHOT_TIMERS; channel++) { + if (flags & (1 << channel)) { + disable_shifter_status_interrupts(1 << channel); + + if (dshot_inst[channel].irq_data != 0) { + flexio_putreg32(dshot_inst[channel].irq_data, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4); + dshot_inst[channel].irq_data = 0; + + } else if (dshot_inst[channel].irq_data == 0 && dshot_inst[channel].state == BDSHOT_RECEIVE) { + dshot_inst[channel].state = BDSHOT_RECEIVE_COMPLETE; + dshot_inst[channel].raw_response = flexio_getreg32(IMXRT_FLEXIO_SHIFTBUFBIS0_OFFSET + channel * 0x4); + + bdshot_recv_mask |= (1 << channel); + + if (bdshot_recv_mask == dshot_mask) { + // Received telemetry on all channels + // Schedule workqueue? + } + } + } + } + + flags = get_timer_status_flags(); + + for (channel = 0; flags && channel < DSHOT_TIMERS; channel++) { + clear_timer_status_flags(1 << channel); + + if (flags & (1 << channel)) { + if (dshot_inst[channel].state == DSHOT_START) { + dshot_inst[channel].state = DSHOT_12BIT_TRANSFERRED; + + } else if (!dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) { + dshot_inst[channel].state = DSHOT_TRANSMIT_COMPLETE; + + } else if (dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) { + disable_shifter_status_interrupts(1 << channel); + dshot_inst[channel].state = BDSHOT_RECEIVE; + uint8_t timer = timer_io_channels[channel].timer_index; + + /* Transmit done, disable timer and reconfigure to receive*/ + flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4); + + /* Input data from pin, no start/stop bit*/ + flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) | + FLEXIO_SHIFTCFG_PWIDTH(0) | + FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_DISABLE) | + FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_SHIFT), + IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4); + + /* Shifter receive mdoe, on FXIO pin input */ + flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) | + FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) | + FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) | + FLEXIO_SHIFTCTL_PINSEL(io_timers[timer].dshot.flexio_pin) | + FLEXIO_SHIFTCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) | + FLEXIO_SHIFTCTL_SMOD(FLEXIO_SHIFTER_MODE_RECEIVE), + IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4); + + /* Make sure there no shifter flags high from transmission */ + clear_shifter_status_flags(1 << channel); + + /* Enable on pin transition, resychronize through reset on rising edge */ + flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_AFFECTED_BY_RESET) | + FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) | + FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_ON_TIMER_PIN_RISING_EDGE) | + FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) | + FLEXIO_TIMCFG_TIMENA(FLEXIO_TIMER_ENABLE_ON_TRIGGER_BOTH_EDGE) | + FLEXIO_TIMCFG_TSTOP(FLEXIO_TIMER_STOP_BIT_ENABLE_ON_TIMER_DISABLE) | + FLEXIO_TIMCFG_TSTART(FLEXIO_TIMER_START_BIT_ENABLED), + IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4); + + /* Enable on pin transition, resychronize through reset on rising edge */ + flexio_putreg32(bdshot_tcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4); + + /* Trigger on FXIO pin transition, Baud mode */ + flexio_putreg32(FLEXIO_TIMCTL_TRGSEL(2 * io_timers[timer].dshot.flexio_pin) | + FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_HIGH) | + FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) | + FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) | + FLEXIO_TIMCTL_PINSEL(0) | + FLEXIO_TIMCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) | + FLEXIO_TIMCTL_TIMOD(FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT), + IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4); + + /* Enable shifter interrupt for receiving data */ + enable_shifter_status_interrupts(1 << channel); + } + } - } else { - // Not supported Dshot frequency - return 0; } - /* Init FlexIO peripheral */ + return OK; +} - flexio_s = imxrt_flexio_initialize(1); + +int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot) +{ + /* Calculate dshot timings based on dshot_pwm_freq */ + dshot_tcmp = 0x2F00 | (((FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2)) & 0xFF); + bdshot_tcmp = 0x2900 | (((FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 1) & 0xFF); + + /* Clock FlexIO peripheral */ + imxrt_clockall_flexio1(); + + /* Reset FlexIO peripheral */ + flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0, + FLEXIO_CTRL_SWRST_MASK); + flexio_putreg32(0, IMXRT_FLEXIO_CTRL_OFFSET); + + /* Initialize FlexIO peripheral */ + flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, + (FLEXIO_CTRL_DOZEN_MASK | + FLEXIO_CTRL_DBGE_MASK | + FLEXIO_CTRL_FASTACC_MASK | + FLEXIO_CTRL_FLEXEN_MASK), + (FLEXIO_CTRL_DBGE(1) | + FLEXIO_CTRL_FASTACC(0) | + FLEXIO_CTRL_FLEXEN(0))); + + /* FlexIO IRQ handling */ up_enable_irq(IMXRT_IRQ_FLEXIO1); - irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, flexio_s); + irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, 0); + + dshot_mask = 0x0; for (unsigned channel = 0; (channel_mask != 0) && (channel < DSHOT_TIMERS); channel++) { if (channel_mask & (1 << channel)) { @@ -114,64 +331,107 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq) continue; } - imxrt_config_gpio(io_timers[timer].dshot.pinmux); - - struct flexio_shifter_config_s shft_cfg; - shft_cfg.timer_select = channel; - shft_cfg.timer_polarity = FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE; - shft_cfg.pin_config = FLEXIO_PIN_CONFIG_OUTPUT; - shft_cfg.pin_select = io_timers[timer].dshot.flexio_pin; - shft_cfg.pin_polarity = FLEXIO_PIN_ACTIVE_HIGH; - shft_cfg.shifter_mode = FLEXIO_SHIFTER_MODE_TRANSMIT; - shft_cfg.parallel_width = 0; - shft_cfg.input_source = FLEXIO_SHIFTER_INPUT_FROM_PIN; - shft_cfg.shifter_stop = FLEXIO_SHIFTER_STOP_BIT_LOW; - shft_cfg.shifter_start = FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_ENABLE; - - flexio_s->ops->set_shifter_config(flexio_s, channel, &shft_cfg); - - struct flexio_timer_config_s tmr_cfg; - tmr_cfg.trigger_select = (4 * channel) + 1; - tmr_cfg.trigger_polarity = FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_LOW; - tmr_cfg.trigger_source = FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL; - tmr_cfg.pin_config = FLEXIO_PIN_CONFIG_OUTPUT_DISABLED; - tmr_cfg.pin_select = 0; - tmr_cfg.pin_polarity = FLEXIO_PIN_ACTIVE_LOW; - tmr_cfg.timer_mode = FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT; - tmr_cfg.timer_output = FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET; - tmr_cfg.timer_decrement = FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT; - tmr_cfg.timer_reset = FLEXIO_TIMER_RESET_NEVER; - tmr_cfg.timer_disable = FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE; - tmr_cfg.timer_enable = FLEXIO_TIMER_ENABLE_ON_TRIGGER_HIGH; - tmr_cfg.timer_stop = FLEXIO_TIMER_STOP_BIT_DISABLED; - tmr_cfg.timer_start = FLEXIO_TIMER_START_BIT_DISABLED; - tmr_cfg.timer_compare = timer_compare; - flexio_s->ops->set_timer_config(flexio_s, channel, &tmr_cfg); + imxrt_config_gpio(io_timers[timer].dshot.pinmux | IOMUX_PULL_UP); + + dshot_inst[channel].bdshot = enable_bidirectional_dshot; + + flexio_dshot_output(channel, io_timers[timer].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot); dshot_inst[channel].init = true; + + // Mask channel to be active on dshot + dshot_mask |= (1 << channel); } } - flexio_s->ops->enable(flexio_s, true); + flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0, + FLEXIO_CTRL_FLEXEN_MASK); return channel_mask; } + +void up_bdshot_erpm(void) +{ + uint32_t value; + uint32_t erpm; + uint32_t csum_data; + + // Decode each individual channel + for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { + if (bdshot_recv_mask & (1 << channel)) { + value = ~dshot_inst[channel].raw_response & 0xFFFFF; + + /* if lowest significant isn't 1 we've got a framing error */ + if (value & 0x1) { + /* Decode RLL */ + value = (value ^ (value >> 1)); + + /* Decode GCR */ + erpm = gcr_decode[value & 0x1fU]; + erpm |= gcr_decode[(value >> 5U) & 0x1fU] << 4U; + erpm |= gcr_decode[(value >> 10U) & 0x1fU] << 8U; + erpm |= gcr_decode[(value >> 15U) & 0x1fU] << 12U; + + /* Calculate checksum */ + csum_data = erpm; + csum_data = csum_data ^ (csum_data >> 8U); + csum_data = csum_data ^ (csum_data >> NIBBLES_SIZE); + + if ((csum_data & 0xFU) != 0xFU) { + dshot_inst[channel].crc_error_cnt++; + + } else { + dshot_inst[channel].erpm = ~(erpm >> 4) & 0xFFF; + //TODO store this or foward this + } + + } else { + dshot_inst[channel].frame_error_cnt++; + } + } + } +} + +void up_bdshot_status(void) +{ + /* Call this function to calculate last ERPM ideally a workqueue does this. + For now this to debug using the dshot status cli command */ + up_bdshot_erpm(); + + for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { + + if (dshot_inst[channel].init) { + PX4_INFO("Channel %i Last erpm %i value", channel, dshot_inst[channel].erpm); + PX4_INFO("CRC errors Frame error No response"); + PX4_INFO("%10lu %11lu %11lu", dshot_inst[channel].crc_error_cnt, dshot_inst[channel].frame_error_cnt, + dshot_inst[channel].no_response_cnt); + } + } +} + void up_dshot_trigger(void) { - uint32_t buf_adr; + clear_timer_status_flags(0xFF); + + for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { + if ((bdshot_recv_mask & (1 << channel)) == 0) { + dshot_inst[channel].no_response_cnt++; + } - for (uint8_t motor_number = 0; (motor_number < DSHOT_TIMERS); motor_number++) { - if (dshot_inst[motor_number].init && dshot_inst[motor_number].data_seg1 != 0) { - buf_adr = flexio_s->ops->get_shifter_buffer_address(flexio_s, FLEXIO_SHIFTER_BUFFER, motor_number); - putreg32(dshot_inst[motor_number].data_seg1, IMXRT_FLEXIO1_BASE + buf_adr); + if (dshot_inst[channel].init && dshot_inst[channel].data_seg1 != 0) { + flexio_putreg32(dshot_inst[channel].data_seg1, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4); } } - flexio_s->ops->clear_timer_status_flags(flexio_s, 0xFF); - flexio_s->ops->enable_shifter_status_interrupts(flexio_s, 0xFF); + bdshot_recv_mask = 0x0; + + clear_timer_status_flags(0xFF); + enable_shifter_status_interrupts(0xFF); + enable_timer_status_interrupts(0xFF); } +/* Expand packet from 16 bits 48 to get T0H and T1H timing */ uint64_t dshot_expand_data(uint16_t packet) { unsigned int mask; @@ -197,16 +457,24 @@ uint64_t dshot_expand_data(uint16_t packet) * bit 12 - dshot telemetry enable/disable * bits 13-16 - XOR checksum **/ -void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemetry) +void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry) { - if (motor_number < DSHOT_TIMERS && dshot_inst[motor_number].init) { + uint8_t timer = timer_io_channels[channel].timer_index; + + if (channel < DSHOT_TIMERS && dshot_inst[channel].init) { + uint16_t csum_data; uint16_t packet = 0; uint16_t checksum = 0; packet |= throttle << DSHOT_THROTTLE_POSITION; packet |= ((uint16_t)telemetry & 0x01) << DSHOT_TELEMETRY_POSITION; - uint16_t csum_data = packet; + if (dshot_inst[channel].bdshot) { + csum_data = ~packet; + + } else { + csum_data = packet; + } /* XOR checksum calculation */ csum_data >>= NIBBLES_SIZE; @@ -219,8 +487,19 @@ void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemet packet |= (checksum & 0x0F); uint64_t dshot_expanded = dshot_expand_data(packet); - dshot_inst[motor_number].data_seg1 = (uint32_t)(dshot_expanded & 0xFFFFFF); - dshot_inst[motor_number].irq_data = (uint32_t)(dshot_expanded >> 24); + dshot_inst[channel].data_seg1 = (uint32_t)(dshot_expanded & 0xFFFFFF); + dshot_inst[channel].irq_data = (uint32_t)(dshot_expanded >> 24); + dshot_inst[channel].state = DSHOT_START; + + if (dshot_inst[channel].bdshot) { + + flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4); + disable_shifter_status_interrupts(1 << channel); + + flexio_dshot_output(channel, io_timers[timer].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot); + + clear_timer_status_flags(0xFF); + } } } From e2969952d318a9e3e731567042999582a8fd2179 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 22 Dec 2023 11:23:07 +0100 Subject: [PATCH 283/652] drivers: dshot: prepare to extend for bidrectional dshot --- .../nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 25 +++++-- .../src/px4/stm/stm32_common/dshot/dshot.c | 6 +- src/drivers/drv_dshot.h | 17 ++++- src/drivers/dshot/DShot.cpp | 67 +++++++++++++++++-- src/drivers/dshot/DShot.h | 9 ++- src/drivers/dshot/module.yaml | 10 +++ 6 files changed, 119 insertions(+), 15 deletions(-) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index e0fad4bb9e79..7475d3d58472 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -89,6 +89,7 @@ static uint32_t dshot_tcmp; static uint32_t bdshot_tcmp; static uint32_t dshot_mask; static uint32_t bdshot_recv_mask; +static uint32_t bdshot_parsed_recv_mask; static inline uint32_t flexio_getreg32(uint32_t offset) { @@ -350,13 +351,14 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi return channel_mask; } - void up_bdshot_erpm(void) { uint32_t value; uint32_t erpm; uint32_t csum_data; + bdshot_parsed_recv_mask = 0; + // Decode each individual channel for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { if (bdshot_recv_mask & (1 << channel)) { @@ -391,13 +393,25 @@ void up_bdshot_erpm(void) } } } + + bdshot_parsed_recv_mask = bdshot_recv_mask; +} + + + +int up_bdshot_get_erpm(uint8_t channel, int *erpm) +{ + if (bdshot_parsed_recv_mask & (1 << channel)) { + *erpm = dshot_inst[channel].erpm; + return 0; + } + + return -1; } + void up_bdshot_status(void) { - /* Call this function to calculate last ERPM ideally a workqueue does this. - For now this to debug using the dshot status cli command */ - up_bdshot_erpm(); for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { @@ -424,6 +438,9 @@ void up_dshot_trigger(void) } } + // Calc data now since we're not event driven + up_bdshot_erpm(); + bdshot_recv_mask = 0x0; clear_timer_status_flags(0xFF); diff --git a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c index 5b501850668a..c977c3a60bdc 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c @@ -82,7 +82,7 @@ static uint8_t dshot_burst_buffer_array[DSHOT_TIMERS * DSHOT_BURST_BUFFER_SIZE(M px4_cache_aligned_data() = {}; static uint32_t *dshot_burst_buffer[DSHOT_TIMERS] = {}; -int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq) +int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot) { unsigned buffer_offset = 0; @@ -152,6 +152,10 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq) return ret_val == OK ? channels_init_mask : ret_val; } +void up_bdshot_status(void) +{ +} + void up_dshot_trigger(void) { for (uint8_t timer = 0; (timer < DSHOT_TIMERS); timer++) { diff --git a/src/drivers/drv_dshot.h b/src/drivers/drv_dshot.h index 2e8dab2d6db9..3d9bed3fdacd 100644 --- a/src/drivers/drv_dshot.h +++ b/src/drivers/drv_dshot.h @@ -91,7 +91,7 @@ typedef enum { * @param dshot_pwm_freq Frequency of DSHOT signal. Usually DSHOT150, DSHOT300, DSHOT600 or DSHOT1200 * @return <0 on error, the initialized channels mask. */ -__EXPORT extern int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq); +__EXPORT extern int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot); /** * Set Dshot motor data, used by up_dshot_motor_data_set() and up_dshot_motor_command() (internal method) @@ -137,4 +137,19 @@ __EXPORT extern void up_dshot_trigger(void); */ __EXPORT extern int up_dshot_arm(bool armed); +/** + * Print bidrectional dshot status + */ +__EXPORT extern void up_bdshot_status(void); + + +/** + * Get bidrectional dshot erpm for a channel + * @param channel Dshot channel + * @param erpm pointer to write the erpm value + * @return <0 on error, OK on succes + */ +__EXPORT extern int up_bdshot_get_erpm(uint8_t channel, int *erpm); + + __END_DECLS diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 5ae0150efba9..569f6619d69c 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -144,7 +144,9 @@ void DShot::enable_dshot_outputs(const bool enabled) } } - int ret = up_dshot_init(_output_mask, dshot_frequency); + _bdshot = _param_bidirectional_enable.get(); + + int ret = up_dshot_init(_output_mask, dshot_frequency, _bdshot); if (ret < 0) { PX4_ERR("up_dshot_init failed (%i)", ret); @@ -167,6 +169,10 @@ void DShot::enable_dshot_outputs(const bool enabled) } _outputs_initialized = true; + + if (_bdshot) { + init_telemetry(NULL); + } } if (_outputs_initialized) { @@ -206,17 +212,20 @@ void DShot::init_telemetry(const char *device) _telemetry->esc_status_pub.advertise(); - int ret = _telemetry->handler.init(device); + if (device != NULL) { + int ret = _telemetry->handler.init(device); - if (ret != 0) { - PX4_ERR("telemetry init failed (%i)", ret); + if (ret != 0) { + PX4_ERR("telemetry init failed (%i)", ret); + } } update_telemetry_num_motors(); } -void DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data) +int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data) { + int ret = 0; // fill in new motor data esc_status_s &esc_status = _telemetry->esc_status_pub.get(); @@ -243,7 +252,7 @@ void DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTele esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1; esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1; - _telemetry->esc_status_pub.update(); + ret = 1; // Indicate we wrapped, so we publish data // reset esc data (in case a motor times out, so we won't send stale data) memset(&esc_status.esc, 0, sizeof(_telemetry->esc_status_pub.get().esc)); @@ -251,6 +260,35 @@ void DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTele } _telemetry->last_telemetry_index = telemetry_index; + + return ret; +} + +int DShot::handle_new_bdshot_erpm(void) +{ + int num_erpms = 0; + int erpm; + uint8_t channel; + esc_status_s &esc_status = _telemetry->esc_status_pub.get(); + + esc_status.timestamp = hrt_absolute_time(); + esc_status.counter = _esc_status_counter++; + esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_DSHOT; + esc_status.esc_armed_flags = _outputs_on; + + for (channel = 0; channel < 8; channel++) { + if (up_bdshot_get_erpm(channel, &erpm) == 0) { + num_erpms++; + esc_status.esc[channel].timestamp = hrt_absolute_time(); + esc_status.esc[channel].esc_rpm = (erpm * 100) / + (_param_mot_pole_count.get() / 2); + } + + } + + esc_status.esc_count = num_erpms; + + return num_erpms; } int DShot::send_command_thread_safe(const dshot_command_t command, const int num_repetitions, const int motor_index) @@ -463,6 +501,7 @@ void DShot::Run() if (_telemetry) { int telem_update = _telemetry->handler.update(); + int need_to_publish = 0; // Are we waiting for ESC info? if (_waiting_for_esc_info) { @@ -472,10 +511,21 @@ void DShot::Run() } } else if (telem_update >= 0) { - handle_new_telemetry_data(telem_update, _telemetry->handler.latestESCData()); + need_to_publish = handle_new_telemetry_data(telem_update, _telemetry->handler.latestESCData()); + } + + if (_bdshot) { + // Add bdshot data to esc status + need_to_publish += handle_new_bdshot_erpm(); + } + + if (need_to_publish > 0) { + // ESC telem wrap around or bdshot update + _telemetry->esc_status_pub.update(); } } + if (_parameter_update_sub.updated()) { update_params(); } @@ -713,6 +763,9 @@ int DShot::print_status() _telemetry->handler.printStatus(); } + /* Print dshot status */ + up_bdshot_status(); + return 0; } diff --git a/src/drivers/dshot/DShot.h b/src/drivers/dshot/DShot.h index 4f314cebb75f..a8dfd92239a2 100644 --- a/src/drivers/dshot/DShot.h +++ b/src/drivers/dshot/DShot.h @@ -131,7 +131,9 @@ class DShot final : public ModuleBase, public OutputModuleInterface void init_telemetry(const char *device); - void handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data); + int handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data); + + int handle_new_bdshot_erpm(void); int request_esc_info(); @@ -158,6 +160,7 @@ class DShot final : public ModuleBase, public OutputModuleInterface bool _outputs_initialized{false}; bool _outputs_on{false}; bool _waiting_for_esc_info{false}; + bool _bdshot{false}; static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS}; uint32_t _output_mask{0}; @@ -169,12 +172,14 @@ class DShot final : public ModuleBase, public OutputModuleInterface uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; + uint16_t _esc_status_counter{0}; DEFINE_PARAMETERS( (ParamFloat) _param_dshot_min, (ParamBool) _param_dshot_3d_enable, (ParamInt) _param_dshot_3d_dead_h, (ParamInt) _param_dshot_3d_dead_l, - (ParamInt) _param_mot_pole_count + (ParamInt) _param_mot_pole_count, + (ParamBool) _param_bidirectional_enable ) }; diff --git a/src/drivers/dshot/module.yaml b/src/drivers/dshot/module.yaml index edd38edd23f1..e2dcf8bc97e8 100644 --- a/src/drivers/dshot/module.yaml +++ b/src/drivers/dshot/module.yaml @@ -33,6 +33,16 @@ parameters: When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. type: boolean default: 0 + DSHOT_BIDIR_EN: + description: + short: Enable bidirectional DShot + long: | + This parameter enables bidirectional DShot which provides RPM feedback. + Note that this requires ESCs that support bidirectional DSHot, e.g. BlHeli32. + This is not the same as DShot telemetry which requires an additional serial connection. + type: boolean + default: 0 + reboot_required: true DSHOT_3D_DEAD_H: description: short: DSHOT 3D deadband high From b0cb697f71862c952904fbc9a92c4359865efc46 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 10 Mar 2024 15:39:57 +0100 Subject: [PATCH 284/652] imxrt: dshot add 1060 support and use channels instead of timers --- .../output_groups_from_timer_config.py | 16 ++++++--- .../fmu-v6xrt/nuttx-config/include/board.h | 4 +++ boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c | 2 +- boards/px4/fmu-v6xrt/src/timer_config.cpp | 32 ++++++++--------- .../nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 32 ++++++++--------- .../px4/nxp/imxrt/include/px4_arch/io_timer.h | 2 +- .../nuttx/src/px4/nxp/rt106x/CMakeLists.txt | 2 +- .../px4/nxp/rt106x/include/px4_arch/dshot.h | 36 +++++++++++++++++++ .../nxp/rt106x/include/px4_arch/io_timer.h | 2 ++ .../px4_arch/io_timer_hw_description.h | 21 +++++++++++ .../px4_arch/io_timer_hw_description.h | 17 ++++++--- 11 files changed, 123 insertions(+), 43 deletions(-) create mode 100644 platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/dshot.h diff --git a/Tools/module_config/output_groups_from_timer_config.py b/Tools/module_config/output_groups_from_timer_config.py index 62ea7c8214c6..8a932ec9dea7 100755 --- a/Tools/module_config/output_groups_from_timer_config.py +++ b/Tools/module_config/output_groups_from_timer_config.py @@ -54,12 +54,21 @@ def extract_timer_from_channel(line, timer_names): return None +def imxrt_is_dshot(line): + + # NXP FlexPWM format format: initIOPWM(PWM::FlexPWM2), + search = re.search('(initIOPWMDshot)', line, re.IGNORECASE) + if search: + return True + + return False + def get_timer_groups(timer_config_file, verbose=False): with open(timer_config_file, 'r') as f: timer_config = f.read() # timers - dshot_support = {} # key: timer + dshot_support = {str(i): False for i in range(16)} timers_start_marker = 'io_timers_t io_timers' timers_start = timer_config.find(timers_start_marker) if timers_start == -1: @@ -78,10 +87,9 @@ def get_timer_groups(timer_config_file, verbose=False): if timer_type == 'imxrt': if verbose: print('imxrt timer found') timer_names.append(timer) + if imxrt_is_dshot(line): + dshot_support[str(len(timers))] = True timers.append(str(len(timers))) - dshot_support = {str(i): False for i in range(16)} - for i in range(8): # First 8 channels support dshot - dshot_support[str(i)] = True elif timer: if verbose: print('found timer def: {:}'.format(timer)) dshot_support[timer] = 'DMA' in line diff --git a/boards/px4/fmu-v6xrt/nuttx-config/include/board.h b/boards/px4/fmu-v6xrt/nuttx-config/include/board.h index 6b704139dc0c..83832f228da1 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/include/board.h +++ b/boards/px4/fmu-v6xrt/nuttx-config/include/board.h @@ -267,6 +267,10 @@ // This is the ENET_1G interface. +/* Dshot Disambiguation *******************************************************/ + +#define IOMUX_DSHOT_DEFAULT (IOMUX_DRIVE_HIGHSTRENGTH | IOMUX_SLEW_FAST) + // Compile time selection #if defined(CONFIG_ETH0_PHY_TJA1103) # define BOARD_PHY_ADDR (18) diff --git a/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c b/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c index d83265ce8f55..db591baf81c9 100644 --- a/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c +++ b/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c @@ -114,7 +114,7 @@ const struct clock_configuration_s g_initial_clkconfig = { .div = 1, .mux = ACMP_CLK_ROOT_OSC_RC_48M_DIV2, }, - .flexio1_clk_root = + .flexio1_clk_root = /* 240 / 2 = 120Mhz */ { .enable = 1, .div = 2, diff --git a/boards/px4/fmu-v6xrt/src/timer_config.cpp b/boards/px4/fmu-v6xrt/src/timer_config.cpp index 1b1497c10137..04be42b4d8ed 100644 --- a/boards/px4/fmu-v6xrt/src/timer_config.cpp +++ b/boards/px4/fmu-v6xrt/src/timer_config.cpp @@ -91,14 +91,14 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { - initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO23_1, 23), - initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule1, GPIO_FLEXIO1_FLEXIO25_1, 25), - initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule2, GPIO_FLEXIO1_FLEXIO27_1, 27), - initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO06_1, 6), - initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1, GPIO_FLEXIO1_FLEXIO08_1, 8), - initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule2, GPIO_FLEXIO1_FLEXIO10_1, 10), - initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule3, GPIO_FLEXIO1_FLEXIO19_1, 19), - initIOPWMDshot(PWM::FlexPWM3, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO29_1, 29), + initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule0), + initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule1), + initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule2), + initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0), + initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1), + initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule2), + initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule3), + initIOPWMDshot(PWM::FlexPWM3, PWM::Submodule0), initIOPWM(PWM::FlexPWM3, PWM::Submodule1), initIOPWM(PWM::FlexPWM3, PWM::Submodule3), initIOPWM(PWM::FlexPWM4, PWM::Submodule0), @@ -106,14 +106,14 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { }; constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { - /* FMU_CH1 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_23), - /* FMU_CH2 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_25), - /* FMU_CH3 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_27), - /* FMU_CH4 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_06), - /* FMU_CH5 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_08), - /* FMU_CH6 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_10), - /* FMU_CH7 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_19), - /* FMU_CH8 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_29), + /* FMU_CH1 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_23, GPIO_FLEXIO1_FLEXIO23_1 | IOMUX_DSHOT_DEFAULT, 23), + /* FMU_CH2 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_25, GPIO_FLEXIO1_FLEXIO25_1 | IOMUX_DSHOT_DEFAULT, 25), + /* FMU_CH3 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_27, GPIO_FLEXIO1_FLEXIO27_1 | IOMUX_DSHOT_DEFAULT, 27), + /* FMU_CH4 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_06, GPIO_FLEXIO1_FLEXIO06_1 | IOMUX_DSHOT_DEFAULT, 6), + /* FMU_CH5 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_08, GPIO_FLEXIO1_FLEXIO08_1 | IOMUX_DSHOT_DEFAULT, 8), + /* FMU_CH6 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_10, GPIO_FLEXIO1_FLEXIO10_1 | IOMUX_DSHOT_DEFAULT, 10), + /* FMU_CH7 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_19, GPIO_FLEXIO1_FLEXIO19_1 | IOMUX_DSHOT_DEFAULT, 19), + /* FMU_CH8 */ initIOTimerChannelDshot(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_29, GPIO_FLEXIO1_FLEXIO29_1 | IOMUX_DSHOT_DEFAULT, 29), /* FMU_CH9 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_31), /* FMU_CH10 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_21), /* FMU_CH11 */ initIOTimerChannel(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_00), diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index 7475d3d58472..15fffdfaf2eb 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -53,6 +53,10 @@ #define NIBBLES_SIZE 4u #define DSHOT_NUMBER_OF_NIBBLES 3u +#if defined(IOMUX_PULL_UP_47K) +#define IOMUX_PULL_UP IOMUX_PULL_UP_47K +#endif + static const uint32_t gcr_decode[32] = { 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9, 0xA, 0xB, 0x0, 0xD, 0xE, 0xF, @@ -195,7 +199,6 @@ static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp, static int flexio_irq_handler(int irq, void *context, void *arg) { - uint32_t flags = get_shifter_status_flags(); uint32_t channel; @@ -236,7 +239,6 @@ static int flexio_irq_handler(int irq, void *context, void *arg) } else if (dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) { disable_shifter_status_interrupts(1 << channel); dshot_inst[channel].state = BDSHOT_RECEIVE; - uint8_t timer = timer_io_channels[channel].timer_index; /* Transmit done, disable timer and reconfigure to receive*/ flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4); @@ -252,7 +254,7 @@ static int flexio_irq_handler(int irq, void *context, void *arg) flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) | FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) | FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) | - FLEXIO_SHIFTCTL_PINSEL(io_timers[timer].dshot.flexio_pin) | + FLEXIO_SHIFTCTL_PINSEL(timer_io_channels[channel].dshot.flexio_pin) | FLEXIO_SHIFTCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) | FLEXIO_SHIFTCTL_SMOD(FLEXIO_SHIFTER_MODE_RECEIVE), IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4); @@ -274,7 +276,7 @@ static int flexio_irq_handler(int irq, void *context, void *arg) flexio_putreg32(bdshot_tcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4); /* Trigger on FXIO pin transition, Baud mode */ - flexio_putreg32(FLEXIO_TIMCTL_TRGSEL(2 * io_timers[timer].dshot.flexio_pin) | + flexio_putreg32(FLEXIO_TIMCTL_TRGSEL(2 * timer_io_channels[channel].dshot.flexio_pin) | FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_HIGH) | FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) | FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) | @@ -315,7 +317,7 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi FLEXIO_CTRL_FASTACC_MASK | FLEXIO_CTRL_FLEXEN_MASK), (FLEXIO_CTRL_DBGE(1) | - FLEXIO_CTRL_FASTACC(0) | + FLEXIO_CTRL_FASTACC(1) | FLEXIO_CTRL_FLEXEN(0))); /* FlexIO IRQ handling */ @@ -326,17 +328,16 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi for (unsigned channel = 0; (channel_mask != 0) && (channel < DSHOT_TIMERS); channel++) { if (channel_mask & (1 << channel)) { - uint8_t timer = timer_io_channels[channel].timer_index; - if (io_timers[timer].dshot.pinmux == 0) { // board does not configure dshot on this pin + if (timer_io_channels[channel].dshot.pinmux == 0) { // board does not configure dshot on this pin continue; } - imxrt_config_gpio(io_timers[timer].dshot.pinmux | IOMUX_PULL_UP); + imxrt_config_gpio(timer_io_channels[channel].dshot.pinmux | IOMUX_PULL_UP); dshot_inst[channel].bdshot = enable_bidirectional_dshot; - flexio_dshot_output(channel, io_timers[timer].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot); + flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot); dshot_inst[channel].init = true; @@ -429,7 +430,7 @@ void up_dshot_trigger(void) clear_timer_status_flags(0xFF); for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { - if ((bdshot_recv_mask & (1 << channel)) == 0) { + if (dshot_inst[channel].bdshot && (bdshot_recv_mask & (1 << channel)) == 0) { dshot_inst[channel].no_response_cnt++; } @@ -439,9 +440,10 @@ void up_dshot_trigger(void) } // Calc data now since we're not event driven - up_bdshot_erpm(); - - bdshot_recv_mask = 0x0; + if(bdshot_recv_mask != 0x0) { + up_bdshot_erpm(); + bdshot_recv_mask = 0x0; + } clear_timer_status_flags(0xFF); enable_shifter_status_interrupts(0xFF); @@ -476,8 +478,6 @@ uint64_t dshot_expand_data(uint16_t packet) **/ void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry) { - uint8_t timer = timer_io_channels[channel].timer_index; - if (channel < DSHOT_TIMERS && dshot_inst[channel].init) { uint16_t csum_data; uint16_t packet = 0; @@ -513,7 +513,7 @@ void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry) flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4); disable_shifter_status_interrupts(1 << channel); - flexio_dshot_output(channel, io_timers[timer].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot); + flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot); clear_timer_status_flags(0xFF); } diff --git a/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/io_timer.h index 4cffe9c858a5..1fba2e04494f 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/io_timer.h @@ -87,7 +87,6 @@ typedef struct io_timers_t { uint32_t clock_register; /* SIM_SCGCn */ uint32_t clock_bit; /* SIM_SCGCn bit pos */ uint32_t vectorno; /* IRQ number */ - dshot_conf_t dshot; } io_timers_t; typedef struct io_timers_channel_mapping_element_t { @@ -112,6 +111,7 @@ typedef struct timer_io_channels_t { uint8_t sub_module; /* 0 based sub module offset */ uint8_t sub_module_bits; /* LDOK and CLDOK bits */ uint8_t timer_channel; /* Unused */ + dshot_conf_t dshot; } timer_io_channels_t; #define SM0 0 diff --git a/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt index d94ea8d902f0..f487b031c7fe 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt @@ -36,7 +36,7 @@ add_subdirectory(../imxrt/adc adc) add_subdirectory(../imxrt/board_critmon board_critmon) add_subdirectory(../imxrt/board_hw_info board_hw_info) add_subdirectory(../imxrt/board_reset board_reset) -#add_subdirectory(../imxrt/dshot dshot) +add_subdirectory(../imxrt/dshot dshot) add_subdirectory(../imxrt/hrt hrt) add_subdirectory(../imxrt/led_pwm led_pwm) add_subdirectory(../imxrt/io_pins io_pins) diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/dshot.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/dshot.h new file mode 100644 index 000000000000..b6aaca410a9d --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/dshot.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../../../imxrt/include/px4_arch/dshot.h" diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer.h index 613ac1b19777..83938d918bfe 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer.h @@ -41,6 +41,7 @@ #include #include +#include "dshot.h" #pragma once __BEGIN_DECLS @@ -110,6 +111,7 @@ typedef struct timer_io_channels_t { uint8_t sub_module; /* 0 based sub module offset */ uint8_t sub_module_bits; /* LDOK and CLDOK bits */ uint8_t timer_channel; /* Unused */ + dshot_conf_t dshot; } timer_io_channels_t; #define SM0 0 diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h index e371b6de83d6..5cbc33fdc3a9 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h @@ -601,6 +601,16 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t return ret; } +static inline constexpr timer_io_channels_t initIOTimerChannelDshot(const io_timers_t io_timers_conf[MAX_IO_TIMERS], + PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio_pin) +{ + timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, pwm_config, pad); + + ret.dshot.pinmux = dshot_pinmux; + ret.dshot.flexio_pin = flexio_pin; + return ret; +} + static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub) { io_timers_t ret{}; @@ -609,3 +619,14 @@ static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubm ret.submodle = sub; return ret; } + + + +static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub) +{ + io_timers_t ret{}; + + ret.base = getFlexPWMBaseRegister(pwm); + ret.submodle = sub; + return ret; +} diff --git a/platforms/nuttx/src/px4/nxp/rt117x/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/nxp/rt117x/include/px4_arch/io_timer_hw_description.h index 77dbfe918417..0bcf5c302ab8 100644 --- a/platforms/nuttx/src/px4/nxp/rt117x/include/px4_arch/io_timer_hw_description.h +++ b/platforms/nuttx/src/px4/nxp/rt117x/include/px4_arch/io_timer_hw_description.h @@ -690,6 +690,16 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t return ret; } +static inline constexpr timer_io_channels_t initIOTimerChannelDshot(const io_timers_t io_timers_conf[MAX_IO_TIMERS], + PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio_pin) +{ + timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, pwm_config, pad); + + ret.dshot.pinmux = dshot_pinmux; + ret.dshot.flexio_pin = flexio_pin; + return ret; +} + static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub) { io_timers_t ret{}; @@ -699,14 +709,13 @@ static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubm return ret; } -static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub, uint32_t pinmux, - uint32_t flexio_pin) + + +static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub) { io_timers_t ret{}; ret.base = getFlexPWMBaseRegister(pwm); ret.submodle = sub; - ret.dshot.pinmux = pinmux; - ret.dshot.flexio_pin = flexio_pin; return ret; } From f3ef0d6610be3ba064d97d80faf3591ff67b3c5b Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Thu, 21 Mar 2024 16:06:04 +0100 Subject: [PATCH 285/652] dshot: fix clearing out esc status --- .../nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 2 +- .../src/px4/stm/stm32_common/dshot/dshot.c | 6 +++++ src/drivers/dshot/DShot.cpp | 26 +++++++++++++++---- src/drivers/dshot/DShot.h | 2 ++ src/drivers/dshot/DShotTelemetry.cpp | 4 +++ src/drivers/dshot/DShotTelemetry.h | 1 + 6 files changed, 35 insertions(+), 6 deletions(-) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index 15fffdfaf2eb..cfd95b936bf6 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -440,7 +440,7 @@ void up_dshot_trigger(void) } // Calc data now since we're not event driven - if(bdshot_recv_mask != 0x0) { + if (bdshot_recv_mask != 0x0) { up_bdshot_erpm(); bdshot_recv_mask = 0x0; } diff --git a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c index c977c3a60bdc..1f6e0b923dcc 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c @@ -152,6 +152,12 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi return ret_val == OK ? channels_init_mask : ret_val; } +int up_bdshot_get_erpm(uint8_t channel, int *erpm) +{ + // Not implemented + return -1; +} + void up_bdshot_status(void) { } diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 569f6619d69c..d5e294609ce1 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -253,10 +253,6 @@ int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelem esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1; ret = 1; // Indicate we wrapped, so we publish data - - // reset esc data (in case a motor times out, so we won't send stale data) - memset(&esc_status.esc, 0, sizeof(_telemetry->esc_status_pub.get().esc)); - esc_status.esc_online_flags = 0; } _telemetry->last_telemetry_index = telemetry_index; @@ -264,6 +260,24 @@ int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelem return ret; } +void DShot::publish_esc_status(void) +{ + esc_status_s &esc_status = _telemetry->esc_status_pub.get(); + + // clear data of the esc that are offline + for (uint8_t channel = 0; (channel < _telemetry->last_telemetry_index); channel++) { + if ((esc_status.esc_online_flags & (1 << channel)) == 0) { + memset(&esc_status.esc[channel], 0, sizeof(struct esc_report_s)); + } + } + + // ESC telem wrap around or bdshot update + _telemetry->esc_status_pub.update(); + + // reset esc online flags + esc_status.esc_online_flags = 0; +} + int DShot::handle_new_bdshot_erpm(void) { int num_erpms = 0; @@ -279,9 +293,11 @@ int DShot::handle_new_bdshot_erpm(void) for (channel = 0; channel < 8; channel++) { if (up_bdshot_get_erpm(channel, &erpm) == 0) { num_erpms++; + esc_status.esc_online_flags |= 1 << channel; esc_status.esc[channel].timestamp = hrt_absolute_time(); esc_status.esc[channel].esc_rpm = (erpm * 100) / (_param_mot_pole_count.get() / 2); + esc_status.esc[channel].actuator_function = _telemetry->actuator_functions[channel]; } } @@ -521,7 +537,7 @@ void DShot::Run() if (need_to_publish > 0) { // ESC telem wrap around or bdshot update - _telemetry->esc_status_pub.update(); + publish_esc_status(); } } diff --git a/src/drivers/dshot/DShot.h b/src/drivers/dshot/DShot.h index a8dfd92239a2..50b8d9eaa012 100644 --- a/src/drivers/dshot/DShot.h +++ b/src/drivers/dshot/DShot.h @@ -133,6 +133,8 @@ class DShot final : public ModuleBase, public OutputModuleInterface int handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data); + void publish_esc_status(void); + int handle_new_bdshot_erpm(void); int request_esc_info(); diff --git a/src/drivers/dshot/DShotTelemetry.cpp b/src/drivers/dshot/DShotTelemetry.cpp index 14a21d5654e0..f0444bff1950 100644 --- a/src/drivers/dshot/DShotTelemetry.cpp +++ b/src/drivers/dshot/DShotTelemetry.cpp @@ -183,6 +183,9 @@ bool DShotTelemetry::decodeByte(uint8_t byte, bool &successful_decoding) _latest_data.erpm); ++_num_successful_responses; successful_decoding = true; + + } else { + ++_num_checksum_errors; } return true; @@ -195,6 +198,7 @@ void DShotTelemetry::printStatus() const { PX4_INFO("Number of successful ESC frames: %i", _num_successful_responses); PX4_INFO("Number of timeouts: %i", _num_timeouts); + PX4_INFO("Number of CRC errors: %i", _num_checksum_errors); } uint8_t DShotTelemetry::updateCrc8(uint8_t crc, uint8_t crc_seed) diff --git a/src/drivers/dshot/DShotTelemetry.h b/src/drivers/dshot/DShotTelemetry.h index a5c549c47676..1164d1e2008c 100644 --- a/src/drivers/dshot/DShotTelemetry.h +++ b/src/drivers/dshot/DShotTelemetry.h @@ -140,4 +140,5 @@ class DShotTelemetry // statistics int _num_timeouts{0}; int _num_successful_responses{0}; + int _num_checksum_errors{0}; }; From 0e41f9730f56a9471cde158fb68158a1c595973a Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 27 Mar 2024 09:50:29 +0100 Subject: [PATCH 286/652] imxrt: dshot improve state machine reduce's no response count --- .../nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 31 ++++++++++--------- 1 file changed, 17 insertions(+), 14 deletions(-) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index cfd95b936bf6..f4b5a1fcc962 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -68,6 +68,7 @@ uint32_t erpms[DSHOT_TIMERS]; typedef enum { DSHOT_START = 0, + DSHOT_12BIT_FIFO, DSHOT_12BIT_TRANSFERRED, DSHOT_TRANSMIT_COMPLETE, BDSHOT_RECEIVE, @@ -206,11 +207,11 @@ static int flexio_irq_handler(int irq, void *context, void *arg) if (flags & (1 << channel)) { disable_shifter_status_interrupts(1 << channel); - if (dshot_inst[channel].irq_data != 0) { + if (dshot_inst[channel].state == DSHOT_START) { + dshot_inst[channel].state = DSHOT_12BIT_FIFO; flexio_putreg32(dshot_inst[channel].irq_data, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4); - dshot_inst[channel].irq_data = 0; - } else if (dshot_inst[channel].irq_data == 0 && dshot_inst[channel].state == BDSHOT_RECEIVE) { + } else if (dshot_inst[channel].state == BDSHOT_RECEIVE) { dshot_inst[channel].state = BDSHOT_RECEIVE_COMPLETE; dshot_inst[channel].raw_response = flexio_getreg32(IMXRT_FLEXIO_SHIFTBUFBIS0_OFFSET + channel * 0x4); @@ -226,11 +227,13 @@ static int flexio_irq_handler(int irq, void *context, void *arg) flags = get_timer_status_flags(); - for (channel = 0; flags && channel < DSHOT_TIMERS; channel++) { - clear_timer_status_flags(1 << channel); + for (channel = 0; flags; (channel = (channel + 1) % DSHOT_TIMERS)) { + flags = get_timer_status_flags(); if (flags & (1 << channel)) { - if (dshot_inst[channel].state == DSHOT_START) { + clear_timer_status_flags(1 << channel); + + if (dshot_inst[channel].state == DSHOT_12BIT_FIFO) { dshot_inst[channel].state = DSHOT_12BIT_TRANSFERRED; } else if (!dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) { @@ -386,7 +389,7 @@ void up_bdshot_erpm(void) } else { dshot_inst[channel].erpm = ~(erpm >> 4) & 0xFFF; - //TODO store this or foward this + bdshot_parsed_recv_mask |= (1 << channel); } } else { @@ -394,8 +397,6 @@ void up_bdshot_erpm(void) } } } - - bdshot_parsed_recv_mask = bdshot_recv_mask; } @@ -427,6 +428,11 @@ void up_bdshot_status(void) void up_dshot_trigger(void) { + // Calc data now since we're not event driven + if (bdshot_recv_mask != 0x0) { + up_bdshot_erpm(); + } + clear_timer_status_flags(0xFF); for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { @@ -439,11 +445,7 @@ void up_dshot_trigger(void) } } - // Calc data now since we're not event driven - if (bdshot_recv_mask != 0x0) { - up_bdshot_erpm(); - bdshot_recv_mask = 0x0; - } + bdshot_recv_mask = 0x0; clear_timer_status_flags(0xFF); enable_shifter_status_interrupts(0xFF); @@ -504,6 +506,7 @@ void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry) packet |= (checksum & 0x0F); uint64_t dshot_expanded = dshot_expand_data(packet); + dshot_inst[channel].data_seg1 = (uint32_t)(dshot_expanded & 0xFFFFFF); dshot_inst[channel].irq_data = (uint32_t)(dshot_expanded >> 24); dshot_inst[channel].state = DSHOT_START; From 5d2fda61728a2efee1c239dece6c648f19f8b4fd Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 27 Mar 2024 13:08:54 +0100 Subject: [PATCH 287/652] dshot: bdshot fix esc offline/online checks --- .../nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 15 ++++++++- .../src/px4/stm/stm32_common/dshot/dshot.c | 6 ++++ src/drivers/drv_dshot.h | 9 ++++++ src/drivers/dshot/DShot.cpp | 31 ++++++++++++++----- src/drivers/dshot/DShot.h | 1 + 5 files changed, 54 insertions(+), 8 deletions(-) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index f4b5a1fcc962..d697234c9c46 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -86,8 +86,11 @@ typedef struct dshot_handler_t { uint32_t crc_error_cnt; uint32_t frame_error_cnt; uint32_t no_response_cnt; + uint32_t last_no_response_cnt; } dshot_handler_t; +#define BDSHOT_OFFLINE_COUNT 400 // If there are no responses for 400 setpoints ESC is offline + static dshot_handler_t dshot_inst[DSHOT_TIMERS] = {}; static uint32_t dshot_tcmp; @@ -390,6 +393,7 @@ void up_bdshot_erpm(void) } else { dshot_inst[channel].erpm = ~(erpm >> 4) & 0xFFF; bdshot_parsed_recv_mask |= (1 << channel); + dshot_inst[channel].last_no_response_cnt = dshot_inst[channel].no_response_cnt; } } else { @@ -411,6 +415,14 @@ int up_bdshot_get_erpm(uint8_t channel, int *erpm) return -1; } +int up_bdshot_channel_status(uint8_t channel) +{ + if (channel < DSHOT_TIMERS) { + return ((dshot_inst[channel].no_response_cnt - dshot_inst[channel].last_no_response_cnt) < BDSHOT_OFFLINE_COUNT); + } + + return -1; +} void up_bdshot_status(void) { @@ -418,7 +430,8 @@ void up_bdshot_status(void) for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) { if (dshot_inst[channel].init) { - PX4_INFO("Channel %i Last erpm %i value", channel, dshot_inst[channel].erpm); + PX4_INFO("Channel %i %s Last erpm %i value", channel, up_bdshot_channel_status(channel) ? "online" : "offline", + dshot_inst[channel].erpm); PX4_INFO("CRC errors Frame error No response"); PX4_INFO("%10lu %11lu %11lu", dshot_inst[channel].crc_error_cnt, dshot_inst[channel].frame_error_cnt, dshot_inst[channel].no_response_cnt); diff --git a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c index 1f6e0b923dcc..00491e976831 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c @@ -158,6 +158,12 @@ int up_bdshot_get_erpm(uint8_t channel, int *erpm) return -1; } +int up_bdshot_channel_status(uint8_t channel) +{ + // Not implemented + return -1; +} + void up_bdshot_status(void) { } diff --git a/src/drivers/drv_dshot.h b/src/drivers/drv_dshot.h index 3d9bed3fdacd..81c92b4d50ee 100644 --- a/src/drivers/drv_dshot.h +++ b/src/drivers/drv_dshot.h @@ -152,4 +152,13 @@ __EXPORT extern void up_bdshot_status(void); __EXPORT extern int up_bdshot_get_erpm(uint8_t channel, int *erpm); +/** + * Get bidrectional dshot status for a channel + * @param channel Dshot channel + * @param erpm pointer to write the erpm value + * @return <0 on error / not supported, 0 on offline, 1 on online + */ +__EXPORT extern int up_bdshot_channel_status(uint8_t channel); + + __END_DECLS diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index d5e294609ce1..26ad1d63b3f5 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -159,6 +159,9 @@ void DShot::enable_dshot_outputs(const bool enabled) for (unsigned i = 0; i < _num_outputs; ++i) { if (((1 << i) & _output_mask) == 0) { _mixing_output.disableFunction(i); + + } else { + _dshot_esc_count++; } } @@ -248,9 +251,6 @@ int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelem esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_DSHOT; esc_status.esc_count = _telemetry->handler.numMotors(); ++esc_status.counter; - // FIXME: mark all ESC's as online, otherwise commander complains even for a single dropout - esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1; - esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1; ret = 1; // Indicate we wrapped, so we publish data } @@ -263,14 +263,31 @@ int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelem void DShot::publish_esc_status(void) { esc_status_s &esc_status = _telemetry->esc_status_pub.get(); + uint8_t channel; // clear data of the esc that are offline - for (uint8_t channel = 0; (channel < _telemetry->last_telemetry_index); channel++) { + for (channel = 0; (channel < _telemetry->last_telemetry_index); channel++) { if ((esc_status.esc_online_flags & (1 << channel)) == 0) { memset(&esc_status.esc[channel], 0, sizeof(struct esc_report_s)); } } + // FIXME: mark all UART Telemetry ESC's as online, otherwise commander complains even for a single dropout + esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1; + esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1; + + if (_bdshot) { + esc_status.esc_online_flags |= _output_mask; + esc_status.esc_armed_flags |= _output_mask; + esc_status.esc_count = _dshot_esc_count; + + for (channel = 0; (channel < 8); channel++) { + if (up_bdshot_channel_status(channel) == 0) { + esc_status.esc_online_flags &= ~(1 << channel); + } + } + } + // ESC telem wrap around or bdshot update _telemetry->esc_status_pub.update(); @@ -302,8 +319,6 @@ int DShot::handle_new_bdshot_erpm(void) } - esc_status.esc_count = num_erpms; - return num_erpms; } @@ -780,7 +795,9 @@ int DShot::print_status() } /* Print dshot status */ - up_bdshot_status(); + if (_bdshot) { + up_bdshot_status(); + } return 0; } diff --git a/src/drivers/dshot/DShot.h b/src/drivers/dshot/DShot.h index 50b8d9eaa012..2dcab5696fe3 100644 --- a/src/drivers/dshot/DShot.h +++ b/src/drivers/dshot/DShot.h @@ -166,6 +166,7 @@ class DShot final : public ModuleBase, public OutputModuleInterface static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS}; uint32_t _output_mask{0}; + uint32_t _dshot_esc_count{0}; perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; From 3874b4c55d1ce4712f32403b67acec8b9de3645e Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sun, 28 Apr 2024 14:23:27 +0200 Subject: [PATCH 288/652] imxrt: move flexio irq handler to itcm --- .../px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld index 5d9cd8de738b..4968488245e5 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld @@ -6,6 +6,7 @@ *(.text.board_autoled_on) *(.text.clock_timer) *(.text.exception_common) +*(.text.flexio_irq_handler) *(.text.hrt_absolute_time) *(.text.hrt_call_enter) *(.text.hrt_tim_isr) From ff6966da5761f2c0697e962551e7918a55ff9fed Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 1 May 2024 16:59:21 +0200 Subject: [PATCH 289/652] imxrt: dshot fix erpm calculation by implementing 3-bit exponent and 9-bit period --- .../nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 31 ++++++++++++++----- src/drivers/dshot/DShot.cpp | 3 +- 2 files changed, 24 insertions(+), 10 deletions(-) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index d697234c9c46..cb92dd1209a3 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -361,8 +361,11 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi void up_bdshot_erpm(void) { uint32_t value; - uint32_t erpm; + uint32_t data; uint32_t csum_data; + uint8_t exponent; + uint16_t period; + uint16_t erpm; bdshot_parsed_recv_mask = 0; @@ -377,13 +380,13 @@ void up_bdshot_erpm(void) value = (value ^ (value >> 1)); /* Decode GCR */ - erpm = gcr_decode[value & 0x1fU]; - erpm |= gcr_decode[(value >> 5U) & 0x1fU] << 4U; - erpm |= gcr_decode[(value >> 10U) & 0x1fU] << 8U; - erpm |= gcr_decode[(value >> 15U) & 0x1fU] << 12U; + data = gcr_decode[value & 0x1fU]; + data |= gcr_decode[(value >> 5U) & 0x1fU] << 4U; + data |= gcr_decode[(value >> 10U) & 0x1fU] << 8U; + data |= gcr_decode[(value >> 15U) & 0x1fU] << 12U; /* Calculate checksum */ - csum_data = erpm; + csum_data = data; csum_data = csum_data ^ (csum_data >> 8U); csum_data = csum_data ^ (csum_data >> NIBBLES_SIZE); @@ -391,7 +394,19 @@ void up_bdshot_erpm(void) dshot_inst[channel].crc_error_cnt++; } else { - dshot_inst[channel].erpm = ~(erpm >> 4) & 0xFFF; + data = (data >> 4) & 0xFFF; + + if (data == 0xFFF) { + erpm = 0; + + } else { + exponent = ((data >> 9U) & 0x7U); /* 3 bit: exponent */ + period = (data & 0x1ffU); /* 9 bit: period base */ + period = period << exponent; /* Period in usec */ + erpm = ((1000000U * 60U / 100U + period / 2U) / period); + } + + dshot_inst[channel].erpm = erpm; bdshot_parsed_recv_mask |= (1 << channel); dshot_inst[channel].last_no_response_cnt = dshot_inst[channel].no_response_cnt; } @@ -408,7 +423,7 @@ void up_bdshot_erpm(void) int up_bdshot_get_erpm(uint8_t channel, int *erpm) { if (bdshot_parsed_recv_mask & (1 << channel)) { - *erpm = dshot_inst[channel].erpm; + *erpm = (int)dshot_inst[channel].erpm; return 0; } diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 26ad1d63b3f5..3582dab43c6c 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -312,8 +312,7 @@ int DShot::handle_new_bdshot_erpm(void) num_erpms++; esc_status.esc_online_flags |= 1 << channel; esc_status.esc[channel].timestamp = hrt_absolute_time(); - esc_status.esc[channel].esc_rpm = (erpm * 100) / - (_param_mot_pole_count.get() / 2); + esc_status.esc[channel].esc_rpm = (erpm * 100) / (_param_mot_pole_count.get() / 2); esc_status.esc[channel].actuator_function = _telemetry->actuator_functions[channel]; } From 7982f54a6accdd5f7821d51e87c7ea3b54450561 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Thu, 23 May 2024 13:18:25 +0200 Subject: [PATCH 290/652] dshot: refactoring --- src/drivers/dshot/DShot.cpp | 29 +++++++++++++---------------- src/drivers/dshot/DShot.h | 3 +-- 2 files changed, 14 insertions(+), 18 deletions(-) diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 3582dab43c6c..5fc7291db282 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -144,9 +144,9 @@ void DShot::enable_dshot_outputs(const bool enabled) } } - _bdshot = _param_bidirectional_enable.get(); + _bidirectional_dshot_enabled = _param_bidirectional_enable.get(); - int ret = up_dshot_init(_output_mask, dshot_frequency, _bdshot); + int ret = up_dshot_init(_output_mask, dshot_frequency, _bidirectional_dshot_enabled); if (ret < 0) { PX4_ERR("up_dshot_init failed (%i)", ret); @@ -160,8 +160,6 @@ void DShot::enable_dshot_outputs(const bool enabled) if (((1 << i) & _output_mask) == 0) { _mixing_output.disableFunction(i); - } else { - _dshot_esc_count++; } } @@ -173,7 +171,7 @@ void DShot::enable_dshot_outputs(const bool enabled) _outputs_initialized = true; - if (_bdshot) { + if (_bidirectional_dshot_enabled) { init_telemetry(NULL); } } @@ -263,12 +261,11 @@ int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelem void DShot::publish_esc_status(void) { esc_status_s &esc_status = _telemetry->esc_status_pub.get(); - uint8_t channel; // clear data of the esc that are offline - for (channel = 0; (channel < _telemetry->last_telemetry_index); channel++) { - if ((esc_status.esc_online_flags & (1 << channel)) == 0) { - memset(&esc_status.esc[channel], 0, sizeof(struct esc_report_s)); + for (int index = 0; (index < _telemetry->last_telemetry_index); index++) { + if ((esc_status.esc_online_flags & (1 << index)) == 0) { + memset(&esc_status.esc[index], 0, sizeof(struct esc_report_s)); } } @@ -276,14 +273,14 @@ void DShot::publish_esc_status(void) esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1; esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1; - if (_bdshot) { + if (_bidirectional_dshot_enabled) { esc_status.esc_online_flags |= _output_mask; esc_status.esc_armed_flags |= _output_mask; - esc_status.esc_count = _dshot_esc_count; + esc_status.esc_count = _telemetry->handler.numMotors(); - for (channel = 0; (channel < 8); channel++) { - if (up_bdshot_channel_status(channel) == 0) { - esc_status.esc_online_flags &= ~(1 << channel); + for (int index = 0; (index < esc_status.esc_count); index++) { + if (up_bdshot_channel_status(index) == 0) { + esc_status.esc_online_flags &= ~(1 << index); } } } @@ -544,7 +541,7 @@ void DShot::Run() need_to_publish = handle_new_telemetry_data(telem_update, _telemetry->handler.latestESCData()); } - if (_bdshot) { + if (_bidirectional_dshot_enabled) { // Add bdshot data to esc status need_to_publish += handle_new_bdshot_erpm(); } @@ -794,7 +791,7 @@ int DShot::print_status() } /* Print dshot status */ - if (_bdshot) { + if (_bidirectional_dshot_enabled) { up_bdshot_status(); } diff --git a/src/drivers/dshot/DShot.h b/src/drivers/dshot/DShot.h index 2dcab5696fe3..e60b33b86279 100644 --- a/src/drivers/dshot/DShot.h +++ b/src/drivers/dshot/DShot.h @@ -162,11 +162,10 @@ class DShot final : public ModuleBase, public OutputModuleInterface bool _outputs_initialized{false}; bool _outputs_on{false}; bool _waiting_for_esc_info{false}; - bool _bdshot{false}; + bool _bidirectional_dshot_enabled{false}; static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS}; uint32_t _output_mask{0}; - uint32_t _dshot_esc_count{0}; perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; From cd93e2982c417d1c853c9f171acf3e627bddd1f5 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 29 May 2024 17:20:07 +0200 Subject: [PATCH 291/652] dshot: telemetry esc_status use sequential numbering for each motor channel != telemetry_index, we've to count from 0 and increment for each enabled ESC --- src/drivers/dshot/DShot.cpp | 38 +++++++++++++++++++++++-------------- 1 file changed, 24 insertions(+), 14 deletions(-) diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 5fc7291db282..940019d9bf04 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -261,6 +261,7 @@ int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelem void DShot::publish_esc_status(void) { esc_status_s &esc_status = _telemetry->esc_status_pub.get(); + int telemetry_index = 0; // clear data of the esc that are offline for (int index = 0; (index < _telemetry->last_telemetry_index); index++) { @@ -270,17 +271,21 @@ void DShot::publish_esc_status(void) } // FIXME: mark all UART Telemetry ESC's as online, otherwise commander complains even for a single dropout + esc_status.esc_count = _telemetry->handler.numMotors(); esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1; esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1; if (_bidirectional_dshot_enabled) { - esc_status.esc_online_flags |= _output_mask; - esc_status.esc_armed_flags |= _output_mask; - esc_status.esc_count = _telemetry->handler.numMotors(); + for (unsigned i = 0; i < _num_outputs; i++) { + if (_mixing_output.isFunctionSet(i)) { + if (up_bdshot_channel_status(i)) { + esc_status.esc_online_flags |= 1 << i; + + } else { + esc_status.esc_online_flags &= ~(1 << i); + } - for (int index = 0; (index < esc_status.esc_count); index++) { - if (up_bdshot_channel_status(index) == 0) { - esc_status.esc_online_flags &= ~(1 << index); + ++telemetry_index; } } } @@ -295,8 +300,8 @@ void DShot::publish_esc_status(void) int DShot::handle_new_bdshot_erpm(void) { int num_erpms = 0; + int telemetry_index = 0; int erpm; - uint8_t channel; esc_status_s &esc_status = _telemetry->esc_status_pub.get(); esc_status.timestamp = hrt_absolute_time(); @@ -304,15 +309,20 @@ int DShot::handle_new_bdshot_erpm(void) esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_DSHOT; esc_status.esc_armed_flags = _outputs_on; - for (channel = 0; channel < 8; channel++) { - if (up_bdshot_get_erpm(channel, &erpm) == 0) { - num_erpms++; - esc_status.esc_online_flags |= 1 << channel; - esc_status.esc[channel].timestamp = hrt_absolute_time(); - esc_status.esc[channel].esc_rpm = (erpm * 100) / (_param_mot_pole_count.get() / 2); - esc_status.esc[channel].actuator_function = _telemetry->actuator_functions[channel]; + for (unsigned i = 0; i < _num_outputs; i++) { + if (_mixing_output.isFunctionSet(i)) { + if (up_bdshot_get_erpm(i, &erpm) == 0) { + num_erpms++; + esc_status.esc_online_flags |= 1 << telemetry_index; + esc_status.esc[telemetry_index].timestamp = hrt_absolute_time(); + esc_status.esc[telemetry_index].esc_rpm = (erpm * 100) / (_param_mot_pole_count.get() / 2); + esc_status.esc[telemetry_index].actuator_function = _telemetry->actuator_functions[telemetry_index]; + } + + ++telemetry_index; } + } return num_erpms; From 42f4e02d7ea7d9ce1ecd8ad86d0c556459365435 Mon Sep 17 00:00:00 2001 From: asimopunov <50725049+asimopunov@users.noreply.github.com> Date: Thu, 30 May 2024 16:52:19 +0400 Subject: [PATCH 292/652] bsondump: add check if bson document size is set to zero and set to decoded size (#23088) --- ROMFS/px4fmu_common/init.d/rcS | 7 ++ src/systemcmds/bsondump/bsondump.cpp | 162 +++++++++++++++++++++------ 2 files changed, 133 insertions(+), 36 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index c0b895a8fe8a..45efbfbc2b56 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -123,6 +123,13 @@ else set PARAM_FILE /fs/mtd_params fi + # Check if /fs/mtd_params is a valid BSON file + if ! bsondump docsize /fs/mtd_caldata + then + echo "New /fs/mtd_caldata size is:" + bsondump docsize /fs/mtd_caldata + fi + # # Load parameters. # diff --git a/src/systemcmds/bsondump/bsondump.cpp b/src/systemcmds/bsondump/bsondump.cpp index 50021eba147f..a7615d0143c2 100644 --- a/src/systemcmds/bsondump/bsondump.cpp +++ b/src/systemcmds/bsondump/bsondump.cpp @@ -36,19 +36,27 @@ #include #include +#include #include -static void print_usage(const char *reason = nullptr) +static void print_usage(const char *reason = nullptr, const char *command = nullptr) { if (reason) { PX4_ERR("%s", reason); } - PRINT_MODULE_DESCRIPTION("read BSON from a file and print in human form"); + PRINT_MODULE_DESCRIPTION("Utility to read BSON from a file and print or output document size."); - PRINT_MODULE_USAGE_NAME_SIMPLE("bsondump", "command"); - PRINT_MODULE_USAGE_ARG("", "File name", false); + if (command == nullptr || strcmp(command, "docsize") == 0) { + PRINT_MODULE_USAGE_NAME_SIMPLE("bsondump docsize", "command"); + PRINT_MODULE_USAGE_ARG("", "The BSON file to decode for document size.", false); + } + + if (command == nullptr) { + PRINT_MODULE_USAGE_NAME_SIMPLE("bsondump", "command"); + PRINT_MODULE_USAGE_ARG("", "The BSON file to decode and print.", false); + } } static int bson_print_callback(bson_decoder_t decoder, bson_node_t node) @@ -82,58 +90,140 @@ static int bson_print_callback(bson_decoder_t decoder, bson_node_t node) return -1; } +static int +bson_docsize_callback(bson_decoder_t decoder, bson_node_t node) +{ + + if (node->type == BSON_EOO) { + PX4_DEBUG("end of parameters"); + return 0; + } + + return 1; +} + extern "C" __EXPORT int bsondump_main(int argc, char *argv[]) { - if (argc != 2) { - print_usage(); + + if (argc < 2) { + print_usage("Invalid number of arguments."); + return -1; + } + + const char *command = argv[1]; + + if (strcmp(command, "docsize") == 0) { + + if (argc != 3) { + print_usage("Usage: bsondump docsize ", "docsize"); + return -1; + } + + const char *file_name = argv[2]; + int source_fd = open(file_name, O_RDONLY); + + if (source_fd < 0) { + PX4_ERR("open '%s' failed (%i)", file_name, errno); + return 1; + } + + bson_decoder_s decoder{}; + int result = -1; + + if (bson_decoder_init_file(&decoder, source_fd, bson_docsize_callback) == 0) { + + do { + result = bson_decoder_next(&decoder); + + } while (result > 0); + + PX4_INFO("DECODED_SIZE:%" PRId32 " SAVED_SIZE:%" PRId32 "\n", + decoder.total_decoded_size, decoder.total_document_size); + } + + close(source_fd); + + if (decoder.total_decoded_size != decoder.total_document_size && decoder.total_document_size == 0) { + + PX4_WARN("Mismatch in BSON sizes and saved size is zero. Setting document size to decoded size."); + + source_fd = open(file_name, O_RDWR); + + if (source_fd == -1) { + perror("Failed to re-open source file for reading and writing"); + return -1; + } + + // Modify the first 4 bytes with the correct decoded size + uint32_t corrected_size = decoder.total_decoded_size; + + if (lseek(source_fd, 0, SEEK_SET) == (off_t) -1) { + perror("Failed to seek to the beginning of the file"); + close(source_fd); + return -1; + } + + if (write(source_fd, &corrected_size, sizeof(corrected_size)) != sizeof(corrected_size)) { + perror("Failed to write the corrected size to the file"); + close(source_fd); + return -1; + } + + close(source_fd); + + return 1; + } + + return 0; + } else { - char *file_name = argv[1]; - if (file_name) { - int fd = open(file_name, O_RDONLY); + const char *file_name = argv[1]; - if (fd < 0) { - PX4_ERR("open '%s' failed (%i)", file_name, errno); - return 1; + int fd = open(file_name, O_RDONLY); - } else { - PX4_INFO_RAW("[bsondump] reading from %s\n", file_name); + if (fd < 0) { + PX4_ERR("open '%s' failed (%i)", file_name, errno); + return 1; - bson_decoder_s decoder{}; + } else { + PX4_INFO_RAW("[bsondump] reading from %s\n", file_name); - if (bson_decoder_init_file(&decoder, fd, bson_print_callback) == 0) { - PX4_INFO_RAW("BSON document size %" PRId32 "\n", decoder.total_document_size); + bson_decoder_s decoder{}; - int result = -1; + if (bson_decoder_init_file(&decoder, fd, bson_print_callback) == 0) { + PX4_INFO_RAW("BSON document size %" PRId32 "\n", decoder.total_document_size); - do { - result = bson_decoder_next(&decoder); + int result = -1; - } while (result > 0); + do { + result = bson_decoder_next(&decoder); - close(fd); + } while (result > 0); - if (result == 0) { - PX4_INFO_RAW("BSON decoded %" PRId32 " bytes (double:%" PRIu16 ", string:%" PRIu16 ", bin:%" PRIu16 ", bool:%" PRIu16 - ", int32:%" PRIu16 ", int64:%" PRIu16 ")\n", - decoder.total_decoded_size, - decoder.count_node_double, decoder.count_node_string, decoder.count_node_bindata, decoder.count_node_bool, - decoder.count_node_int32, decoder.count_node_int64); + close(fd); - return 0; + if (result == 0) { + PX4_INFO_RAW("BSON decoded %" PRId32 " bytes (double:%" PRIu16 ", string:%" PRIu16 ", bin:%" PRIu16 ", bool:%" PRIu16 + ", int32:%" PRIu16 ", int64:%" PRIu16 ")\n", + decoder.total_decoded_size, + decoder.count_node_double, decoder.count_node_string, decoder.count_node_bindata, decoder.count_node_bool, + decoder.count_node_int32, decoder.count_node_int64); - } else if (result == -ENODATA) { - PX4_WARN("no data"); - return -1; + return 0; - } else { - PX4_ERR("failed (%d)", result); - return -1; - } + } else if (result == -ENODATA) { + PX4_WARN("no data"); + return -1; + + } else { + PX4_ERR("failed (%d)", result); + return -1; } } } + } return -1; From 493c9e49dbd79596fe6bdc135229e80c49eb3b5e Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Thu, 30 May 2024 13:53:48 -0700 Subject: [PATCH 293/652] uORB: ORBSet don't allow duplicate insertion * fixes a small memory leak in uORBManager.cpp (if using ORB_COMMUNICATOR) --- platforms/common/uORB/ORBSet.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/platforms/common/uORB/ORBSet.hpp b/platforms/common/uORB/ORBSet.hpp index 28e283c7b9e7..967f6bd7e4b8 100644 --- a/platforms/common/uORB/ORBSet.hpp +++ b/platforms/common/uORB/ORBSet.hpp @@ -62,6 +62,11 @@ class ORBSet { Node **p; + // Don't allow duplicates to be inserted + if (find(node_name)) { + return; + } + if (_top == nullptr) { p = &_top; From c11c75d32e7cb2ec3e7e536a6b0671b1cff484ee Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 10:11:33 +0200 Subject: [PATCH 294/652] ekf2-mag: always add process noise until initial value --- src/modules/ekf2/EKF/covariance.cpp | 26 +++++++++++++++----------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 5190ad12139d..13f2399be5ff 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -163,22 +163,26 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag) { - // mag_I: add process noise - float mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.f, 1.f); - float mag_I_process_noise = sq(mag_I_sig); + // mag_I: add process noise + float mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.f, 1.f); + float mag_I_process_noise = sq(mag_I_sig); + + for (unsigned index = 0; index < State::mag_I.dof; index++) { + const unsigned i = State::mag_I.idx + index; - for (unsigned index = 0; index < State::mag_I.dof; index++) { - const unsigned i = State::mag_I.idx + index; + if (P(i, i) < sq(_params.mag_noise)) { P(i, i) += mag_I_process_noise; } + } + + // mag_B: add process noise + float mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.f, 1.f); + float mag_B_process_noise = sq(mag_B_sig); - // mag_B: add process noise - float mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.f, 1.f); - float mag_B_process_noise = sq(mag_B_sig); + for (unsigned index = 0; index < State::mag_B.dof; index++) { + const unsigned i = State::mag_B.idx + index; - for (unsigned index = 0; index < State::mag_B.dof; index++) { - const unsigned i = State::mag_B.idx + index; + if (P(i, i) < sq(_params.mag_noise)) { P(i, i) += mag_B_process_noise; } } From a6007e4b93b2a9561940e9bb31e8a4ae2cfc6fbc Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 10:17:42 +0200 Subject: [PATCH 295/652] ekf2-mag: turn around update_all_states condition Non-functional --- .../EKF/aid_sources/magnetometer/mag_fusion.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) 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 ad03b8533147..ddb0dd1fb3b2 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -103,7 +103,13 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima VectorState Kfusion = P * H / aid_src.innovation_variance[index]; - if (!update_all_states) { + if (update_all_states) { + if (!update_tilt) { + Kfusion(State::quat_nominal.idx + 0) = 0.f; + Kfusion(State::quat_nominal.idx + 1) = 0.f; + } + + } else { // zero non-mag Kalman gains if not updating all states // copy mag_I and mag_B Kalman gains @@ -116,11 +122,6 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima Kfusion.slice(State::mag_B.idx, 0) = K_mag_B; } - if (!update_tilt) { - Kfusion(State::quat_nominal.idx + 0) = 0.f; - Kfusion(State::quat_nominal.idx + 1) = 0.f; - } - if (measurementUpdate(Kfusion, H, aid_src.observation_variance[index], aid_src.innovation[index])) { fused[index] = true; limitDeclination(); From c3d984703c4c4a0b1cdcc83fff87dd234c554484 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 10:16:38 +0200 Subject: [PATCH 296/652] ekf2-mag: remove immediate declination fusion after reset --- .../aid_sources/magnetometer/mag_control.cpp | 61 ++++++------------- src/modules/ekf2/EKF/covariance.cpp | 5 +- src/modules/ekf2/EKF/ekf.h | 1 - 3 files changed, 21 insertions(+), 46 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 1601178cd296..0077736bb04f 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -59,13 +59,6 @@ void Ekf::controlMagFusion() return; } - // stop mag (require a reset before using again) if there was an external yaw reset (yaw estimator, GPS yaw, etc) - if (_mag_decl_cov_reset && (_state_reset_status.reset_count.quat != _state_reset_count_prev.quat)) { - ECL_INFO("yaw reset, stopping mag fusion to force reinitialization"); - stopMagFusion(); - resetMagCov(); - } - magSample mag_sample; if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) { @@ -154,11 +147,13 @@ void Ekf::controlMagFusion() // 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; + { - const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; + const bool mag_consistent_or_no_ne_aiding = _control_status.flags.mag_heading_consistent || !using_ne_aiding; const bool common_conditions_passing = _control_status.flags.mag - && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) + && ((_control_status.flags.yaw_align && mag_consistent_or_no_ne_aiding) || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) && !_control_status.flags.mag_fault && !_control_status.flags.mag_field_disturbed @@ -186,9 +181,8 @@ void Ekf::controlMagFusion() // if we are using 3-axis magnetometer fusion, but without external NE aiding, // then the declination must be fused as an observation to prevent long term heading drift // fusing declination when gps aiding is available is optional. - const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; _control_status.flags.mag_dec = _control_status.flags.mag - && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight); + && (!using_ne_aiding || !_control_status.flags.mag_aligned_in_flight); if (_control_status.flags.mag) { @@ -200,33 +194,22 @@ void Ekf::controlMagFusion() aid_src.time_last_fuse = _time_delayed_us; } else { - if (!_mag_decl_cov_reset) { - // After any magnetic field covariance reset event the earth field state - // covariances need to be corrected to incorporate knowledge of the declination - // before fusing magnetometer data to prevent rapid rotation of the earth field - // states for the first few observations. - fuseDeclination(0.02f); - _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, R_MAG, H, aid_src); - - } else { - // The normal sequence is to fuse the magnetometer data first before fusing - // declination angle at a higher uncertainty to allow some learning of - // declination angle over time. - const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; - const bool update_tilt = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, R_MAG, H, aid_src, update_all_states, update_tilt); - - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - if (update_all_states && update_tilt) { - _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); - } + // The normal sequence is to fuse the magnetometer data first before fusing + // declination angle at a higher uncertainty to allow some learning of + // declination angle over time. + const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; + const bool update_tilt = _control_status.flags.mag_3D; + fuseMag(mag_sample.mag, R_MAG, H, aid_src, update_all_states, update_tilt); + + // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned + if (update_all_states && update_tilt) { + _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); + } - if (_control_status.flags.mag_dec) { - fuseDeclination(0.5f); - } + if (_control_status.flags.mag_dec) { + fuseDeclination(0.5f); } } @@ -272,7 +255,6 @@ void Ekf::controlMagFusion() // activate fusion, reset mag states and initialize variance if first init or in flight reset if (!_control_status.flags.yaw_align || wmm_updated - || !_mag_decl_cov_reset || !_state.mag_I.longerThan(0.f) || (getStateVariance().min() < kMagVarianceMin) || (getStateVariance().min() < kMagVarianceMin) @@ -399,9 +381,6 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) resetMagHeading(mag); } - // earth field was reset to WMM, skip initial declination fusion - _mag_decl_cov_reset = true; - } else { // mag_B: reset _state.mag_B.zero(); diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 13f2399be5ff..a086a11700d3 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -308,10 +308,7 @@ void Ekf::resetAccelBiasCov() #if defined(CONFIG_EKF2_MAGNETOMETER) void Ekf::resetMagCov() { - if (_mag_decl_cov_reset) { - ECL_INFO("reset mag covariance"); - _mag_decl_cov_reset = false; - } + ECL_INFO("reset mag covariance"); P.uncorrelateCovarianceSetVariance(State::mag_I.idx, sq(_params.mag_noise)); P.uncorrelateCovarianceSetVariance(State::mag_B.idx, sq(_params.mag_noise)); diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 95add3dec9ce..8ec3c0698790 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -705,7 +705,6 @@ class Ekf final : public EstimatorInterface // used by magnetometer fusion mode selection bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable AlphaFilter _mag_heading_innov_lpf{0.1f}; - bool _mag_decl_cov_reset{false}; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event. uint8_t _nb_mag_3d_reset_available{0}; uint32_t _min_mag_health_time_us{1'000'000}; ///< magnetometer is marked as healthy only after this amount of time From 774b6ed3b8f7992f4a959b597e98213237a79196 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 10:44:55 +0200 Subject: [PATCH 297/652] ekf2-mag: do not use yaw emergency estimator to reset mag states On slowly moving vehicles (e.g.: boats, rovers), the yaw estimator has worse convergence than the main EKF. Resetting the mag states using the yaw estimator as reference can lead to poor heading. Also, the EKF can recover really well from initially incorrect mag states. --- .../EKF/aid_sources/magnetometer/mag_control.cpp | 16 ---------------- 1 file changed, 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 0077736bb04f..5d857100fa94 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -349,23 +349,7 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) * Vector3f(_mag_strength_gps, 0, 0); // mag_B: reset -#if defined(CONFIG_EKF2_GNSS) - - if (isYawEmergencyEstimateAvailable()) { - - const Dcmf R_to_earth = updateYawInRotMat(_yawEstimator.getYaw(), _R_to_earth); - const Dcmf R_to_body = R_to_earth.transpose(); - - // mag_B: reset using WMM and yaw estimator - _state.mag_B = mag - (R_to_body * mag_earth_pred); - - ECL_INFO("resetMagStates using yaw estimator"); - - } else if (!reset_heading && _control_status.flags.yaw_align) { -#else - if (!reset_heading && _control_status.flags.yaw_align) { -#endif // mag_B: reset using WMM const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); _state.mag_B = mag - (R_to_body * mag_earth_pred); From 6515935b529ca755cf5cce78bbb9879f3efc740a Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 10:48:23 +0200 Subject: [PATCH 298/652] ekf2-mag: do not limit the earth mag field estimate The EKF can recover from an initial bad earth mag field estimate. Constraining the field is not necessary and can lead to an unpredicted behavior of the filter. Declination fusion is safe to run even when the horizontal field is 0 --- .../aid_sources/magnetometer/mag_fusion.cpp | 76 ------------------- src/modules/ekf2/EKF/ekf.h | 2 - 2 files changed, 78 deletions(-) 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 ddb0dd1fb3b2..c1b88f674dd7 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -124,7 +124,6 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima if (measurementUpdate(Kfusion, H, aid_src.observation_variance[index], aid_src.innovation[index])) { fused[index] = true; - limitDeclination(); } } @@ -192,87 +191,12 @@ bool Ekf::fuseDeclination(float decl_sigma) _fault_status.flags.bad_mag_decl = !is_fused; - if (is_fused) { - limitDeclination(); - } - return is_fused; } return false; } -void Ekf::limitDeclination() -{ - const Vector3f mag_I_before = _state.mag_I; - - // get a reference value for the earth field declinaton and minimum plausible horizontal field strength - float decl_reference = NAN; - float h_field_min = 0.001f; - - if (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL - && (PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps) && PX4_ISFINITE(_mag_inclination_gps)) - ) { - decl_reference = _mag_declination_gps; - - // set to 50% of the horizontal strength from geo tables if location is known - h_field_min = fmaxf(h_field_min, 0.5f * _mag_strength_gps * cosf(_mag_inclination_gps)); - - } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) - && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) - ) { - // use parameter value if GPS isn't available - decl_reference = math::radians(_params.mag_declination_deg); - } - - if (!PX4_ISFINITE(decl_reference)) { - return; - } - - // do not allow the horizontal field length to collapse - this will make the declination fusion badly conditioned - // and can result in a reversal of the NE field states which the filter cannot recover from - // apply a circular limit - float h_field = sqrtf(_state.mag_I(0) * _state.mag_I(0) + _state.mag_I(1) * _state.mag_I(1)); - - if (h_field < h_field_min) { - if (h_field > 0.001f * h_field_min) { - const float h_scaler = h_field_min / h_field; - _state.mag_I(0) *= h_scaler; - _state.mag_I(1) *= h_scaler; - - } else { - // too small to scale radially so set to expected value - _state.mag_I(0) = 2.0f * h_field_min * cosf(decl_reference); - _state.mag_I(1) = 2.0f * h_field_min * sinf(decl_reference); - } - - h_field = h_field_min; - } - - // do not allow the declination estimate to vary too much relative to the reference value - constexpr float decl_tolerance = 0.5f; - const float decl_max = decl_reference + decl_tolerance; - const float decl_min = decl_reference - decl_tolerance; - const float decl_estimate = atan2f(_state.mag_I(1), _state.mag_I(0)); - - if (decl_estimate > decl_max) { - _state.mag_I(0) = h_field * cosf(decl_max); - _state.mag_I(1) = h_field * sinf(decl_max); - - } else if (decl_estimate < decl_min) { - _state.mag_I(0) = h_field * cosf(decl_min); - _state.mag_I(1) = h_field * sinf(decl_min); - } - - if ((mag_I_before - _state.mag_I).longerThan(0.01f)) { - ECL_DEBUG("declination limited mag I [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f] (decl: %.3f)", - (double)mag_I_before(0), (double)mag_I_before(1), (double)mag_I_before(2), - (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2), - (double)decl_reference - ); - } -} - float Ekf::calculate_synthetic_mag_z_measurement(const Vector3f &mag_meas, const Vector3f &mag_earth_predicted) { // theoretical magnitude of the magnetometer Z component value given X and Y sensor measurement and our knowledge diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 8ec3c0698790..bdf434af36d2 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -763,8 +763,6 @@ class Ekf final : public EstimatorInterface // argument passed in is the declination uncertainty in radians bool fuseDeclination(float decl_sigma); - // apply sensible limits to the declination and length of the NE mag field states estimates - void limitDeclination(); #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_AIRSPEED) From ee765e7859a0c50e7861ae562d9c5a417ac9d887 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 16:15:07 +0200 Subject: [PATCH 299/652] ekf2-mag: do not reset when NE aiding is active --- .../aid_sources/magnetometer/mag_control.cpp | 23 ++++--------------- .../aid_sources/magnetometer/mag_fusion.cpp | 4 ---- src/modules/ekf2/EKF/ekf.h | 1 - 3 files changed, 4 insertions(+), 24 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 5d857100fa94..2ab11454e263 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -216,26 +216,12 @@ void Ekf::controlMagFusion() const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); if (is_fusion_failing) { - if (_nb_mag_3d_reset_available > 0) { - // Data seems good, attempt a reset (mag states only unless mag_3D currently active) + if (!using_ne_aiding || !_control_status.flags.mag_aligned_in_flight) { ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = _time_delayed_us; - if (_control_status.flags.in_air) { - _nb_mag_3d_reset_available--; - } - - } else if (starting_conditions_passing) { - // Data seems good, but previous reset did not fix the issue - // something else must be wrong, declare the sensor faulty and stop the fusion - //_control_status.flags.mag_fault = true; - ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); - stopMagFusion(); - } else { - // A reset did not fix the issue but all the starting checks are not passing - // This could be a temporary issue, stop the fusion without declaring the sensor faulty ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); stopMagFusion(); } @@ -250,8 +236,6 @@ void Ekf::controlMagFusion() } else { if (starting_conditions_passing) { - _control_status.flags.mag = true; - // activate fusion, reset mag states and initialize variance if first init or in flight reset if (!_control_status.flags.yaw_align || wmm_updated @@ -265,16 +249,17 @@ void Ekf::controlMagFusion() resetMagStates(_mag_lpf.getState(), reset_heading); aid_src.time_last_fuse = _time_delayed_us; - _nb_mag_3d_reset_available = 2; if (reset_heading) { _control_status.flags.yaw_align = true; } + _control_status.flags.mag = true; + } else { if (fuseMag(mag_sample.mag, R_MAG, H, aid_src)) { ECL_INFO("starting %s fusion", AID_SRC_NAME); - _nb_mag_3d_reset_available = 2; + _control_status.flags.mag = true; } } } 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 c1b88f674dd7..474e654ec60d 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -149,10 +149,6 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima bool Ekf::fuseDeclination(float decl_sigma) { - if (!_control_status.flags.mag) { - return false; - } - float decl_measurement = NAN; if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index bdf434af36d2..c1542e8d046d 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -705,7 +705,6 @@ class Ekf final : public EstimatorInterface // used by magnetometer fusion mode selection bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable AlphaFilter _mag_heading_innov_lpf{0.1f}; - uint8_t _nb_mag_3d_reset_available{0}; uint32_t _min_mag_health_time_us{1'000'000}; ///< magnetometer is marked as healthy only after this amount of time estimator_aid_source3d_s _aid_src_mag{}; From 3dac9af09e429e0435425bd099f737d3a422470c Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 16:48:25 +0200 Subject: [PATCH 300/652] ekf2-mag: do not reset on WMM change when NE aiding is active The mag field states are observed. No need to reset them. --- .../ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 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 2ab11454e263..5be05364f7d9 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -180,15 +180,14 @@ void Ekf::controlMagFusion() // if we are using 3-axis magnetometer fusion, but without external NE aiding, // then the declination must be fused as an observation to prevent long term heading drift - // fusing declination when gps aiding is available is optional. - _control_status.flags.mag_dec = _control_status.flags.mag - && (!using_ne_aiding || !_control_status.flags.mag_aligned_in_flight); + const bool no_ne_aiding_or_pre_takeoff = !using_ne_aiding || !_control_status.flags.mag_aligned_in_flight; + _control_status.flags.mag_dec = _control_status.flags.mag && no_ne_aiding_or_pre_takeoff; if (_control_status.flags.mag) { if (continuing_conditions_passing && _control_status.flags.yaw_align) { - if (mag_sample.reset || checkHaglYawResetReq() || wmm_updated) { + if (mag_sample.reset || 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 = _time_delayed_us; @@ -216,7 +215,7 @@ void Ekf::controlMagFusion() const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); if (is_fusion_failing) { - if (!using_ne_aiding || !_control_status.flags.mag_aligned_in_flight) { + if (no_ne_aiding_or_pre_takeoff) { ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = _time_delayed_us; From 53210dd8f3725e298e85aaf5c333fcb022504ca4 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 22 May 2024 17:01:25 +0200 Subject: [PATCH 301/652] ekf2-mag: with NE aiding, constrain heading drift only before takeoff After takeoff, the heading is easily observable --- .../aid_sources/magnetometer/mag_control.cpp | 2 +- .../test/change_indication/ekf_gsf_reset.csv | 338 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 296 +++++++-------- 3 files changed, 318 insertions(+), 318 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 5be05364f7d9..458ca5c1db48 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -180,7 +180,7 @@ void Ekf::controlMagFusion() // 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.mag_aligned_in_flight; + 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; if (_control_status.flags.mag) { 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 7faff984e16f..6d57f7ba8743 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -220,172 +220,172 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 21790000,0.78,-0.016,-0.0032,-0.63,-0.0054,-0.0054,0.016,-0.0081,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 21890000,0.78,-0.016,-0.0033,-0.63,-0.006,-0.0063,0.016,-0.0088,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 21990000,0.78,-0.016,-0.0032,-0.63,-0.0059,-0.0035,0.017,-0.0082,-0.0069,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0058,0.0064,0.00027,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22190000,0.78,-0.016,-0.0032,-0.63,-0.0043,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22490000,0.78,-0.016,-0.0033,-0.63,-0.00016,-0.006,0.018,-0.0055,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0056,0.02,-0.0026,-0.0059,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0057,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0048,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00046,-0.043,-0.0096,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.048,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00037,-0.00011,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00053,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.044,-0.4,0.0006,0.0037,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0069,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,6.3e-05,0.0012,0.00059,0.0011,0.0012,1,1 -24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,6.3e-05,0.0012,0.00059,0.0011,0.0012,1,1 -24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,6.3e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0068,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.2e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.1e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.9e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,6.1e-05,0.0012,0.00057,0.0011,0.0012,1,1 -25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,6e-05,0.0012,0.00057,0.0011,0.0011,1,1 -25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00062,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,6e-05,0.0011,0.00057,0.0011,0.0011,1,1 -25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.9e-05,0.0011,0.00057,0.0011,0.0011,1,1 -25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1 -25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.061,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,5.7e-05,0.0011,0.00056,0.001,0.0011,1,1 -25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,5.6e-05,0.0011,0.00055,0.001,0.0011,1,1 -26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,5.5e-05,0.0011,0.00055,0.00098,0.0011,1,1 -26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,5.4e-05,0.001,0.00054,0.00094,0.001,1,1 -26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0058,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1 -26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1 -26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0066,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.9e-05,0.00093,0.0005,0.00084,0.00093,1,1 -26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,4.7e-05,0.00088,0.00048,0.0008,0.00088,1,1 -26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,4.4e-05,0.00082,0.00045,0.00074,0.00082,1,1 -26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,4.2e-05,0.00078,0.00042,0.00069,0.00077,1,1 -26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,4e-05,0.00073,0.00039,0.00065,0.00073,1,1 -26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00058,3.7e-05,0.00066,0.00036,0.00059,0.00066,1,1 -27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,3.4e-05,0.00059,0.00032,0.00053,0.00059,1,1 -27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.16,-0.036,0.47,-0.0075,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,3.2e-05,0.00055,0.00029,0.00049,0.00054,1,1 -27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,3.1e-05,0.00052,0.00026,0.00046,0.00051,1,1 -27390000,0.76,0.078,-0.033,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,3e-05,0.0005,0.00024,0.00044,0.00049,1,1 -27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.9e-05,0.00049,0.00022,0.00043,0.00048,1,1 -27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.9e-05,0.00048,0.0002,0.00042,0.00048,1,1 -27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.9e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.00041,2.9e-05,0.00048,0.00019,0.00042,0.00047,1,1 -27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.4e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0056,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.8e-05,0.00047,0.00018,0.00041,0.00047,1,1 -27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0056,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.8e-05,0.00047,0.00017,0.0004,0.00047,1,1 -27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0056,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.8e-05,0.00047,0.00016,0.0004,0.00046,1,1 -28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.0051,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2.7e-05,0.00046,0.00015,0.00039,0.00046,1,1 -28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.0051,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2.7e-05,0.00046,0.00015,0.00038,0.00045,1,1 -28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0048,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00014,0.00038,0.00045,1,1 -28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.7e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0046,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00014,0.00037,0.00045,1,1 -28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00045,1,1 -28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.1e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00044,1,1 -28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00044,1,1 -28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.2e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1 -28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1 -28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0039,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1 -29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29390000,0.78,7.3e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.6e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0034,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1 -29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.4e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1 -29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1 -29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00043,1,1 -29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.3e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1 -29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.003,-0.028,-0.027,0,0,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1 -29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1 -30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,0.0001,0.00036,0.00042,1,1 -30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.7e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,9.9e-05,0.00036,0.00042,1,1 -30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.7e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,9.8e-05,0.00036,0.00042,1,1 -30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.5e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.11,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.8e-05,0.00036,0.00042,1,1 -30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.4e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.7e-05,0.00036,0.00042,1,1 -30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-7.1e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.6e-05,0.00036,0.00042,1,1 -30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.6e-05,0.00036,0.00042,1,1 -30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.1e-06,0.075,-0.0097,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.5e-05,0.00036,0.00042,1,1 -30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,2.6e-05,0.00042,9.5e-05,0.00036,0.00042,1,1 -30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,2.6e-05,0.00042,9.4e-05,0.00036,0.00041,1,1 -31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,2.6e-05,0.00042,9.4e-05,0.00036,0.00041,1,1 -31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1 -31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1 -31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1 -31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00035,2.6e-05,0.00042,9.2e-05,0.00036,0.00041,1,1 -31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0039,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1 -31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.6,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1 -31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.0021,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1 -31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0015,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.00041,1,1 -31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00054,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.00041,1,1 -32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00015,-0.11,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.0004,1,1 -32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2.6e-05,0.00041,9.1e-05,0.00036,0.0004,1,1 -32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2.6e-05,0.00041,9e-05,0.00036,0.0004,1,1 -32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2.6e-05,0.00041,9e-05,0.00036,0.0004,1,1 -32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 -32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 -32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 -32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 -32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1 -32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1 -33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1 -33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1 -33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.7e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.5e-05,0.0004,8.9e-05,0.00035,0.00039,1,1 -33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.00096,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,2.4e-05,0.0004,8.6e-05,0.00032,0.00039,1,1 -33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00044,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,2.1e-05,0.00039,7.7e-05,0.00024,0.00039,1,1 -33590000,0.99,-0.0082,-2.9e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,1.7e-05,0.00039,6.3e-05,0.00015,0.00039,1,1 -33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.1e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00017,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,1.4e-05,0.00039,5e-05,9.7e-05,0.00038,1,1 -33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00053,-0.0066,-0.025,0,0,0.00015,0.0001,0.0024,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,1.3e-05,0.00038,3.7e-05,6.2e-05,0.00038,1,1 -33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00075,-0.0053,-0.025,0,0,0.00015,0.0001,0.0021,0.04,0.046,0.042,0.32,0.32,0.065,2.8e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5.1e-05,1.2e-05,0.00038,2.8e-05,4.2e-05,0.00038,1,1 -33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.8e-05,0.0018,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,1.1e-05,0.00038,2.1e-05,3e-05,0.00038,1,1 -34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.064,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0017,0.038,0.046,0.033,0.33,0.33,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,1.1e-05,0.00038,1.8e-05,2.4e-05,0.00038,1,1 -34190000,0.75,-0.014,0.0071,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0016,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,1.1e-05,0.00038,1.5e-05,1.9e-05,0.00038,1,1 -34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.7e-05,0.0015,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,1.1e-05,0.00038,1.3e-05,1.6e-05,0.00038,1,1 -34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0041,-0.11,-0.2,-0.044,0.46,8.9e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0015,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.5e-05,1.1e-05,0.00038,1.1e-05,1.4e-05,0.00038,1,1 -34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,4.7e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0014,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.4e-05,1.1e-05,0.00038,1e-05,1.2e-05,0.00038,1,1 -34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0039,-0.11,-0.2,-0.044,0.46,-5e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0014,0.057,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.2e-05,1e-05,0.00038,9.2e-06,1.1e-05,0.00038,1,1 -34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.5e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0014,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.2e-05,1e-05,0.00038,8.5e-06,9.9e-06,0.00038,1,1 -34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0014,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2.1e-05,1e-05,0.00038,7.9e-06,9.1e-06,0.00038,1,1 -34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.7e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0013,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2e-05,1e-05,0.00038,7.4e-06,8.4e-06,0.00038,1,1 -34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0013,0.091,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2e-05,1e-05,0.00038,7.1e-06,7.9e-06,0.00038,1,1 -35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00022,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0013,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.9e-05,1e-05,0.00038,6.7e-06,7.4e-06,0.00038,1,1 -35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00026,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0013,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.9e-05,1e-05,0.00038,6.4e-06,7e-06,0.00038,1,1 -35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0013,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,6.1e-06,6.6e-06,0.00038,1,1 -35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0013,0.13,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,5.9e-06,6.3e-06,0.00038,1,1 -35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00045,-0.0016,-0.025,0,0,0.00013,9.2e-05,0.0013,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,5.7e-06,6e-06,0.00038,1,1 -35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00042,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0013,0.15,0.21,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.5e-06,5.8e-06,0.00038,1,1 -35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00048,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0013,0.16,0.22,0.011,0.69,0.78,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.4e-06,5.6e-06,0.00038,1,1 -35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9.1e-05,0.0013,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.2e-06,5.3e-06,0.00038,1,1 -35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.0005,-0.0015,-0.025,0,0,0.00013,9e-05,0.0013,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.1e-06,5.2e-06,0.00038,1,1 -35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0015,-0.025,0,0,0.00013,9e-05,0.0013,0.19,0.27,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5e-06,5e-06,0.00037,1,1 -36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,9e-05,0.0013,0.21,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,1e-05,0.00038,4.9e-06,4.8e-06,0.00037,1,1 -36190000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0012,0.22,0.3,0.0086,0.97,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.8e-06,4.7e-06,0.00037,1,1 -36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00059,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0012,0.23,0.32,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.7e-06,4.6e-06,0.00037,1,1 -36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0012,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.6e-06,4.4e-06,0.00037,1,1 -36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00055,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.6e-06,4.3e-06,0.00037,1,1 -36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00059,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.28,0.37,0.0076,1.3,1.6,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.5e-06,4.2e-06,0.00037,1,1 -36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.4e-06,4.1e-06,0.00037,1,1 -36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00065,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.4e-06,4e-06,0.00037,1,1 -36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00068,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0012,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.3e-06,3.9e-06,0.00037,1,1 -36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0012,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.3e-06,3.9e-06,0.00037,1,1 -37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.6e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0012,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.8e-06,0.00037,1,1 -37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.6e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0012,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.7e-06,0.00037,1,1 -37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.0007,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.7e-06,0.00037,1,1 -37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00072,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.42,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.6e-06,0.00037,1,1 -37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.5e-06,0.00037,1,1 -37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.5e-06,0.00037,1,1 -37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.0012,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4e-06,3.4e-06,0.00037,1,1 -37790000,0.65,-0.0068,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.0012,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.5e-05,1e-05,0.00038,4e-06,3.4e-06,0.00037,1,1 -37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.068,0.0043,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.52,0.65,0.0065,3.3,4.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.3e-06,0.00037,1,1 -37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.54,0.67,0.0065,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.3e-06,0.00037,1,1 -38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.0012,0.56,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.2e-06,0.00037,1,1 -38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00079,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.58,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.2e-06,0.00037,1,1 -38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00079,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.0012,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.1e-06,0.00037,1,1 -38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0039,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.63,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.1e-06,0.00037,1,1 -38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.65,0.8,0.0065,5,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1 -38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.68,0.82,0.0065,5.4,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1 -38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.7,0.85,0.0065,5.7,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1 -38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00081,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.72,0.88,0.0065,6.1,7.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,2.9e-06,0.00037,1,1 -38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.00081,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.74,0.89,0.0065,6.5,8.2,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.8e-06,2.9e-06,0.00037,1,1 +22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22190000,0.78,-0.016,-0.0032,-0.63,-0.0043,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22490000,0.78,-0.016,-0.0033,-0.63,-0.00016,-0.006,0.018,-0.0055,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0056,0.02,-0.0026,-0.0059,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0057,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0048,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00046,-0.043,-0.0096,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.0059,0.00019,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00037,-0.00011,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00053,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.044,-0.4,0.0006,0.0037,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00058,0.0012,0.0012,1,1 +24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.9e-05,0.0012,0.00058,0.0012,0.0012,1,1 +24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0069,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0068,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.2e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.7e-05,0.0012,0.00057,0.0011,0.0012,1,1 +25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.7e-05,0.0012,0.00057,0.0011,0.0012,1,1 +25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.9e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,5.6e-05,0.0012,0.00057,0.0011,0.0012,1,1 +25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.5e-05,0.0012,0.00057,0.0011,0.0011,1,1 +25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00062,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.5e-05,0.0011,0.00057,0.0011,0.0011,1,1 +25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.4e-05,0.0011,0.00056,0.0011,0.0011,1,1 +25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.3e-05,0.0011,0.00056,0.001,0.0011,1,1 +25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.061,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,5.2e-05,0.0011,0.00056,0.001,0.0011,1,1 +25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,5.1e-05,0.0011,0.00055,0.001,0.0011,1,1 +26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,5e-05,0.0011,0.00055,0.00098,0.0011,1,1 +26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.035,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,4.9e-05,0.001,0.00054,0.00094,0.001,1,1 +26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0057,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,4.7e-05,0.001,0.00053,0.00091,0.00099,1,1 +26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,4.6e-05,0.00097,0.00051,0.00088,0.00096,1,1 +26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0065,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.4e-05,0.00093,0.00049,0.00084,0.00093,1,1 +26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,4.2e-05,0.00088,0.00047,0.0008,0.00088,1,1 +26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,3.9e-05,0.00082,0.00045,0.00074,0.00082,1,1 +26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,3.7e-05,0.00078,0.00042,0.00069,0.00077,1,1 +26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,3.5e-05,0.00073,0.00039,0.00065,0.00073,1,1 +26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00057,3.2e-05,0.00066,0.00035,0.00059,0.00066,1,1 +27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,2.9e-05,0.00059,0.00032,0.00053,0.00059,1,1 +27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.036,0.47,-0.0074,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,2.7e-05,0.00055,0.00029,0.00049,0.00054,1,1 +27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,2.6e-05,0.00052,0.00026,0.00046,0.00051,1,1 +27390000,0.76,0.078,-0.034,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,2.5e-05,0.0005,0.00023,0.00044,0.00049,1,1 +27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.4e-05,0.00049,0.00021,0.00043,0.00048,1,1 +27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.4e-05,0.00048,0.0002,0.00042,0.00048,1,1 +27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.9e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.0004,2.4e-05,0.00048,0.00018,0.00042,0.00047,1,1 +27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.4e-05,0.082,-0.026,-0.13,-0.17,-0.037,0.47,-0.0056,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.3e-05,0.00047,0.00017,0.00041,0.00047,1,1 +27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0056,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.3e-05,0.00047,0.00016,0.0004,0.00047,1,1 +27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0055,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.3e-05,0.00047,0.00016,0.0004,0.00046,1,1 +28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2.2e-05,0.00046,0.00015,0.00039,0.00046,1,1 +28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2.2e-05,0.00046,0.00014,0.00038,0.00045,1,1 +28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0047,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00014,0.00038,0.00045,1,1 +28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.7e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00013,0.00037,0.00045,1,1 +28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00013,0.00037,0.00045,1,1 +28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00012,0.00037,0.00044,1,1 +28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00012,0.00037,0.00044,1,1 +28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.2e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00044,0.00012,0.00037,0.00044,1,1 +28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.1e-05,0.00044,0.00011,0.00037,0.00044,1,1 +28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00044,1,1 +29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0036,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.0001,0.00037,0.00043,1,1 +29390000,0.78,7.2e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.6e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1 +29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1 +29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1 +29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.9e-05,0.00037,0.00043,1,1 +29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.2e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.8e-05,0.00037,0.00042,1,1 +29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.6e-05,0.00037,0.00042,1,1 +29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2e-05,0.00043,9.5e-05,0.00036,0.00042,1,1 +30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.5e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1 +30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1 +30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1 +30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.4e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1 +30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.3e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1 +30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-8.2e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1 +30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4.1e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9e-05,0.00036,0.00042,1,1 +30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.2e-06,0.075,-0.0096,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9e-05,0.00036,0.00042,1,1 +30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1 +30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1 +31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 +31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 +31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 +31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00034,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 +31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 +31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0038,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 +31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 +31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 +31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0014,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1 +31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00053,-0.12,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.14,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1 +32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00016,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 +32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 +32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 +32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2e-05,0.00041,8.4e-05,0.00036,0.0004,1,1 +32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 +32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 +33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 +33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 +33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1 +33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.0009,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,1.8e-05,0.0004,8e-05,0.00032,0.00039,1,1 +33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.6e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00041,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,1.5e-05,0.00039,7.3e-05,0.00024,0.00039,1,1 +33590000,0.99,-0.0082,-3.1e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,1.1e-05,0.00039,6e-05,0.00015,0.00039,1,1 +33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00018,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,8.4e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1 +33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00052,-0.0066,-0.025,0,0,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,6.8e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1 +33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.9e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00074,-0.0053,-0.025,0,0,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5.1e-05,5.9e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1 +33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.7e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,5.4e-06,0.00038,2.1e-05,3e-05,0.00038,1,1 +34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.065,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,5.1e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1 +34190000,0.75,-0.014,0.0071,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,4.9e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1 +34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.6e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,4.7e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1 +34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0041,-0.11,-0.2,-0.044,0.46,9e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.5e-05,4.6e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1 +34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,4.8e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.005,8.8e-05,2.3e-05,4.6e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1 +34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0039,-0.11,-0.2,-0.044,0.46,-4.8e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0012,0.056,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.2e-05,4.5e-06,0.00038,9e-06,1.1e-05,0.00038,1,1 +34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.5e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.1e-05,4.5e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1 +34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.067,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,4.4e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1 +34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.6e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,4.4e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1 +34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.3e-05,0.0012,0.09,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,4.3e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1 +35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00021,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0012,0.098,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,4.3e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1 +35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00025,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.3e-06,0.00038,6.2e-06,7e-06,0.00038,1,1 +35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.3e-06,0.00038,6e-06,6.6e-06,0.00038,1,1 +35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.13,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.2e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1 +35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00044,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.13,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.6e-06,6e-06,0.00037,1,1 +35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00041,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1 +35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1 +35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.17,0.23,0.01,0.73,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1 +35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.18,0.25,0.0096,0.78,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5e-06,5.2e-06,0.00037,1,1 +35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00046,-0.0016,-0.025,0,0,0.00013,9e-05,0.0011,0.19,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.9e-06,5e-06,0.00037,1,1 +36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.2,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1 +36190000,0.65,-0.0066,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.22,0.3,0.0086,0.96,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1 +36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.23,0.32,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1 +36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00057,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1 +36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00054,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,4.1e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1 +36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1 +36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1 +36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00064,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.3e-06,4e-06,0.00037,1,1 +36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00067,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.32,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 +36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 +37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0011,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1 +37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00068,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 +37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.5e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0011,0.39,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 +37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00071,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.41,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.6e-06,0.00037,1,1 +37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.6e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.43,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 +37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.2e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.45,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 +37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.042,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.47,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 +37790000,0.65,-0.0069,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.49,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 +37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.2e-05,0.068,0.0043,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.001,0.51,0.65,0.0065,3.3,4.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 +37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.001,0.53,0.67,0.0065,3.5,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 +38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.078,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.55,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1 +38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.001,0.58,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1 +38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.001,0.6,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 +38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0039,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.62,0.77,0.0065,4.6,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 +38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.64,0.8,0.0065,5,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 +38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.67,0.82,0.0065,5.3,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 +38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0045,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.69,0.85,0.0065,5.6,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 +38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.72,0.88,0.0065,6,7.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1 +38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.3e-05,0.001,0.73,0.89,0.0065,6.4,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.7e-06,2.9e-06,0.00037,1,1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 0ca0e5b75d9f..aac40d267e0d 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -201,151 +201,151 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 19890000,-0.28,0.015,-0.0052,0.96,-0.023,0.013,0.023,-0.02,0.01,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 19990000,-0.28,0.015,-0.0052,0.96,-0.02,0.014,0.021,-0.015,0.0093,0.012,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 20090000,-0.28,0.015,-0.0052,0.96,-0.023,0.017,0.021,-0.018,0.011,0.015,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20990000,-0.29,0.0064,0.0073,0.96,0.0086,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0057,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0041,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0098,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22590000,-0.29,0.015,-0.0054,0.96,-0.057,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 -23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.075,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0089,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00081,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0082,0.0099,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0083,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26990000,-0.29,0.015,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27490000,-0.29,0.02,-0.0069,0.96,0.071,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.05,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.064,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00011,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29890000,-0.29,0.015,-0.0025,0.96,0.07,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.095,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30590000,-0.29,0.016,-0.0031,0.96,0.061,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30790000,-0.29,0.016,-0.0032,0.96,0.052,-0.015,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.099,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0033,0.8,0.096,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31390000,-0.29,0.015,-0.003,0.96,0.035,0.0017,0.8,0.09,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31490000,-0.29,0.016,-0.0027,0.96,0.037,0.005,0.8,0.095,-0.037,-0.52,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0068,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-3e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,2.1e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31990000,-0.29,0.016,-0.0027,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,1.2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32090000,-0.29,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,8.1e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.006,-0.028,-0.0012,-0.0058,3.9e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.097,-0.0033,0.042,-0.0012,-0.0058,7.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32390000,-0.28,0.016,-0.0034,0.96,0.024,0.032,0.79,0.093,0.00041,0.12,-0.0012,-0.0058,5.9e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0081,0.12,-0.0012,-0.0058,3.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0011,0.1,-0.0012,-0.0058,-1.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32690000,-0.29,0.015,-0.0065,0.96,-0.0087,0.091,-0.082,0.091,0.0099,0.087,-0.0012,-0.0058,-1.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32790000,-0.29,0.015,-0.0063,0.96,-0.0048,0.09,-0.083,0.092,0.0024,0.072,-0.0012,-0.0058,-6.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32890000,-0.29,0.015,-0.0063,0.96,-0.0052,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32990000,-0.29,0.015,-0.0062,0.96,-0.0014,0.091,-0.084,0.092,-0.0019,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -33090000,-0.29,0.015,-0.0061,0.96,0.0025,0.097,-0.081,0.092,0.0074,0.036,-0.0013,-0.0058,-9.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -33190000,-0.29,0.015,-0.0061,0.96,0.0066,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0015,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0067,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.096,0.0026,0.0017,-0.0013,-0.0058,-2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.6e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0013,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0054,-0.028,-0.0013,-0.0058,-2.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.014,-0.032,-0.0013,-0.0057,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.0041,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.0061,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34390000,-0.29,0.015,-0.0053,0.96,0.043,0.096,-0.055,0.093,-0.018,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0082,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.091,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.096,-0.012,0.095,-0.0013,-0.0057,-3.6e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34790000,-0.29,0.014,-0.0052,0.96,0.052,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.6e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.095,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 +20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.6e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20990000,-0.29,0.0064,0.0073,0.96,0.0086,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.5e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0057,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0041,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0098,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22590000,-0.29,0.015,-0.0054,0.96,-0.057,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1 +22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1 +22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.075,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0089,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00081,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0082,0.0099,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0083,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26990000,-0.29,0.015,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27490000,-0.29,0.02,-0.0069,0.96,0.071,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.05,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.064,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29890000,-0.29,0.015,-0.0025,0.96,0.07,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.095,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30590000,-0.29,0.016,-0.0031,0.96,0.061,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30790000,-0.29,0.016,-0.0032,0.96,0.052,-0.015,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.099,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0032,0.8,0.096,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31390000,-0.29,0.015,-0.003,0.96,0.036,0.0017,0.8,0.09,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31490000,-0.29,0.016,-0.0027,0.96,0.037,0.0051,0.8,0.095,-0.037,-0.52,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0068,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-4.3e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31990000,-0.29,0.016,-0.0028,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,1.1e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32090000,-0.28,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,6.9e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.0059,-0.028,-0.0012,-0.0058,3.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.097,-0.0033,0.042,-0.0012,-0.0058,7.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32390000,-0.28,0.016,-0.0034,0.96,0.024,0.032,0.79,0.093,0.00043,0.12,-0.0012,-0.0058,5.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0081,0.12,-0.0012,-0.0058,3.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0012,0.1,-0.0012,-0.0058,-1.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32690000,-0.29,0.015,-0.0065,0.96,-0.0087,0.091,-0.082,0.091,0.0099,0.087,-0.0012,-0.0058,-1.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32790000,-0.29,0.015,-0.0063,0.96,-0.0048,0.09,-0.083,0.092,0.0024,0.072,-0.0012,-0.0058,-7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32890000,-0.29,0.015,-0.0063,0.96,-0.0052,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32990000,-0.29,0.015,-0.0062,0.96,-0.0014,0.091,-0.084,0.092,-0.0018,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33090000,-0.29,0.015,-0.0061,0.96,0.0025,0.097,-0.081,0.092,0.0074,0.036,-0.0013,-0.0058,-9.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33190000,-0.29,0.015,-0.0061,0.96,0.0066,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0015,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0067,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.096,0.0027,0.0017,-0.0013,-0.0058,-2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0013,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0054,-0.028,-0.0013,-0.0058,-2.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.014,-0.032,-0.0013,-0.0057,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.0041,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.0061,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34390000,-0.29,0.015,-0.0053,0.96,0.043,0.097,-0.055,0.093,-0.018,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0082,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.091,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.096,-0.012,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34790000,-0.29,0.014,-0.0052,0.96,0.052,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.095,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 From ca112fea8a8292e6892f7e551b4a3237779f6f05 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 31 May 2024 15:59:38 +0200 Subject: [PATCH 302/652] fix commander: make sure to count all valid mags in preflight check Previously, if a mag was not required (not index 0 and not used by ekf), it was not counted in num_enabled_and_valid_calibration. If a user set SYS_HAS_MAG to e.g. 3, it would then trigger a preflight failure, even if there were 3 calibrated and enabled mags. --- .../HealthAndArmingChecks/checks/magnetometerCheck.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/magnetometerCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/magnetometerCheck.cpp index 117a23a2b8d8..6716a8e06ad2 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/magnetometerCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/magnetometerCheck.cpp @@ -50,10 +50,6 @@ void MagnetometerChecks::checkAndReport(const Context &context, Report &reporter bool is_mag_fault = false; const bool is_required = instance == 0 || isMagRequired(instance, is_mag_fault); - if (!is_required) { - continue; - } - const bool exists = _sensor_mag_sub[instance].advertised(); bool is_valid = false; bool is_calibration_valid = false; @@ -83,6 +79,11 @@ void MagnetometerChecks::checkAndReport(const Context &context, Report &reporter reporter.setIsPresent(health_component_t::magnetometer); } + // Do not raise errors if a mag is not required + if (!is_required) { + continue; + } + const bool is_sensor_ok = is_valid && is_calibration_valid && !is_mag_fault; if (!is_sensor_ok) { From 0a665a526c9249b69c95c967106b30d74fd06383 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 27 May 2024 09:28:40 +0200 Subject: [PATCH 303/652] ekf2: add mag type init In this mode, the mag is used to inilialize the heading. During flight, the heading is predicted using gyros and corrected by GNSS measurements if available. --- .../EKF/aid_sources/magnetometer/mag_control.cpp | 4 +++- src/modules/ekf2/EKF/common.h | 3 ++- src/modules/ekf2/EKF2.cpp | 1 + src/modules/ekf2/module.yaml | 15 +++++++-------- 4 files changed, 13 insertions(+), 10 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 458ca5c1db48..2e288adfbc21 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -130,7 +130,9 @@ void Ekf::controlMagFusion() _innov_check_fail_status.flags.reject_mag_z = (aid_src.test_ratio[2] > 1.f); // determine if we should use mag fusion - bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) + bool continuing_conditions_passing = ((_params.mag_fusion_type == MagFuseType::INIT) + || (_params.mag_fusion_type == MagFuseType::AUTO) + || (_params.mag_fusion_type == MagFuseType::HEADING)) && _control_status.flags.tilt_align && (_control_status.flags.yaw_align || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) && mag_sample.mag.longerThan(0.f) diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 8624501cb261..845c2d4edbfb 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -101,7 +101,8 @@ enum MagFuseType : uint8_t { // Integer definitions for mag_fusion_type AUTO = 0, ///< The selection of either heading or 3D magnetometer fusion will be automatic HEADING = 1, ///< Simple yaw angle fusion will always be used. This is less accurate, but less affected by earth field distortions. It should not be used for pitch angles outside the range from -60 to +60 deg - NONE = 5 ///< Do not use magnetometer under any circumstance.. + NONE = 5, ///< Do not use magnetometer under any circumstance. + INIT = 6 ///< Use the mag for heading initialization only. }; #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 7cfefd9d2c26..2d15b7262cc9 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -769,6 +769,7 @@ void EKF2::VerifyParams() if ((_param_ekf2_mag_type.get() != MagFuseType::AUTO) && (_param_ekf2_mag_type.get() != MagFuseType::HEADING) && (_param_ekf2_mag_type.get() != MagFuseType::NONE) + && (_param_ekf2_mag_type.get() != MagFuseType::INIT) ) { mavlink_log_critical(&_mavlink_log_pub, "EKF2_MAG_TYPE invalid, resetting to default"); diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 9f2f83519637..77a6ab547dfa 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -401,19 +401,18 @@ parameters: heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading - fusion is used when on-ground and 3-axis magnetic field fusion in-flight - with fallback to magnetic heading fusion if there is insufficient motion - to make yaw or magnetic field states observable. If set to 'Magnetic heading' - magnetic heading fusion is used at all times. If set to 'None' the magnetometer - will not be used under any circumstance. If no external source of yaw is - available, it is possible to use post-takeoff horizontal movement combined - with GPS velocity measurements to align the yaw angle with the timer required - (depending on the amount of movement and GPS data quality). + fusion is used when on-ground and 3-axis magnetic field fusion in-flight. + If set to 'Magnetic heading' magnetic heading fusion is used at all times. + If set to 'None' the magnetometer will not be used under any circumstance. + If no external source of yaw is available, it is possible to use post-takeoff + horizontal movement combined with GNSS velocity measurements to align the yaw angle. + If set to 'Init' the magnetometer is only used to initalize the heading. type: enum values: 0: Automatic 1: Magnetic heading 5: None + 6: Init default: 0 reboot_required: true EKF2_MAG_ACCLIM: From 7fab93ede8eaf8814d0be9cac33c2fbe38ca50f5 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Sat, 1 Jun 2024 19:35:17 +0200 Subject: [PATCH 304/652] fmu-v6xrt: Fix flash configuration Fixes correct dummy cycle count of 20 --- boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_flash.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_flash.c b/boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_flash.c index 6ae7589d60ef..dfdf13da6dbe 100644 --- a/boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_flash.c +++ b/boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_flash.c @@ -104,9 +104,10 @@ const struct flexspi_nor_config_s g_flash_fast_config = { .busyBitPolarity = 0u, .lookupTable = { - /* Read */// EEH+11H+32bit addr+20dummy cycles+ 4Bytes read data //200Mhz 18 dummy=10+8 + /* Read */// EEH+11H+32bit addr+20dummy cycles+ 4Bytes read data + /* Macronix manual says 20 dummy cycles @ 200Mhz, FlexSPI peripheral Operand value needs to be 2N in DDR mode hence 0x28 */ [0 + 0] = FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0xEE, CMD_DDR, FLEXSPI_8PAD, 0x11), //0x871187ee, - [0 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, DUMMY_DDR, FLEXSPI_8PAD, 0x04),//0xb3048b20, + [0 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, DUMMY_DDR, FLEXSPI_8PAD, 0x28),//0xb3288b20, [0 + 2] = FLEXSPI_LUT_SEQ(READ_DDR, FLEXSPI_8PAD, 0x04, STOP_EXE, FLEXSPI_1PAD, 0x00), //0xa704, /* Read status */ From c22f725d858e93aeaa638dac41c28be42ddfb293 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 10 May 2024 17:09:43 +0200 Subject: [PATCH 305/652] fmu-v6xrt: Support RC telemetry --- boards/px4/fmu-v6xrt/src/board_config.h | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/px4/fmu-v6xrt/src/board_config.h b/boards/px4/fmu-v6xrt/src/board_config.h index a2edff8dabc8..059d0ac696d8 100644 --- a/boards/px4/fmu-v6xrt/src/board_config.h +++ b/boards/px4/fmu-v6xrt/src/board_config.h @@ -455,6 +455,7 @@ #define RC_SERIAL_SINGLEWIRE 1 // Suport Single wire wiring #define RC_SERIAL_SWAP_RXTX 1 // Set Swap (but not supported in HW) to use Single wire #define RC_SERIAL_SWAP_USING_SINGLEWIRE 1 // Set to use Single wire swap as HW does not support swap +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT /* FLEXSPI4 */ From de5087ae3ef45b6f54cb206bdf40909f8c626cfd Mon Sep 17 00:00:00 2001 From: Matteo Del Seppia <71389092+matteodelseppia@users.noreply.github.com> Date: Mon, 3 Jun 2024 21:10:28 +0200 Subject: [PATCH 306/652] Patch for issue #22818 (#23170) When calling "differential_drive stop" a missing return statement was causing a segmentation fault due to access to already freed memory. --- src/modules/differential_drive/DifferentialDrive.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/differential_drive/DifferentialDrive.cpp b/src/modules/differential_drive/DifferentialDrive.cpp index 70553ffeb369..a1d34e01e7d2 100644 --- a/src/modules/differential_drive/DifferentialDrive.cpp +++ b/src/modules/differential_drive/DifferentialDrive.cpp @@ -66,6 +66,7 @@ void DifferentialDrive::Run() if (should_exit()) { ScheduleClear(); exit_and_cleanup(); + return; } hrt_abstime now = hrt_absolute_time(); From de0e73d50577aa9460be78db0565ea425b4b5ef9 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Mon, 3 Jun 2024 19:43:26 -0600 Subject: [PATCH 307/652] vscode cmake-variants fix ark_septentrio-gps (#23222) --- .vscode/cmake-variants.yaml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index ef05fbdbae15..1311079ff988 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -151,16 +151,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_can-rtk-gps_canbootloader - ark_septentrio_gps_default: - short: ark_septentrio_gps_default + ark_septentrio-gps_default: + short: ark_septentrio-gps_default buildType: MinSizeRel settings: - CONFIG: ark_septentrio_gps_default - ark_septentrio_gps_canbootloader: - short: ark_septentrio_gps_canbootloader + CONFIG: ark_septentrio-gps_default + ark_septentrio-gps_canbootloader: + short: ark_septentrio-gps_canbootloader buildType: MinSizeRel settings: - CONFIG: ark_septentrio_gps_canbootloader + CONFIG: ark_septentrio-gps_canbootloader ark_cannode_default: short: ark_cannode_default buildType: MinSizeRel From a8617cf6817e063b56ceaad360186c41033aa785 Mon Sep 17 00:00:00 2001 From: Matteo Del Seppia <71389092+matteodelseppia@users.noreply.github.com> Date: Tue, 4 Jun 2024 03:48:38 +0200 Subject: [PATCH 308/652] Fix float and uint64_t comparison (#23199) fix: ControlAllocator float and int comparison bug There was an incorrect comparison between a float variable `dt` and a `uint64_t` value representing 5 milliseconds (`5_ms`). As a result, `do_update` could never become true even if the last torque setpoint was received more than 5 milliseconds before. To solve this, the `5_ms` value has been converted to seconds (0.005f) for the comparison with `dt`. --- src/modules/control_allocator/ControlAllocator.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index 2ead22c57079..3399bd619016 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -393,7 +393,7 @@ ControlAllocator::Run() if (_vehicle_thrust_setpoint_sub.update(&vehicle_thrust_setpoint)) { _thrust_sp = matrix::Vector3f(vehicle_thrust_setpoint.xyz); - if (dt > 5_ms) { + if (dt > 0.005f) { do_update = true; _timestamp_sample = vehicle_thrust_setpoint.timestamp_sample; } From 36ec576c0f32e9fb67cd97d983d50c23705008f2 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Mon, 3 Jun 2024 19:52:17 -0600 Subject: [PATCH 309/652] boards: ark-pi6x remove ekf delay param defaults (#23177) --- boards/ark/pi6x/init/rc.board_defaults | 9 --------- 1 file changed, 9 deletions(-) diff --git a/boards/ark/pi6x/init/rc.board_defaults b/boards/ark/pi6x/init/rc.board_defaults index 50c60d5f837a..717632839be8 100644 --- a/boards/ark/pi6x/init/rc.board_defaults +++ b/boards/ark/pi6x/init/rc.board_defaults @@ -32,19 +32,10 @@ then param set-default SENS_TEMP_ID 2490378 fi -param set-default EKF2_BARO_DELAY 39 -param set-default EKF2_BARO_NOISE 0.9 -param set-default EKF2_HGT_REF 0 -param set-default EKF2_MAG_DELAY 60 -param set-default EKF2_MAG_NOISE 0.06 param set-default EKF2_MULTI_IMU 2 param set-default EKF2_OF_CTRL 1 -param set-default EKF2_OF_DELAY 28 param set-default EKF2_OF_N_MIN 0.05 param set-default EKF2_RNG_A_HMAX 25 -param set-default EKF2_RNG_DELAY 105 -param set-default EKF2_RNG_NOISE 0.03 param set-default EKF2_RNG_QLTY_T 0.1 -param set-default EKF2_RNG_SFE 0.03 param set-default SENS_FLOW_RATE 150 From 22a38c0c6dc10ff51f0cf51a70d7f57eee043606 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Mon, 3 Jun 2024 18:15:00 -0800 Subject: [PATCH 310/652] drivers/imu: sch16t improvements (#23221) * individual perf counters for frame errors * don't treat saturation as an error * added parameters for gyro/accel LPF and decimation ratio --- .../murata/sch16t/Murata_SCH16T_registers.hpp | 102 +++++- src/drivers/imu/murata/sch16t/SCH16T.cpp | 313 ++++++++++++++---- src/drivers/imu/murata/sch16t/SCH16T.hpp | 31 +- src/drivers/imu/murata/sch16t/parameters.c | 46 +++ src/drivers/imu/murata/sch16t/sch16t_main.cpp | 2 +- 5 files changed, 413 insertions(+), 81 deletions(-) diff --git a/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp b/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp index 07d84dcb36e7..3d85c6eb012c 100644 --- a/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp +++ b/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp @@ -37,17 +37,101 @@ namespace Murata_SCH16T { -static constexpr uint32_t SPI_SPEED = 5 * 1000 * 1000; // 5 MHz SPI serial interface -static constexpr uint32_t SAMPLE_INTERVAL_US = 678; // 1500 Hz -- decimation factor 8, F_PRIM/16, 1.475 kHz -static constexpr uint16_t EOI = (1 << 1); // End of Initialization -static constexpr uint16_t EN_SENSOR = (1 << 0); // Enable RATE and ACC measurement -static constexpr uint16_t DRY_DRV_EN = (1 << 5); // Enables Data ready function -static constexpr uint16_t FILTER_BYPASS = (0b111); // Bypass filter -static constexpr uint16_t RATE_300DPS_1475HZ = 0b0'001'001'011'011'011; // Gyro XYZ range 300 deg/s @ 1475Hz -static constexpr uint16_t ACC12_8G_1475HZ = 0b0'001'001'011'011'011; // Acc XYZ range 8 G and 1475 update rate -static constexpr uint16_t ACC3_26G = (0b000 << 0); +// General definitions +static constexpr uint16_t EOI = (1 << 1); // End of Initialization +static constexpr uint16_t EN_SENSOR = (1 << 0); // Enable RATE and ACC measurement +static constexpr uint16_t DRY_DRV_EN = (1 << 5); // Enables Data ready function static constexpr uint16_t SPI_SOFT_RESET = (0b1010); +// Filter settings +static constexpr uint8_t FILTER_13_HZ = (0b010); +static constexpr uint8_t FILTER_30_HZ = (0b001); +static constexpr uint8_t FILTER_68_HZ = (0b000); +static constexpr uint8_t FILTER_280_HZ = (0b011); +static constexpr uint8_t FILTER_370_HZ = (0b100); +static constexpr uint8_t FILTER_235_HZ = (0b101); +static constexpr uint8_t FILTER_BYPASS = (0b111); + +// Dynamic range settings +static constexpr uint8_t RATE_RANGE_300 = (0b001); +static constexpr uint8_t ACC12_RANGE_80 = (0b001); +static constexpr uint8_t ACC3_RANGE_260 = (0b000); + +// Decimation ratio settings +static constexpr uint8_t DECIMATION_NONE = (0b000); +static constexpr uint8_t DECIMATION_5900_HZ = (0b001); +static constexpr uint8_t DECIMATION_2950_HZ = (0b010); +static constexpr uint8_t DECIMATION_1475_HZ = (0b011); +static constexpr uint8_t DECIMATION_738_HZ = (0b100); + +union CTRL_FILT_RATE_Register { + struct { + uint16_t FILT_SEL_RATE_X : 3; + uint16_t FILT_SEL_RATE_Y : 3; + uint16_t FILT_SEL_RATE_Z : 3; + uint16_t reserved : 7; + } bits; + + uint16_t value; +}; + +union CTRL_FILT_ACC12_Register { + struct { + uint16_t FILT_SEL_ACC_X12 : 3; + uint16_t FILT_SEL_ACC_Y12 : 3; + uint16_t FILT_SEL_ACC_Z12 : 3; + uint16_t reserved : 7; + } bits; + + uint16_t value; +}; + +union CTRL_FILT_ACC3_Register { + struct { + uint16_t FILT_SEL_ACC_X3 : 3; + uint16_t FILT_SEL_ACC_Y3 : 3; + uint16_t FILT_SEL_ACC_Z3 : 3; + uint16_t reserved : 7; + } bits; + + uint16_t value; +}; + +union RATE_CTRL_Register { + struct { + uint16_t DEC_RATE_X2 : 3; + uint16_t DEC_RATE_Y2 : 3; + uint16_t DEC_RATE_Z2 : 3; + uint16_t DYN_RATE_XYZ2: 3; + uint16_t DYN_RATE_XYZ1: 3; + uint16_t reserved : 1; + } bits; + + uint16_t value; +}; + +union ACC12_CTRL_Register { + struct { + uint16_t DEC_ACC_X2 : 3; + uint16_t DEC_ACC_Y2 : 3; + uint16_t DEC_ACC_Z2 : 3; + uint16_t DYN_ACC_XYZ2: 3; + uint16_t DYN_ACC_XYZ1: 3; + uint16_t reserved : 1; + } bits; + + uint16_t value; +}; + +union ACC3_CTRL_Register { + struct { + uint16_t DYN_ACC_XYZ3 : 3; + uint16_t reserved : 13; + } bits; + + uint16_t value; +}; + // Data registers #define RATE_X1 0x01 // 20 bit #define RATE_Y1 0x02 // 20 bit diff --git a/src/drivers/imu/murata/sch16t/SCH16T.cpp b/src/drivers/imu/murata/sch16t/SCH16T.cpp index 5a682bfe23bd..d7ed53f27c7a 100644 --- a/src/drivers/imu/murata/sch16t/SCH16T.cpp +++ b/src/drivers/imu/murata/sch16t/SCH16T.cpp @@ -44,6 +44,7 @@ static constexpr uint32_t POWER_ON_TIME = 250_ms; SCH16T::SCH16T(const I2CSPIDriverConfig &config) : SPI(config), I2CSPIDriver(config), + ModuleParams(nullptr), _px4_accel(get_device_id(), config.rotation), _px4_gyro(get_device_id(), config.rotation), _drdy_gpio(config.drdy_gpio) @@ -62,8 +63,11 @@ SCH16T::~SCH16T() perf_free(_reset_perf); perf_free(_bad_transfer_perf); perf_free(_perf_crc_bad); - perf_free(_perf_frame_bad); perf_free(_drdy_missed_perf); + perf_free(_perf_general_error); + perf_free(_perf_command_error); + perf_free(_perf_saturation_error); + perf_free(_perf_doing_initialization); } int SCH16T::init() @@ -104,9 +108,7 @@ int SCH16T::probe() PX4_INFO("COMP_ID:\t 0x%0x", comp_id); PX4_INFO("ASIC_ID:\t 0x%0x", asic_id); - // SCH16T-K01 - ID hex = 0x0020 - // SCH1633-B13 - ID hex = 0x0017 - bool success = asic_id == 0x20 && comp_id == 0x17; + bool success = asic_id == 0x21 && comp_id == 0x23; return success ? PX4_OK : PX4_ERROR; } @@ -145,8 +147,11 @@ void SCH16T::print_status() perf_print_counter(_reset_perf); perf_print_counter(_bad_transfer_perf); perf_print_counter(_perf_crc_bad); - perf_print_counter(_perf_frame_bad); perf_print_counter(_drdy_missed_perf); + perf_print_counter(_perf_general_error); + perf_print_counter(_perf_command_error); + perf_print_counter(_perf_saturation_error); + perf_print_counter(_perf_doing_initialization); } void SCH16T::RunImpl() @@ -186,6 +191,7 @@ void SCH16T::RunImpl() } case STATE::CONFIGURE: { + ConfigurationFromParameters(); Configure(); _state = STATE::LOCK_CONFIGURATION; @@ -215,7 +221,7 @@ void SCH16T::RunImpl() ScheduleDelayed(100_ms); // backup schedule as a watchdog timeout } else { - ScheduleOnInterval(SAMPLE_INTERVAL_US, SAMPLE_INTERVAL_US); + ScheduleOnInterval(_sample_interval_us, _sample_interval_us); } } else { @@ -233,7 +239,7 @@ void SCH16T::RunImpl() // scheduled from interrupt if _drdy_timestamp_sample was set as expected const hrt_abstime drdy_timestamp_sample = _drdy_timestamp_sample.fetch_and(0); - if ((now - drdy_timestamp_sample) < SAMPLE_INTERVAL_US) { + if ((now - drdy_timestamp_sample) < _sample_interval_us) { timestamp_sample = drdy_timestamp_sample; } else { @@ -241,7 +247,7 @@ void SCH16T::RunImpl() } // push backup schedule back - ScheduleDelayed(SAMPLE_INTERVAL_US * 2); + ScheduleDelayed(_sample_interval_us * 2); } // Collect the data @@ -279,48 +285,51 @@ void SCH16T::RunImpl() bool SCH16T::ReadData(SensorData *data) { - uint64_t temp = 0; - uint64_t gyro_x = 0; - uint64_t gyro_y = 0; - uint64_t gyro_z = 0; - uint64_t acc_x = 0; - uint64_t acc_y = 0; - uint64_t acc_z = 0; + // Register reads return 48bits. See SafeSpi 48bit out-of-frame protocol. + RegisterRead(RATE_X2); + uint64_t gyro_x = RegisterRead(RATE_Y2); + uint64_t gyro_y = RegisterRead(RATE_Z2); + uint64_t gyro_z = RegisterRead(ACC_X2); + uint64_t acc_x = RegisterRead(ACC_Y2); + uint64_t acc_y = RegisterRead(ACC_Z2); + uint64_t acc_z = RegisterRead(TEMP); + uint64_t temp = RegisterRead(TEMP); + + static constexpr uint64_t MASK48_GENERAL_ERROR = 0b00000000'00010000'00000000'00000000'00000000'00000000; + static constexpr uint64_t MASK48_COMMAND_ERROR = 0b00000000'00001000'00000000'00000000'00000000'00000000; + static constexpr uint64_t MASK48_SATURATION_ERROR = 0b00000000'00000100'00000000'00000000'00000000'00000000; + static constexpr uint64_t MASK48_DOING_INIT = 0b00000000'00000110'00000000'00000000'00000000'00000000; - // Data registers are 20bit 2s complement - RegisterRead(TEMP); - temp = RegisterRead(STAT_SUM_SAT); - _sensor_status.saturation = SPI48_DATA_UINT16(RegisterRead(RATE_X2)); - gyro_x = RegisterRead(RATE_Y2); - gyro_y = RegisterRead(RATE_Z2); - - // Check if ACC2 is saturated, if so, use ACC3 - if ((_sensor_status.saturation & STAT_SUM_SAT_ACC_X2) || (_sensor_status.saturation & STAT_SUM_SAT_ACC_Y2) - || (_sensor_status.saturation & STAT_SUM_SAT_ACC_Z2)) { - gyro_z = RegisterRead(ACC_X3); - acc_x = RegisterRead(ACC_Y3); - acc_y = RegisterRead(ACC_Z3); - acc_z = RegisterRead(TEMP); - _px4_accel.set_scale(1.f / 1600.f); - _px4_accel.set_range(260.f); - - } else { - gyro_z = RegisterRead(ACC_X2); - acc_x = RegisterRead(ACC_Y2); - acc_y = RegisterRead(ACC_Z2); - acc_z = RegisterRead(TEMP); - _px4_accel.set_scale(1.f / 3200.f); - _px4_accel.set_range(163.4f); - } - - static constexpr uint64_t MASK48_ERROR = 0x001E00000000UL; uint64_t values[] = { gyro_x, gyro_y, gyro_z, acc_x, acc_y, acc_z, temp }; for (auto v : values) { - // Check for frame errors - if (v & MASK48_ERROR) { - perf_count(_perf_frame_bad); + // [1b ][1b][ 2b ] + // [IDS][CE][S1:0] + // IDS: Internal Data Status indication. SCH16T uses this field to indicate common cause error. This is redundant, more accurate info + // is seen from sensor status (S1:S0). + // CE: Command Error indication. SCH16T reports only semantically invalid frame content using this field. SPI protocol + // level errors are indicated with High-Z on MISO pin. + // S1,0: Sensor status indication. + // 00: Normal operation + // 01: Error status + // 10: Saturation error + // 11: Initialization running + + if (v & MASK48_GENERAL_ERROR) { + perf_count(_perf_general_error); + return false; + + } else if (v & MASK48_COMMAND_ERROR) { + perf_count(_perf_command_error); + return false; + + } else if ((v & MASK48_DOING_INIT) == MASK48_DOING_INIT) { + perf_count(_perf_doing_initialization); return false; + + } else if (v & MASK48_SATURATION_ERROR) { + perf_count(_perf_saturation_error); + // Don't consider saturation an error } // Validate the CRC @@ -339,7 +348,6 @@ bool SCH16T::ReadData(SensorData *data) data->gyro_z = SPI48_DATA_INT32(gyro_z); // Temperature data is always 16 bits wide. Drop 4 LSBs as they are not used. data->temp = SPI48_DATA_INT32(temp) >> 4; - // Conver to PX4 coordinate system (FLU to FRD) data->acc_x = data->acc_x; data->acc_y = -data->acc_y; @@ -347,10 +355,210 @@ bool SCH16T::ReadData(SensorData *data) data->gyro_x = data->gyro_x; data->gyro_y = -data->gyro_y; data->gyro_z = -data->gyro_z; - return true; } +void SCH16T::ConfigurationFromParameters() +{ + // NOTE: We use ACC2 and RATE2 which are both decimated without interpolation + CTRL_FILT_RATE_Register filt_rate; + CTRL_FILT_ACC12_Register filt_acc12; + CTRL_FILT_ACC3_Register filt_acc3; + RATE_CTRL_Register rate_ctrl; + ACC12_CTRL_Register acc12_ctrl; + ACC3_CTRL_Register acc3_ctrl; + + // We always use the maximum dynamic range for gyro and accel + rate_ctrl.bits.DYN_RATE_XYZ1 = RATE_RANGE_300; + rate_ctrl.bits.DYN_RATE_XYZ2 = RATE_RANGE_300; + acc12_ctrl.bits.DYN_ACC_XYZ1 = ACC12_RANGE_80; + acc12_ctrl.bits.DYN_ACC_XYZ2 = ACC12_RANGE_80; + acc3_ctrl.bits.DYN_ACC_XYZ3 = ACC3_RANGE_260; + + _px4_gyro.set_range(math::radians(327.5f)); // 327.5 °/sec + _px4_gyro.set_scale(math::radians(1.f / 1600.f)); // 1600 LSB/(°/sec) + _px4_accel.set_range(163.4f); // 163.4 m/s2 + _px4_accel.set_scale(1.f / 3200.f); // 3200 LSB/(m/s2) + + // Gyro filter + switch (_sch16t_gyro_filt.get()) { + case 0: + filt_rate.bits.FILT_SEL_RATE_X = FILTER_13_HZ; + filt_rate.bits.FILT_SEL_RATE_Y = FILTER_13_HZ; + filt_rate.bits.FILT_SEL_RATE_Z = FILTER_13_HZ; + break; + + case 1: + filt_rate.bits.FILT_SEL_RATE_X = FILTER_30_HZ; + filt_rate.bits.FILT_SEL_RATE_Y = FILTER_30_HZ; + filt_rate.bits.FILT_SEL_RATE_Z = FILTER_30_HZ; + break; + + case 2: + filt_rate.bits.FILT_SEL_RATE_X = FILTER_68_HZ; + filt_rate.bits.FILT_SEL_RATE_Y = FILTER_68_HZ; + filt_rate.bits.FILT_SEL_RATE_Z = FILTER_68_HZ; + break; + + case 3: + filt_rate.bits.FILT_SEL_RATE_X = FILTER_235_HZ; + filt_rate.bits.FILT_SEL_RATE_Y = FILTER_235_HZ; + filt_rate.bits.FILT_SEL_RATE_Z = FILTER_235_HZ; + break; + + case 4: + filt_rate.bits.FILT_SEL_RATE_X = FILTER_280_HZ; + filt_rate.bits.FILT_SEL_RATE_Y = FILTER_280_HZ; + filt_rate.bits.FILT_SEL_RATE_Z = FILTER_280_HZ; + break; + + case 5: + filt_rate.bits.FILT_SEL_RATE_X = FILTER_370_HZ; + filt_rate.bits.FILT_SEL_RATE_Y = FILTER_370_HZ; + filt_rate.bits.FILT_SEL_RATE_Z = FILTER_370_HZ; + break; + + case 6: + filt_rate.bits.FILT_SEL_RATE_X = FILTER_BYPASS; + filt_rate.bits.FILT_SEL_RATE_Y = FILTER_BYPASS; + filt_rate.bits.FILT_SEL_RATE_Z = FILTER_BYPASS; + break; + } + + // ACC12 / ACC3 filter + switch (_sch16t_acc_filt.get()) { + case 0: + filt_acc12.bits.FILT_SEL_ACC_X12 = FILTER_13_HZ; + filt_acc12.bits.FILT_SEL_ACC_Y12 = FILTER_13_HZ; + filt_acc12.bits.FILT_SEL_ACC_Z12 = FILTER_13_HZ; + + filt_acc3.bits.FILT_SEL_ACC_X3 = FILTER_13_HZ; + filt_acc3.bits.FILT_SEL_ACC_Y3 = FILTER_13_HZ; + filt_acc3.bits.FILT_SEL_ACC_Z3 = FILTER_13_HZ; + break; + + case 1: + filt_acc12.bits.FILT_SEL_ACC_X12 = FILTER_30_HZ; + filt_acc12.bits.FILT_SEL_ACC_Y12 = FILTER_30_HZ; + filt_acc12.bits.FILT_SEL_ACC_Z12 = FILTER_30_HZ; + + filt_acc3.bits.FILT_SEL_ACC_X3 = FILTER_30_HZ; + filt_acc3.bits.FILT_SEL_ACC_Y3 = FILTER_30_HZ; + filt_acc3.bits.FILT_SEL_ACC_Z3 = FILTER_30_HZ; + break; + + case 2: + filt_acc12.bits.FILT_SEL_ACC_X12 = FILTER_68_HZ; + filt_acc12.bits.FILT_SEL_ACC_Y12 = FILTER_68_HZ; + filt_acc12.bits.FILT_SEL_ACC_Z12 = FILTER_68_HZ; + + filt_acc3.bits.FILT_SEL_ACC_X3 = FILTER_68_HZ; + filt_acc3.bits.FILT_SEL_ACC_Y3 = FILTER_68_HZ; + filt_acc3.bits.FILT_SEL_ACC_Z3 = FILTER_68_HZ; + break; + + case 3: + filt_acc12.bits.FILT_SEL_ACC_X12 = FILTER_235_HZ; + filt_acc12.bits.FILT_SEL_ACC_Y12 = FILTER_235_HZ; + filt_acc12.bits.FILT_SEL_ACC_Z12 = FILTER_235_HZ; + + filt_acc3.bits.FILT_SEL_ACC_X3 = FILTER_235_HZ; + filt_acc3.bits.FILT_SEL_ACC_Y3 = FILTER_235_HZ; + filt_acc3.bits.FILT_SEL_ACC_Z3 = FILTER_235_HZ; + break; + + case 4: + filt_acc12.bits.FILT_SEL_ACC_X12 = FILTER_280_HZ; + filt_acc12.bits.FILT_SEL_ACC_Y12 = FILTER_280_HZ; + filt_acc12.bits.FILT_SEL_ACC_Z12 = FILTER_280_HZ; + + filt_acc3.bits.FILT_SEL_ACC_X3 = FILTER_280_HZ; + filt_acc3.bits.FILT_SEL_ACC_Y3 = FILTER_280_HZ; + filt_acc3.bits.FILT_SEL_ACC_Z3 = FILTER_280_HZ; + break; + + case 5: + filt_acc12.bits.FILT_SEL_ACC_X12 = FILTER_370_HZ; + filt_acc12.bits.FILT_SEL_ACC_Y12 = FILTER_370_HZ; + filt_acc12.bits.FILT_SEL_ACC_Z12 = FILTER_370_HZ; + + filt_acc3.bits.FILT_SEL_ACC_X3 = FILTER_370_HZ; + filt_acc3.bits.FILT_SEL_ACC_Y3 = FILTER_370_HZ; + filt_acc3.bits.FILT_SEL_ACC_Z3 = FILTER_370_HZ; + break; + + case 6: + filt_acc12.bits.FILT_SEL_ACC_X12 = FILTER_BYPASS; + filt_acc12.bits.FILT_SEL_ACC_Y12 = FILTER_BYPASS; + filt_acc12.bits.FILT_SEL_ACC_Z12 = FILTER_BYPASS; + + filt_acc3.bits.FILT_SEL_ACC_X3 = FILTER_BYPASS; + filt_acc3.bits.FILT_SEL_ACC_Y3 = FILTER_BYPASS; + filt_acc3.bits.FILT_SEL_ACC_Z3 = FILTER_BYPASS; + break; + } + + // Gyro decimation (only affects channel 2, ie RATE2) + switch (_sch16t_decim.get()) { + case 0: + _sample_interval_us = 85; + rate_ctrl.bits.DEC_RATE_X2 = DECIMATION_NONE; + rate_ctrl.bits.DEC_RATE_Y2 = DECIMATION_NONE; + rate_ctrl.bits.DEC_RATE_Z2 = DECIMATION_NONE; + acc12_ctrl.bits.DEC_ACC_X2 = DECIMATION_NONE; + acc12_ctrl.bits.DEC_ACC_Y2 = DECIMATION_NONE; + acc12_ctrl.bits.DEC_ACC_Z2 = DECIMATION_NONE; + break; + + case 1: + _sample_interval_us = 169; + rate_ctrl.bits.DEC_RATE_X2 = DECIMATION_5900_HZ; + rate_ctrl.bits.DEC_RATE_Y2 = DECIMATION_5900_HZ; + rate_ctrl.bits.DEC_RATE_Z2 = DECIMATION_5900_HZ; + acc12_ctrl.bits.DEC_ACC_X2 = DECIMATION_5900_HZ; + acc12_ctrl.bits.DEC_ACC_Y2 = DECIMATION_5900_HZ; + acc12_ctrl.bits.DEC_ACC_Z2 = DECIMATION_5900_HZ; + break; + + case 2: + _sample_interval_us = 338; + rate_ctrl.bits.DEC_RATE_X2 = DECIMATION_2950_HZ; + rate_ctrl.bits.DEC_RATE_Y2 = DECIMATION_2950_HZ; + rate_ctrl.bits.DEC_RATE_Z2 = DECIMATION_2950_HZ; + acc12_ctrl.bits.DEC_ACC_X2 = DECIMATION_2950_HZ; + acc12_ctrl.bits.DEC_ACC_Y2 = DECIMATION_2950_HZ; + acc12_ctrl.bits.DEC_ACC_Z2 = DECIMATION_2950_HZ; + break; + + case 3: + _sample_interval_us = 678; + rate_ctrl.bits.DEC_RATE_X2 = DECIMATION_1475_HZ; + rate_ctrl.bits.DEC_RATE_Y2 = DECIMATION_1475_HZ; + rate_ctrl.bits.DEC_RATE_Z2 = DECIMATION_1475_HZ; + acc12_ctrl.bits.DEC_ACC_X2 = DECIMATION_1475_HZ; + acc12_ctrl.bits.DEC_ACC_Y2 = DECIMATION_1475_HZ; + acc12_ctrl.bits.DEC_ACC_Z2 = DECIMATION_1475_HZ; + break; + + case 4: + _sample_interval_us = 1355; + rate_ctrl.bits.DEC_RATE_X2 = DECIMATION_738_HZ; + rate_ctrl.bits.DEC_RATE_Y2 = DECIMATION_738_HZ; + rate_ctrl.bits.DEC_RATE_Z2 = DECIMATION_738_HZ; + acc12_ctrl.bits.DEC_ACC_X2 = DECIMATION_738_HZ; + acc12_ctrl.bits.DEC_ACC_Y2 = DECIMATION_738_HZ; + acc12_ctrl.bits.DEC_ACC_Z2 = DECIMATION_738_HZ; + break; + } + + _registers[0] = RegisterConfig(CTRL_FILT_RATE, filt_rate.value); + _registers[1] = RegisterConfig(CTRL_FILT_ACC12, filt_acc12.value); + _registers[2] = RegisterConfig(CTRL_FILT_ACC3, filt_acc3.value); + _registers[3] = RegisterConfig(CTRL_RATE, rate_ctrl.value); + _registers[4] = RegisterConfig(CTRL_ACC12, acc12_ctrl.value); + _registers[5] = RegisterConfig(CTRL_ACC3, acc3_ctrl.value); +} + void SCH16T::Configure() { for (auto &r : _registers) { @@ -359,15 +567,6 @@ void SCH16T::Configure() RegisterWrite(CTRL_USER_IF, DRY_DRV_EN); // Enable data ready RegisterWrite(CTRL_MODE, EN_SENSOR); // Enable the sensor - - // NOTE: we use ACC3 for the higher range. The DRDY frequency adjusts to whichever register bank is - // being sampled from (decimated vs interpolated outputs). RATE_XYZ2 is decimated and RATE_XYZ1 is interpolated. - _px4_gyro.set_range(math::radians(327.68f)); // +-/ 300°/sec calibrated range, 327.68°/sec electrical headroom (20bit) - _px4_gyro.set_scale(math::radians(1.f / 1600.f)); // scaling 1600 LSB/°/sec -> rad/s per LSB - - // ACC12 range is 163.4 m/s^2, 3200 LSB/(m/s^2), ACC3 range is 260 m/s^2, 1600 LSB/(m/s^2) - _px4_accel.set_range(163.4f); - _px4_accel.set_scale(1.f / 3200.f); } bool SCH16T::ValidateRegisterConfiguration() @@ -449,8 +648,6 @@ void SCH16T::RegisterWrite(uint8_t addr, uint16_t value) // The SPI protocol (SafeSPI) is 48bit out-of-frame. This means read return frames will be received on the next transfer. uint64_t SCH16T::TransferSpiFrame(uint64_t frame) { - set_frequency(SPI_SPEED); - uint16_t buf[3]; for (int index = 0; index < 3; index++) { diff --git a/src/drivers/imu/murata/sch16t/SCH16T.hpp b/src/drivers/imu/murata/sch16t/SCH16T.hpp index 6e390d70b7d8..3487bf115e0e 100644 --- a/src/drivers/imu/murata/sch16t/SCH16T.hpp +++ b/src/drivers/imu/murata/sch16t/SCH16T.hpp @@ -34,14 +34,14 @@ #pragma once #include "Murata_SCH16T_registers.hpp" - +#include #include #include #include using namespace Murata_SCH16T; -class SCH16T : public device::SPI, public I2CSPIDriver +class SCH16T : public device::SPI, public I2CSPIDriver, public ModuleParams { public: SCH16T(const I2CSPIDriverConfig &config); @@ -79,7 +79,7 @@ class SCH16T : public device::SPI, public I2CSPIDriver }; struct RegisterConfig { - RegisterConfig(uint16_t a, uint16_t v) + RegisterConfig(uint16_t a = 0, uint16_t v = 0) : addr(a) , value(v) {}; @@ -100,6 +100,8 @@ class SCH16T : public device::SPI, public I2CSPIDriver void ReadStatusRegisters(); void Configure(); + void ConfigurationFromParameters(); + void SoftwareReset(); void RegisterWrite(uint8_t addr, uint16_t value); @@ -131,19 +133,22 @@ class SCH16T : public device::SPI, public I2CSPIDriver READ, } _state{STATE::RESET_INIT}; - RegisterConfig _registers[6] = { - RegisterConfig(CTRL_FILT_RATE, FILTER_BYPASS), // Bypass filter - RegisterConfig(CTRL_FILT_ACC12, FILTER_BYPASS), // Bypass filter - RegisterConfig(CTRL_FILT_ACC3, FILTER_BYPASS), // Bypass filter - RegisterConfig(CTRL_RATE, RATE_300DPS_1475HZ), // +/- 300 deg/s, 1600 LSB/(deg/s) -- default, Decimation 8, 1475Hz - RegisterConfig(CTRL_ACC12, ACC12_8G_1475HZ), // +/- 80 m/s^2, 3200 LSB/(m/s^2) -- default, Decimation 8, 1475Hz - RegisterConfig(CTRL_ACC3, ACC3_26G) // +/- 260 m/s^2, 1600 LSB/(m/s^2) -- default - }; + RegisterConfig _registers[6]; + + uint32_t _sample_interval_us = 678; perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": reset")}; perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")}; perf_counter_t _perf_crc_bad{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": CRC8 bad"))}; - perf_counter_t _perf_frame_bad{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": Frame bad"))}; perf_counter_t _drdy_missed_perf{nullptr}; - + perf_counter_t _perf_general_error{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": general error"))}; + perf_counter_t _perf_command_error{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": command error"))}; + perf_counter_t _perf_saturation_error{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": saturation error"))}; + perf_counter_t _perf_doing_initialization{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": re-initializing"))}; + + DEFINE_PARAMETERS( + (ParamInt) _sch16t_gyro_filt, + (ParamInt) _sch16t_acc_filt, + (ParamInt) _sch16t_decim + ) }; diff --git a/src/drivers/imu/murata/sch16t/parameters.c b/src/drivers/imu/murata/sch16t/parameters.c index 205b2f020e08..85e6728f6461 100644 --- a/src/drivers/imu/murata/sch16t/parameters.c +++ b/src/drivers/imu/murata/sch16t/parameters.c @@ -42,3 +42,49 @@ * @value 1 Enabled */ PARAM_DEFINE_INT32(SENS_EN_SCH16T, 0); + +/** + * Gyro filter settings + * + * @value 0 13 Hz + * @value 1 30 Hz + * @value 2 68 Hz + * @value 3 235 Hz + * @value 4 280 Hz + * @value 5 370 Hz + * @value 6 No filter + * + * @reboot_required true + * + */ +PARAM_DEFINE_INT32(SCH16T_GYRO_FILT, 2); + +/** + * Accel filter settings + * + * @value 0 13 Hz + * @value 1 30 Hz + * @value 2 68 Hz + * @value 3 235 Hz + * @value 4 280 Hz + * @value 5 370 Hz + * @value 6 No filter + * + * @reboot_required true + * + */ +PARAM_DEFINE_INT32(SCH16T_ACC_FILT, 6); + +/** + * Gyro and Accel decimation settings + * + * @value 0 None + * @value 1 5900 Hz + * @value 2 2950 Hz + * @value 3 1475 Hz + * @value 4 738 Hz + * + * @reboot_required true + * + */ +PARAM_DEFINE_INT32(SCH16T_DECIM, 4); diff --git a/src/drivers/imu/murata/sch16t/sch16t_main.cpp b/src/drivers/imu/murata/sch16t/sch16t_main.cpp index a5ae892c9973..0f2341abd8b8 100644 --- a/src/drivers/imu/murata/sch16t/sch16t_main.cpp +++ b/src/drivers/imu/murata/sch16t/sch16t_main.cpp @@ -50,7 +50,7 @@ extern "C" int sch16t_main(int argc, char *argv[]) int ch; using ThisDriver = SCH16T; BusCLIArguments cli{false, true}; - cli.default_spi_frequency = SPI_SPEED; + cli.default_spi_frequency = 5000000; cli.spi_mode = SPIDEV_MODE0; while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { From 5fa3b9d86ae8e6f0378de4bf323d464cc4186946 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 16 May 2024 14:45:48 -0400 Subject: [PATCH 311/652] lib/world_magnetic_model: fetch_noaa_table.py refactor and scaling improvements - upate to NOAA grid API to build WMM table in one pass - refactor declination/inclination/totalintensity table printing to shared method - compute scaling factor to maximize resolution --- .../world_magnetic_model/fetch_noaa_table.py | 236 +- .../world_magnetic_model/generate_gtest.py | 2 +- .../geo_mag_declination.cpp | 16 +- .../geo_magnetic_tables.hpp | 152 +- .../world_magnetic_model/test_geo_lookup.cpp | 5300 ++++++++--------- .../test/change_indication/ekf_gsf_reset.csv | 644 +- .../ekf2/test/change_indication/iris_gps.csv | 560 +- 7 files changed, 3420 insertions(+), 3490 deletions(-) diff --git a/src/lib/world_magnetic_model/fetch_noaa_table.py b/src/lib/world_magnetic_model/fetch_noaa_table.py index 8914506f91c9..83ff3dda1e06 100755 --- a/src/lib/world_magnetic_model/fetch_noaa_table.py +++ b/src/lib/world_magnetic_model/fetch_noaa_table.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 ############################################################################ # -# Copyright (c) 2020-2023 PX4 Development Team. All rights reserved. +# Copyright (c) 2020-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 @@ -33,6 +33,7 @@ ############################################################################ import math +import numpy import json import statistics import sys @@ -49,7 +50,7 @@ def constrain(n, nmin, nmax): header = """/**************************************************************************** * - * Copyright (c) 2020-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-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 @@ -80,6 +81,9 @@ def constrain(n, nmin, nmax): * ****************************************************************************/ """ + +key=sys.argv[1] # NOAA key (https://www.ngdc.noaa.gov/geomag/CalcSurvey.shtml) + print(header) print('#include \n') @@ -97,188 +101,106 @@ def constrain(n, nmin, nmax): print('static constexpr int LON_DIM = {}'.format(LON_DIM) + ';') print('\n') -print('// *INDENT-OFF*') - -# Declination -params = urllib.parse.urlencode({'lat1': 0, 'lat2': 0, 'lon1': 0, 'lon2': 0, 'latStepSize': 1, 'lonStepSize': 1, 'magneticComponent': 'd', 'resultFormat': 'json'}) -key=sys.argv[1] # NOAA key (https://www.ngdc.noaa.gov/geomag/CalcSurvey.shtml) -f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params)) -data = json.loads(f.read()) -print("// Magnetic declination data in radians * 10^-4") -print('// Model: {},'.format(data['model'])) -print('// Version: {},'.format(data['version'])) -print('// Date: {},'.format(data['result'][0]['date'])) -print('static constexpr const int16_t declination_table[{}][{}]'.format(LAT_DIM, LON_DIM) + " {") -print('\t// LONGITUDE: ', end='') -for l in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES): - print('{0:6d},'.format(l), end='') -print('') - -declination_min = float('inf') -declination_max = float('-inf') -declination_min_lat_lon = () -declination_max_lat_lon = () - -for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES): - params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'd', 'resultFormat': 'json'}) - f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params)) - data = json.loads(f.read()) - - latitude_blackout_zone = False - - print('\t/* LAT: {0:3d} */'.format(latitude) + ' { ', end='') - for p in data['result']: - declination_rad = math.radians(p['declination']) - - warning = False +print('// *INDENT-OFF*\n\n\n') - try: - if p['warning']: - warning = True - latitude_blackout_zone = True - #print("WARNING black out zone!", p) - except: - pass - # declination in radians * 10^-4 - declination_int = constrain(int(round(declination_rad * 10000)), 32767, -32768) - print('{0:6d},'.format(declination_int), end='') +# build the world magnetic model dictionary +world_magnitude_model = {} # lat/lon dictionary with grid result - if (declination_rad > declination_max): - declination_max = declination_rad - declination_max_lat_lon = (p['latitude'], p['longitude']) - - if (declination_rad < declination_min): - declination_min = declination_rad - declination_min_lat_lon = (p['latitude'], p['longitude']) - - if latitude_blackout_zone: - print(' }, // WARNING! black out zone') - else: - print(' },') - -print("};") - -print('static constexpr float WMM_DECLINATION_MIN_RAD = {:.3f}; // latitude: {:.0f}, longitude: {:.0f}'.format(declination_min, declination_min_lat_lon[0], declination_min_lat_lon[1])) -print('static constexpr float WMM_DECLINATION_MAX_RAD = {:.3f}; // latitude: {:.0f}, longitude: {:.0f}'.format(declination_max, declination_max_lat_lon[0], declination_max_lat_lon[1])) -print("\n") - - -# Inclination -params = urllib.parse.urlencode({'lat1': 0, 'lat2': 0, 'lon1': 0, 'lon2': 0, 'latStepSize': 1, 'lonStepSize': 1, 'magneticComponent': 'i', 'resultFormat': 'json'}) -f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params)) +params = urllib.parse.urlencode({'lat1': 0, 'lon1': 0, 'resultFormat': 'json'}) +f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfwmm?key=%s&%s" % (key, params)) data = json.loads(f.read()) -print("// Magnetic inclination data in radians * 10^-4") -print('// Model: {},'.format(data['model'])) -print('// Version: {},'.format(data['version'])) -print('// Date: {},'.format(data['result'][0]['date'])) -print('static constexpr const int16_t inclination_table[{}][{}]'.format(LAT_DIM, LON_DIM) + " {") -print('\t// LONGITUDE: ', end='') -for l in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES): - print('{0:6d},'.format(l), end='') -print('') -inclination_min = float('inf') -inclination_max = float('-inf') -inclination_min_lat_lon = () -inclination_max_lat_lon = () +world_magnitude_model_units = data['units'] for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES): - params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'i', 'resultFormat': 'json'}) - f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params)) - data = json.loads(f.read()) + world_magnitude_model[latitude] = {} - latitude_blackout_zone = False + for longitude in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES): + params = urllib.parse.urlencode({'lat1': latitude, 'lon1': longitude, 'lon2': SAMPLING_MAX_LON, 'resultFormat': 'json'}) + f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfwmm?key=%s&%s" % (key, params)) + data = json.loads(f.read()) + #print(json.dumps(data, indent = 4)) # debugging - print('\t/* LAT: {0:3d} */'.format(latitude) + ' { ', end='') - for p in data['result']: - inclination_rad = math.radians(p['inclination']) + world_magnitude_model[latitude][longitude] = data['result'][0] + #print(world_magnitude_model[latitude][longitude]) - warning = False - try: - if p['warning']: - warning = True - latitude_blackout_zone = True - #print("WARNING black out zone!", p) +def print_wmm_table(key_name): - except: - pass + value_min = float('inf') + value_min_lat_lon = () - # inclination in radians * 10^-4 - inclination_int = constrain(int(round(inclination_rad * 10000)), 32767, -32768) - print('{0:6d},'.format(inclination_int), end='') + value_max = float('-inf') + value_max_lat_lon = () - if (inclination_rad > inclination_max): - inclination_max = inclination_rad - inclination_max_lat_lon = (p['latitude'], p['longitude']) + for latitude, lat_row in world_magnitude_model.items(): + #print(latitude, lat_row) + for longitude, result in lat_row.items(): + #print(result) - if (inclination_rad < inclination_min): - inclination_min = inclination_rad - inclination_min_lat_lon = (p['latitude'], p['longitude']) + value = float(result[key_name]) - if latitude_blackout_zone: - print(' }, // WARNING! black out zone') - else: - print(' },') + if (value > value_max): + value_max = value + value_max_lat_lon = (latitude, longitude) -print("};") + if (value < value_min): + value_min = value + value_min_lat_lon = (latitude, longitude) -print('static constexpr float WMM_INCLINATION_MIN_RAD = {:.3f}; // latitude: {:.0f}, longitude: {:.0f}'.format(inclination_min, inclination_min_lat_lon[0], inclination_min_lat_lon[1])) -print('static constexpr float WMM_INCLINATION_MAX_RAD = {:.3f}; // latitude: {:.0f}, longitude: {:.0f}'.format(inclination_max, inclination_max_lat_lon[0], inclination_max_lat_lon[1])) -print("\n") + # scale the values to fit into int16_t + value_scale_max = abs(numpy.iinfo(numpy.int16).max) / abs(value_max) + value_scale_min = abs(numpy.iinfo(numpy.int16).min) / abs(value_min) + value_scale = min(value_scale_max, value_scale_min) -# total intensity -params = urllib.parse.urlencode({'lat1': 0, 'lat2': 0, 'lon1': 0, 'lon2': 0, 'latStepSize': 1, 'lonStepSize': 1, 'magneticComponent': 'i', 'resultFormat': 'json'}) -f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params)) -data = json.loads(f.read()) -print("// Magnetic strength data in milli-Gauss * 10") -print('// Model: {},'.format(data['model'])) -print('// Version: {},'.format(data['version'])) -print('// Date: {},'.format(data['result'][0]['date'])) -print('static constexpr const int16_t strength_table[{}][{}]'.format(LAT_DIM, LON_DIM) + " {") -print('\t// LONGITUDE: ', end='') -for l in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES): - print('{0:5d},'.format(l), end='') -print('') + units_str = world_magnitude_model_units[key_name].split(' ')[0] -strength_min = float('inf') -strength_max = 0 -strength_min_lat_lon = () -strength_max_lat_lon = () -strength_sum = 0 -strength_sum_count = 0 + # print the table + print('// Magnetic {} data in {:.4g} {}'.format(key_name, 1.0 / value_scale, units_str)) + print('// Model: {},'.format(data['model'])) + print('// Version: {},'.format(data['version'])) + print('// Date: {},'.format(data['result'][0]['date'])) + print('static constexpr const int16_t {}_table[{}][{}]'.format(key_name, LAT_DIM, LON_DIM) + " {") + print('\t// LONGITUDE: ', end='') + for l in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES): + print('{0:6d},'.format(l), end='') + print('') -strength_list = [] + for latitude, lat_row in world_magnitude_model.items(): + print('\t/* LAT: {0:3d} */'.format(latitude) + ' { ', end='') + latitude_blackout_zone = False -for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES): - params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'f', 'resultFormat': 'json'}) - f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params)) - data = json.loads(f.read()) + for longitude, result in lat_row.items(): + + value = float(result[key_name]) + + # value scaled to fit into int16_t + value_int = int(round(value * value_scale)) + print('{0:6d},'.format(value_int), end='') - print('\t/* LAT: {0:3d} */'.format(latitude) + ' { ', end='') - for p in data['result']: + # blackout warning at this latitude + try: + if result['warning']: + latitude_blackout_zone = True - strength_gauss = p['totalintensity'] * 1e-3 - strength_list.append(strength_gauss) + except: + pass - totalintensity_int = int(round(p['totalintensity']/10)) - print('{0:5d},'.format(totalintensity_int), end='') + if latitude_blackout_zone: + print(' }, // WARNING! black out zone') + else: + print(' },') - if (strength_gauss > strength_max): - strength_max = strength_gauss - strength_max_lat_lon = (p['latitude'], p['longitude']) + print("};") - if (strength_gauss < strength_min): - strength_min = strength_gauss - strength_min_lat_lon = (p['latitude'], p['longitude']) + print('static constexpr float WMM_{}_SCALE_TO_{} = {:.9g}f;'.format(key_name.upper(), units_str.upper(), 1.0 / value_scale)) + print('static constexpr float WMM_{}_MIN_{} = {:.1f}f; // latitude: {:.0f}, longitude: {:.0f}'.format(key_name.upper(), units_str.upper(), value_min, value_min_lat_lon[0], value_min_lat_lon[1])) + print('static constexpr float WMM_{}_MAX_{} = {:.1f}f; // latitude: {:.0f}, longitude: {:.0f}'.format(key_name.upper(), units_str.upper(), value_max, value_max_lat_lon[0], value_max_lat_lon[1])) + print("\n") - print(' },') -print("};") -print('static constexpr float WMM_STRENGTH_MIN_GS = {:.1f}; // latitude: {:.0f}, longitude: {:.0f}'.format(strength_min, strength_min_lat_lon[0], strength_min_lat_lon[1])) -print('static constexpr float WMM_STRENGTH_MAX_GS = {:.1f}; // latitude: {:.0f}, longitude: {:.0f}'.format(strength_max, strength_max_lat_lon[0], strength_max_lat_lon[1])) -print('static constexpr float WMM_STRENGTH_MEAN_GS = {:.1f};'.format(statistics.mean(strength_list))) -print('static constexpr float WMM_STRENGTH_MEDIAN_GS = {:.1f};'.format(statistics.median(strength_list))) -print("\n") +print_wmm_table('declination') +print_wmm_table('inclination') +print_wmm_table('totalintensity') diff --git a/src/lib/world_magnetic_model/generate_gtest.py b/src/lib/world_magnetic_model/generate_gtest.py index bcf204a49c26..966e56a4bd02 100755 --- a/src/lib/world_magnetic_model/generate_gtest.py +++ b/src/lib/world_magnetic_model/generate_gtest.py @@ -44,7 +44,7 @@ header = """/**************************************************************************** * - * Copyright (c) 2020-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-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 diff --git a/src/lib/world_magnetic_model/geo_mag_declination.cpp b/src/lib/world_magnetic_model/geo_mag_declination.cpp index f40a77935004..97105f4a11e8 100644 --- a/src/lib/world_magnetic_model/geo_mag_declination.cpp +++ b/src/lib/world_magnetic_model/geo_mag_declination.cpp @@ -103,30 +103,34 @@ static constexpr float get_table_data(float lat, float lon, const int16_t table[ float get_mag_declination_radians(float lat, float lon) { - return get_table_data(lat, lon, declination_table) * 1e-4f; // declination table stored as 10^-4 radians + return math::radians(get_mag_declination_degrees(lat, lon)); } float get_mag_declination_degrees(float lat, float lon) { - return math::degrees(get_mag_declination_radians(lat, lon)); + // table stored as scaled degrees + return get_table_data(lat, lon, declination_table) * WMM_DECLINATION_SCALE_TO_DEGREES; } float get_mag_inclination_radians(float lat, float lon) { - return get_table_data(lat, lon, inclination_table) * 1e-4f; // inclination table stored as 10^-4 radians + return math::radians(get_mag_inclination_degrees(lat, lon)); } float get_mag_inclination_degrees(float lat, float lon) { - return math::degrees(get_mag_inclination_radians(lat, lon)); + // table stored as scaled degrees + return get_table_data(lat, lon, inclination_table) * WMM_INCLINATION_SCALE_TO_DEGREES; } float get_mag_strength_gauss(float lat, float lon) { - return get_table_data(lat, lon, strength_table) * 1e-4f; // strength table table stored as milli-Gauss * 10 + // 1 Gauss = 1e4 Tesla + return get_mag_strength_tesla(lat, lon) * 1e4f; } float get_mag_strength_tesla(float lat, float lon) { - return get_mag_strength_gauss(lat, lon) * 1e-4f; // 1 Gauss == 0.0001 Tesla + // table stored as scaled nanotesla + return get_table_data(lat, lon, totalintensity_table) * WMM_TOTALINTENSITY_SCALE_TO_NANOTESLA * 1e-9f; } diff --git a/src/lib/world_magnetic_model/geo_magnetic_tables.hpp b/src/lib/world_magnetic_model/geo_magnetic_tables.hpp index 3a1268ae400e..cba035c0e2f4 100644 --- a/src/lib/world_magnetic_model/geo_magnetic_tables.hpp +++ b/src/lib/world_magnetic_model/geo_magnetic_tables.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2020-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-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 @@ -44,95 +44,99 @@ static constexpr int LON_DIM = 37; // *INDENT-OFF* -// Magnetic declination data in radians * 10^-4 + + + +// Magnetic declination data in 0.005451 degrees // Model: WMM-2020, // Version: 0.5.1.11, -// Date: 2024.0684, +// Date: 2024.41257, static constexpr const int16_t declination_table[19][37] { // LONGITUDE: -180, -170, -160, -150, -140, -130, -120, -110, -100, -90, -80, -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 180, - /* LAT: -90 */ { 25949, 24204, 22458, 20713, 18968, 17222, 15477, 13732, 11986, 10241, 8496, 6750, 5005, 3260, 1514, -231, -1976, -3722, -5467, -7212, -8958,-10703,-12448,-14194,-15939,-17684,-19430,-21175,-22920,-24666,-26411,-28156,-29902, 31185, 29440, 27694, 25949, }, - /* LAT: -80 */ { 22511, 20385, 18448, 16677, 15039, 13502, 12039, 10628, 9254, 7905, 6573, 5255, 3947, 2642, 1334, 13, -1329, -2704, -4116, -5571, -7068, -8608,-10188,-11810,-13476,-15197,-16985,-18860,-20845,-22966,-25242,-27677,-30245, 29950, 27336, 24836, 22511, }, - /* LAT: -70 */ { 14988, 13587, 12457, 11491, 10618, 9783, 8939, 8049, 7095, 6075, 5005, 3913, 2830, 1777, 757, -252, -1291, -2401, -3608, -4915, -6302, -7737, -9189,-10634,-12063,-13481,-14912,-16402,-18033,-19960,-22502,-26331, 30582, 24088, 19617, 16858, 14988, }, // WARNING! black out zone - /* LAT: -60 */ { 8460, 8207, 7918, 7636, 7376, 7117, 6803, 6366, 5747, 4924, 3920, 2809, 1692, 671, -201, -952, -1680, -2508, -3524, -4735, -6077, -7455, -8781, -9992,-11055,-11951,-12664,-13158,-13330,-12882,-10766, -3382, 5057, 7748, 8493, 8605, 8460, }, // WARNING! black out zone - /* LAT: -50 */ { 5516, 5549, 5488, 5392, 5313, 5271, 5232, 5100, 4751, 4082, 3066, 1790, 453, -715, -1568, -2116, -2503, -2947, -3651, -4691, -5957, -7246, -8389, -9286, -9875,-10102, -9893, -9123, -7602, -5231, -2320, 430, 2541, 3966, 4841, 5314, 5516, }, - /* LAT: -40 */ { 3977, 4068, 4072, 4021, 3956, 3918, 3919, 3905, 3727, 3185, 2151, 702, -859, -2158, -2999, -3428, -3594, -3645, -3829, -4438, -5452, -6544, -7426, -7951, -8039, -7639, -6731, -5338, -3632, -1939, -487, 732, 1779, 2650, 3311, 3745, 3977, }, - /* LAT: -30 */ { 3003, 3088, 3113, 3092, 3028, 2945, 2881, 2845, 2716, 2229, 1178, -353, -1958, -3193, -3909, -4234, -4292, -4059, -3621, -3439, -3855, -4626, -5316, -5645, -5497, -4889, -3917, -2714, -1520, -590, 79, 677, 1305, 1916, 2433, 2801, 3003, }, - /* LAT: -20 */ { 2360, 2404, 2416, 2410, 2361, 2262, 2149, 2071, 1924, 1420, 347, -1155, -2629, -3669, -4175, -4268, -4043, -3462, -2592, -1820, -1589, -1975, -2627, -3080, -3097, -2722, -2080, -1269, -508, -33, 221, 519, 966, 1455, 1887, 2202, 2360, }, - /* LAT: -10 */ { 1966, 1959, 1931, 1919, 1885, 1794, 1677, 1582, 1396, 839, -238, -1623, -2888, -3693, -3930, -3676, -3084, -2295, -1450, -709, -266, -325, -809, -1310, -1509, -1409, -1091, -597, -111, 118, 156, 311, 689, 1139, 1545, 1841, 1966, }, - /* LAT: 0 */ { 1752, 1717, 1655, 1639, 1621, 1545, 1432, 1311, 1055, 430, -618, -1847, -2888, -3450, -3420, -2898, -2123, -1344, -699, -169, 235, 331, 37, -380, -627, -679, -580, -323, -41, 38, -35, 49, 397, 854, 1287, 1617, 1752, }, - /* LAT: 10 */ { 1612, 1619, 1571, 1581, 1601, 1545, 1414, 1220, 842, 124, -899, -1971, -2783, -3100, -2872, -2252, -1473, -767, -260, 116, 438, 577, 403, 80, -149, -257, -285, -210, -113, -163, -313, -290, 19, 487, 979, 1396, 1612, }, - /* LAT: 20 */ { 1419, 1567, 1624, 1712, 1794, 1768, 1605, 1296, 751, -104, -1144, -2086, -2666, -2757, -2413, -1803, -1092, -447, 5, 310, 566, 706, 607, 362, 166, 46, -53, -127, -214, -411, -655, -715, -474, -16, 534, 1059, 1419, }, - /* LAT: 30 */ { 1105, 1471, 1730, 1952, 2110, 2117, 1924, 1498, 769, -255, -1364, -2227, -2625, -2550, -2143, -1560, -904, -289, 167, 468, 696, 837, 810, 660, 512, 385, 219, -5, -297, -677, -1049, -1207, -1042, -608, -27, 584, 1105, }, - /* LAT: 40 */ { 732, 1317, 1812, 2206, 2456, 2499, 2283, 1748, 839, -380, -1603, -2452, -2759, -2599, -2149, -1556, -902, -275, 231, 591, 857, 1050, 1137, 1123, 1047, 895, 615, 189, -362, -974, -1493, -1732, -1610, -1189, -591, 77, 732, }, - /* LAT: 50 */ { 425, 1168, 1851, 2413, 2785, 2895, 2669, 2019, 887, -593, -1994, -2892, -3177, -2982, -2491, -1845, -1135, -440, 172, 674, 1088, 1437, 1711, 1876, 1891, 1695, 1235, 507, -401, -1306, -1977, -2253, -2123, -1682, -1054, -331, 425, }, - /* LAT: 60 */ { 203, 1050, 1857, 2558, 3072, 3295, 3093, 2299, 813, -1110, -2799, -3769, -4020, -3763, -3195, -2453, -1630, -793, 11, 759, 1447, 2073, 2610, 2999, 3148, 2946, 2284, 1141, -289, -1606, -2460, -2757, -2588, -2101, -1421, -635, 203, }, - /* LAT: 70 */ { -80, 847, 1743, 2546, 3170, 3479, 3255, 2178, 39, -2583, -4513, -5355, -5387, -4922, -4167, -3243, -2226, -1167, -98, 958, 1979, 2941, 3805, 4505, 4941, 4955, 4314, 2796, 566, -1545, -2828, -3261, -3103, -2582, -1848, -994, -80, }, // WARNING! black out zone - /* LAT: 80 */ { -944, -26, 822, 1513, 1909, 1772, 716, -1590, -4521, -6612, -7444, -7396, -6828, -5954, -4893, -3716, -2466, -1173, 144, 1465, 2775, 4055, 5282, 6422, 7420, 8182, 8523, 8052, 6011, 1989, -1732, -3421, -3747, -3398, -2713, -1863, -944, }, // WARNING! black out zone - /* LAT: 90 */ { -29255,-27510,-25765,-24019,-22274,-20529,-18783,-17038,-15293,-13547,-11802,-10057, -8311, -6566, -4821, -3075, -1330, 415, 2161, 3906, 5651, 7397, 9142, 10887, 12633, 14378, 16123, 17869, 19614, 21359, 23105, 24850, 26595, 28341, 30086,-31001,-29255, }, // WARNING! black out zone + /* LAT: -90 */ { 27264, 25429, 23595, 21761, 19926, 18092, 16258, 14423, 12589, 10754, 8920, 7086, 5251, 3417, 1583, -252, -2086, -3921, -5755, -7589, -9424,-11258,-13092,-14927,-16761,-18596,-20430,-22264,-24099,-25933,-27768,-29602,-31436, 32767, 30933, 29098, 27264, }, + /* LAT: -80 */ { 23650, 21416, 19382, 17521, 15799, 14184, 12647, 11165, 9721, 8303, 6904, 5519, 4143, 2772, 1397, 9, -1403, -2848, -4333, -5863, -7437, -9056,-10718,-12423,-14175,-15984,-17864,-19835,-21922,-24152,-26545,-29105,-31803, 31464, 28718, 26092, 23650, }, + /* LAT: -70 */ { 15755, 14282, 13094, 12077, 11159, 10281, 9392, 8457, 7454, 6381, 5257, 4109, 2971, 1865, 794, -267, -1359, -2527, -3797, -5172, -6632, -8142, -9669,-11188,-12690,-14181,-15686,-17253,-18969,-20997,-23675,-27707, 32110, 25303, 20617, 17720, 15755, }, // WARNING! black out zone + /* LAT: -60 */ { 8903, 8634, 8328, 8030, 7755, 7481, 7150, 6689, 6037, 5171, 4116, 2948, 1775, 704, -211, -998, -1763, -2635, -3706, -4982, -6396, -7846, -9240,-10513,-11630,-12572,-13320,-13839,-14019,-13549,-11322, -3523, 5353, 8167, 8943, 9057, 8903, }, // WARNING! black out zone + /* LAT: -50 */ { 5806, 5839, 5774, 5672, 5587, 5541, 5499, 5359, 4991, 4286, 3216, 1875, 470, -754, -1647, -2218, -2623, -3091, -3835, -4934, -6270, -7627, -8830, -9771,-10388,-10623,-10400, -9587, -7986, -5492, -2431, 460, 2679, 4178, 5097, 5594, 5806, }, + /* LAT: -40 */ { 4186, 4282, 4284, 4229, 4159, 4118, 4119, 4103, 3914, 3342, 2253, 728, -912, -2273, -3151, -3597, -3767, -3819, -4016, -4665, -5740, -6891, -7817, -8365, -8453, -8028, -7069, -5603, -3811, -2034, -509, 772, 1872, 2790, 3486, 3942, 4186, }, + /* LAT: -30 */ { 3161, 3250, 3275, 3251, 3182, 3094, 3026, 2988, 2851, 2337, 1229, -384, -2070, -3364, -4111, -4446, -4503, -4252, -3790, -3609, -4059, -4874, -5597, -5938, -5777, -5133, -4109, -2845, -1594, -619, 83, 710, 1372, 2016, 2561, 2948, 3161, }, + /* LAT: -20 */ { 2485, 2532, 2542, 2534, 2481, 2375, 2255, 2172, 2018, 1486, 353, -1228, -2777, -3865, -4390, -4481, -4240, -3623, -2707, -1902, -1669, -2082, -2768, -3241, -3254, -2856, -2179, -1328, -531, -35, 229, 542, 1013, 1529, 1985, 2318, 2485, }, + /* LAT: -10 */ { 2072, 2064, 2032, 2018, 1980, 1883, 1758, 1657, 1461, 874, -261, -1719, -3046, -3887, -4129, -3855, -3229, -2397, -1510, -734, -274, -342, -854, -1379, -1586, -1478, -1143, -624, -116, 121, 159, 321, 720, 1197, 1625, 1939, 2072, }, + /* LAT: 0 */ { 1847, 1810, 1742, 1723, 1703, 1621, 1500, 1371, 1102, 444, -660, -1952, -3043, -3628, -3589, -3035, -2219, -1401, -724, -169, 254, 350, 38, -401, -658, -711, -608, -338, -43, 36, -42, 45, 413, 896, 1354, 1703, 1847, }, + /* LAT: 10 */ { 1699, 1705, 1653, 1662, 1681, 1620, 1480, 1275, 878, 122, -954, -2080, -2929, -3256, -3012, -2356, -1536, -796, -265, 129, 466, 610, 425, 85, -155, -268, -299, -222, -121, -175, -335, -312, 14, 509, 1030, 1470, 1699, }, + /* LAT: 20 */ { 1494, 1649, 1708, 1799, 1884, 1855, 1681, 1355, 781, -117, -1209, -2197, -2803, -2893, -2528, -1885, -1137, -461, 13, 332, 601, 746, 640, 383, 178, 51, -55, -135, -228, -437, -694, -758, -503, -19, 561, 1114, 1494, }, + /* LAT: 30 */ { 1160, 1544, 1816, 2050, 2215, 2221, 2017, 1567, 802, -275, -1438, -2341, -2756, -2673, -2242, -1629, -939, -294, 184, 499, 738, 885, 855, 696, 542, 408, 230, -8, -317, -718, -1109, -1275, -1099, -642, -30, 613, 1160, }, + /* LAT: 40 */ { 765, 1379, 1900, 2314, 2577, 2622, 2393, 1831, 876, -403, -1685, -2574, -2892, -2722, -2248, -1623, -936, -278, 252, 629, 908, 1109, 1199, 1184, 1104, 944, 647, 195, -387, -1030, -1576, -1826, -1696, -1253, -625, 77, 765, }, + /* LAT: 50 */ { 437, 1218, 1936, 2528, 2919, 3036, 2799, 2116, 928, -623, -2091, -3030, -3327, -3121, -2604, -1925, -1180, -449, 193, 719, 1153, 1519, 1805, 1977, 1991, 1784, 1297, 527, -430, -1381, -2085, -2373, -2234, -1771, -1112, -355, 437, }, + /* LAT: 60 */ { 198, 1087, 1936, 2674, 3216, 3452, 3243, 2411, 855, -1158, -2926, -3941, -4206, -3936, -3339, -2560, -1696, -817, 27, 812, 1534, 2191, 2754, 3160, 3315, 3098, 2397, 1190, -317, -1699, -2593, -2902, -2725, -2214, -1502, -680, 198, }, + /* LAT: 70 */ { -111, 863, 1803, 2648, 3305, 3634, 3405, 2285, 58, -2678, -4700, -5589, -5627, -5143, -4352, -3383, -2317, -1205, -83, 1026, 2098, 3108, 4014, 4748, 5204, 5214, 4533, 2927, 575, -1644, -2988, -3441, -3276, -2730, -1962, -1068, -111, }, // WARNING! black out zone + /* LAT: 80 */ { -1054, -90, 801, 1527, 1946, 1812, 731, -1632, -4654, -6842, -7732, -7698, -7114, -6204, -5096, -3864, -2554, -1197, 184, 1572, 2947, 4292, 5581, 6779, 7828, 8630, 8988, 8486, 6313, 2026, -1910, -3677, -4009, -3636, -2914, -2019, -1054, }, // WARNING! black out zone + /* LAT: 90 */ { -30607,-28773,-26938,-25104,-23269,-21435,-19601,-17766,-15932,-14097,-12263,-10429, -8594, -6760, -4926, -3091, -1257, 578, 2412, 4246, 6081, 7915, 9749, 11584, 13418, 15253, 17087, 18921, 20756, 22590, 24424, 26259, 28093, 29928, 31762,-32441,-30607, }, // WARNING! black out zone }; -static constexpr float WMM_DECLINATION_MIN_RAD = -3.100; // latitude: 90, longitude: 170 -static constexpr float WMM_DECLINATION_MAX_RAD = 3.118; // latitude: -90, longitude: 150 +static constexpr float WMM_DECLINATION_SCALE_TO_DEGREES = 0.00545143529f; +static constexpr float WMM_DECLINATION_MIN_DEGREES = -176.9f; // latitude: 90, longitude: 170 +static constexpr float WMM_DECLINATION_MAX_DEGREES = 178.6f; // latitude: -90, longitude: 150 -// Magnetic inclination data in radians * 10^-4 +// Magnetic inclination data in 0.002699 degrees // Model: WMM-2020, // Version: 0.5.1.11, -// Date: 2024.0684, +// Date: 2024.41257, static constexpr const int16_t inclination_table[19][37] { // LONGITUDE: -180, -170, -160, -150, -140, -130, -120, -110, -100, -90, -80, -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 180, - /* LAT: -90 */ { -12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562,-12562, }, - /* LAT: -80 */ { -13644,-13510,-13349,-13169,-12975,-12774,-12571,-12371,-12181,-12005,-11849,-11715,-11605,-11519,-11455,-11414,-11394,-11396,-11423,-11477,-11561,-11676,-11821,-11995,-12194,-12412,-12641,-12874,-13102,-13314,-13500,-13649,-13752,-13802,-13798,-13743,-13644, }, - /* LAT: -70 */ { -14091,-13772,-13453,-13130,-12799,-12455,-12102,-11746,-11404,-11097,-10846,-10664,-10553,-10501,-10487,-10488,-10492,-10499,-10521,-10576,-10685,-10861,-11110,-11427,-11802,-12221,-12670,-13135,-13601,-14053,-14469,-14811,-14995,-14937,-14705,-14407,-14091, }, // WARNING! black out zone - /* LAT: -60 */ { -13509,-13155,-12816,-12483,-12140,-11768,-11353,-10900,-10434,-10006, -9680, -9510, -9511, -9650, -9853,-10040,-10158,-10193,-10174,-10157,-10205,-10369,-10664,-11078,-11581,-12140,-12727,-13324,-13913,-14474,-14971,-15259,-15076,-14687,-14279,-13884,-13509, }, // WARNING! black out zone - /* LAT: -50 */ { -12492,-12148,-11816,-11493,-11170,-10823,-10425, -9954, -9426, -8909, -8526, -8410, -8620, -9086, -9648,-10152,-10499,-10648,-10604,-10443,-10301,-10315,-10547,-10974,-11522,-12117,-12703,-13240,-13683,-13979,-14086,-14012,-13807,-13523,-13193,-12844,-12492, }, - /* LAT: -40 */ { -11239,-10888,-10538,-10191, -9852, -9514, -9155, -8732, -8213, -7652, -7235, -7210, -7686, -8518, -9438,-10259,-10906,-11324,-11443,-11256,-10906,-10641,-10650,-10946,-11416,-11922,-12363,-12679,-12833,-12837,-12748,-12613,-12435,-12204,-11917,-11588,-11239, }, - /* LAT: -30 */ { -9603, -9218, -8834, -8442, -8050, -7677, -7323, -6936, -6425, -5817, -5378, -5486, -6282, -7498, -8746, -9831,-10733,-11426,-11801,-11765,-11376,-10868,-10548,-10564,-10824,-11146,-11397,-11501,-11434,-11258,-11088,-10959,-10818,-10614,-10333, -9985, -9603, }, - /* LAT: -20 */ { -7374, -6924, -6499, -6068, -5624, -5196, -4810, -4404, -3842, -3160, -2729, -3025, -4173, -5803, -7426, -8778, -9823,-10578,-10993,-11002,-10618, -9994, -9442, -9212, -9270, -9434, -9570, -9580, -9403, -9133, -8945, -8869, -8775, -8573, -8256, -7840, -7374, }, - /* LAT: -10 */ { -4420, -3869, -3405, -2963, -2506, -2057, -1649, -1205, -588, 107, 447, -20, -1391, -3330, -5297, -6877, -7942, -8550, -8793, -8710, -8280, -7581, -6919, -6585, -6553, -6646, -6760, -6778, -6587, -6293, -6148, -6175, -6151, -5943, -5559, -5026, -4420, }, - /* LAT: 0 */ { -913, -272, 205, 613, 1033, 1448, 1832, 2262, 2833, 3397, 3578, 3047, 1712, -222, -2259, -3876, -4847, -5247, -5286, -5101, -4641, -3909, -3204, -2843, -2786, -2852, -2974, -3044, -2913, -2681, -2639, -2805, -2890, -2713, -2288, -1650, -913, }, - /* LAT: 10 */ { 2555, 3197, 3642, 3988, 4344, 4710, 5056, 5430, 5867, 6224, 6243, 5728, 4617, 3031, 1345, -3, -774, -994, -886, -639, -213, 438, 1072, 1402, 1466, 1428, 1331, 1240, 1281, 1380, 1291, 1002, 789, 851, 1205, 1815, 2555, }, - /* LAT: 20 */ { 5412, 5951, 6338, 6637, 6951, 7293, 7631, 7968, 8290, 8479, 8378, 7898, 7045, 5939, 4818, 3927, 3420, 3323, 3486, 3737, 4077, 4551, 5012, 5264, 5324, 5314, 5270, 5211, 5196, 5172, 4987, 4639, 4326, 4229, 4402, 4831, 5412, }, - /* LAT: 30 */ { 7567, 7945, 8266, 8551, 8860, 9206, 9559, 9893, 10162, 10266, 10112, 9680, 9044, 8331, 7675, 7174, 6895, 6867, 7019, 7236, 7488, 7793, 8083, 8256, 8315, 8334, 8340, 8330, 8304, 8215, 7986, 7624, 7260, 7036, 7020, 7218, 7567, }, - /* LAT: 40 */ { 9266, 9488, 9744, 10030, 10356, 10715, 11080, 11414, 11660, 11735, 11580, 11216, 10741, 10270, 9878, 9601, 9460, 9464, 9581, 9747, 9926, 10114, 10287, 10412, 10492, 10556, 10614, 10648, 10628, 10512, 10265, 9909, 9538, 9251, 9108, 9122, 9266, }, - /* LAT: 50 */ { 10802, 10922, 11123, 11391, 11713, 12065, 12416, 12729, 12947, 13002, 12861, 12563, 12200, 11857, 11585, 11403, 11315, 11317, 11388, 11494, 11611, 11729, 11847, 11964, 12083, 12208, 12324, 12396, 12383, 12253, 12003, 11672, 11331, 11046, 10857, 10777, 10802, }, - /* LAT: 60 */ { 12320, 12390, 12538, 12754, 13021, 13319, 13619, 13883, 14057, 14084, 13950, 13702, 13416, 13147, 12929, 12775, 12687, 12659, 12678, 12728, 12798, 12885, 12993, 13127, 13288, 13465, 13630, 13737, 13739, 13614, 13387, 13107, 12829, 12593, 12423, 12331, 12320, }, - /* LAT: 70 */ { 13757, 13796, 13888, 14027, 14204, 14404, 14610, 14790, 14895, 14879, 14747, 14549, 14334, 14132, 13960, 13826, 13734, 13680, 13663, 13677, 13720, 13794, 13899, 14037, 14205, 14393, 14577, 14716, 14759, 14683, 14520, 14321, 14127, 13963, 13842, 13772, 13757, }, // WARNING! black out zone - /* LAT: 80 */ { 14991, 15001, 15036, 15092, 15166, 15249, 15325, 15371, 15359, 15287, 15180, 15059, 14938, 14826, 14727, 14646, 14584, 14544, 14526, 14531, 14558, 14608, 14680, 14774, 14886, 15014, 15150, 15283, 15390, 15432, 15389, 15299, 15201, 15115, 15049, 15007, 14991, }, // WARNING! black out zone - /* LAT: 90 */ { 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, 15400, }, // WARNING! black out zone + /* LAT: -90 */ { -26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663,-26663, }, + /* LAT: -80 */ { -28959,-28675,-28333,-27951,-27540,-27113,-26682,-26258,-25854,-25482,-25150,-24867,-24633,-24450,-24315,-24226,-24183,-24188,-24245,-24361,-24539,-24783,-25092,-25462,-25884,-26346,-26833,-27328,-27812,-28262,-28656,-28973,-29191,-29297,-29287,-29170,-28959, }, + /* LAT: -70 */ { -29906,-29230,-28552,-27867,-27164,-26436,-25685,-24930,-24205,-23555,-23023,-22638,-22403,-22293,-22261,-22264,-22272,-22285,-22330,-22447,-22678,-23053,-23582,-24256,-25053,-25944,-26898,-27885,-28874,-29833,-30717,-31441,-31829,-31704,-31211,-30578,-29906, }, // WARNING! black out zone + /* LAT: -60 */ { -28675,-27922,-27202,-26495,-25766,-24977,-24097,-23135,-22147,-21240,-20551,-20191,-20196,-20492,-20922,-21317,-21564,-21635,-21592,-21554,-21657,-22006,-22635,-23517,-24587,-25775,-27023,-28290,-29540,-30732,-31788,-32398,-32004,-31178,-30310,-29471,-28675, }, // WARNING! black out zone + /* LAT: -50 */ { -26518,-25787,-25081,-24395,-23709,-22973,-22127,-21129,-20009,-18913,-18103,-17862,-18313,-19305,-20497,-21563,-22295,-22602,-22503,-22157,-21856,-21888,-22387,-23298,-24466,-25730,-26974,-28112,-29052,-29680,-29904,-29747,-29313,-28709,-28008,-27265,-26518, }, + /* LAT: -40 */ { -23859,-23111,-22367,-21631,-20911,-20195,-19433,-18535,-17434,-16245,-15366,-15320,-16340,-18110,-20062,-21801,-23168,-24048,-24290,-23883,-23136,-22578,-22605,-23240,-24242,-25316,-26251,-26918,-27243,-27250,-27062,-26776,-26401,-25910,-25300,-24601,-23859, }, + /* LAT: -30 */ { -20386,-19567,-18750,-17917,-17085,-16293,-15544,-14724,-13640,-12351,-11424,-11666,-13370,-15956,-18605,-20904,-22812,-24277,-25061,-24972,-24136,-23057,-22385,-22426,-22983,-23667,-24196,-24414,-24269,-23896,-23536,-23265,-22968,-22536,-21939,-21200,-20386, }, + /* LAT: -20 */ { -15655,-14695,-13789,-12872,-11930,-11023,-10206, -9346, -8156, -6711, -5803, -6449, -8904,-12373,-15815,-18676,-20887,-22480,-23348,-23356,-22530,-21203,-20034,-19551,-19678,-20026,-20313,-20331,-19954,-19380,-18986,-18828,-18633,-18206,-17535,-16650,-15655, }, + /* LAT: -10 */ { -9385, -8209, -7218, -6278, -5306, -4355, -3491, -2554, -1249, 222, 935, -75, -3005, -7132,-11304,-14645,-16891,-18169,-18676,-18490,-17568,-16077,-14672,-13969,-13905,-14103,-14342,-14377,-13970,-13348,-13045,-13109,-13066,-12627,-11813,-10677, -9385, }, + /* LAT: 0 */ { -1941, -572, 447, 1316, 2208, 3089, 3901, 4808, 6012, 7204, 7577, 6434, 3584, -534, -4855, -8273,-10317,-11152,-11228,-10827, -9842, -8280, -6784, -6023, -5903, -6042, -6299, -6446, -6167, -5676, -5592, -5955, -6145, -5775, -4872, -3514, -1941, }, + /* LAT: 10 */ { 5421, 6791, 7742, 8478, 9236, 10013, 10743, 11532, 12453, 13205, 13235, 12131, 9759, 6384, 2805, -45, -1666, -2121, -1883, -1354, -444, 946, 2291, 2989, 3125, 3048, 2844, 2651, 2737, 2945, 2751, 2128, 1664, 1792, 2543, 3843, 5421, }, + /* LAT: 20 */ { 11488, 12637, 13462, 14098, 14766, 15492, 16206, 16917, 17594, 17991, 17771, 16744, 14925, 12573, 10194, 8309, 7245, 7046, 7400, 7937, 8662, 9672, 10651, 11186, 11314, 11296, 11203, 11079, 11045, 10991, 10595, 9848, 9176, 8967, 9335, 10249, 11488, }, + /* LAT: 30 */ { 16064, 16869, 17552, 18157, 18813, 19547, 20295, 21001, 21567, 21785, 21452, 20532, 19178, 17663, 16272, 15213, 14627, 14573, 14900, 15364, 15901, 16550, 17167, 17534, 17662, 17704, 17719, 17697, 17639, 17449, 16959, 16185, 15409, 14931, 14899, 15320, 16064, }, + /* LAT: 40 */ { 19670, 20142, 20688, 21294, 21986, 22747, 23519, 24226, 24746, 24903, 24570, 23795, 22787, 21787, 20958, 20373, 20075, 20088, 20340, 20695, 21077, 21477, 21845, 22111, 22280, 22419, 22544, 22615, 22571, 22323, 21795, 21038, 20247, 19638, 19335, 19364, 19670, }, + /* LAT: 50 */ { 22933, 23187, 23612, 24182, 24864, 25609, 26354, 27016, 27477, 27593, 27291, 26658, 25888, 25162, 24586, 24201, 24016, 24023, 24176, 24404, 24654, 24906, 25156, 25404, 25658, 25925, 26171, 26324, 26295, 26017, 25483, 24780, 24056, 23451, 23049, 22878, 22933, }, + /* LAT: 60 */ { 26155, 26303, 26615, 27072, 27639, 28270, 28905, 29465, 29833, 29890, 29605, 29081, 28474, 27904, 27442, 27117, 26932, 26874, 26915, 27023, 27173, 27359, 27588, 27873, 28215, 28592, 28943, 29169, 29170, 28904, 28420, 27827, 27237, 26736, 26376, 26179, 26155, }, + /* LAT: 70 */ { 29204, 29286, 29480, 29773, 30146, 30572, 31008, 31388, 31612, 31580, 31301, 30883, 30427, 29998, 29634, 29351, 29155, 29043, 29006, 29037, 29130, 29287, 29511, 29805, 30163, 30562, 30953, 31246, 31335, 31173, 30826, 30404, 29992, 29643, 29386, 29237, 29204, }, // WARNING! black out zone + /* LAT: 80 */ { 31820, 31841, 31914, 32033, 32188, 32362, 32524, 32622, 32598, 32449, 32224, 31969, 31713, 31474, 31265, 31093, 30963, 30878, 30840, 30850, 30908, 31015, 31169, 31368, 31607, 31878, 32167, 32450, 32679, 32767, 32672, 32479, 32271, 32087, 31945, 31855, 31820, }, // WARNING! black out zone + /* LAT: 90 */ { 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, 32694, }, // WARNING! black out zone }; -static constexpr float WMM_INCLINATION_MIN_RAD = -1.526; // latitude: -60, longitude: 130 -static constexpr float WMM_INCLINATION_MAX_RAD = 1.543; // latitude: 80, longitude: 110 +static constexpr float WMM_INCLINATION_SCALE_TO_DEGREES = 0.00269892697f; +static constexpr float WMM_INCLINATION_MIN_DEGREES = -87.4f; // latitude: -60, longitude: 130 +static constexpr float WMM_INCLINATION_MAX_DEGREES = 88.4f; // latitude: 80, longitude: 110 -// Magnetic strength data in milli-Gauss * 10 +// Magnetic totalintensity data in 2.042 nanoTesla // Model: WMM-2020, // Version: 0.5.1.11, -// Date: 2024.0684, -static constexpr const int16_t strength_table[19][37] { - // LONGITUDE: -180, -170, -160, -150, -140, -130, -120, -110, -100, -90, -80, -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 180, - /* LAT: -90 */ { 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, 5442, }, - /* LAT: -80 */ { 6049, 5985, 5905, 5812, 5709, 5596, 5478, 5356, 5234, 5114, 5000, 4895, 4802, 4722, 4660, 4615, 4591, 4590, 4612, 4659, 4730, 4825, 4940, 5072, 5216, 5367, 5517, 5660, 5791, 5905, 5997, 6065, 6109, 6128, 6123, 6096, 6049, }, - /* LAT: -70 */ { 6294, 6159, 6007, 5841, 5661, 5468, 5263, 5048, 4829, 4615, 4413, 4231, 4074, 3943, 3840, 3764, 3718, 3706, 3735, 3813, 3942, 4124, 4354, 4623, 4919, 5227, 5531, 5815, 6064, 6268, 6418, 6512, 6553, 6544, 6493, 6407, 6294, }, - /* LAT: -60 */ { 6179, 5985, 5782, 5572, 5352, 5116, 4860, 4581, 4289, 4000, 3734, 3508, 3330, 3196, 3098, 3025, 2974, 2954, 2981, 3074, 3245, 3499, 3829, 4217, 4640, 5075, 5496, 5880, 6204, 6451, 6613, 6690, 6691, 6626, 6511, 6358, 6179, }, - /* LAT: -50 */ { 5838, 5606, 5373, 5140, 4907, 4661, 4390, 4087, 3758, 3427, 3126, 2888, 2728, 2638, 2590, 2555, 2520, 2492, 2498, 2572, 2750, 3045, 3445, 3920, 4428, 4934, 5408, 5826, 6163, 6403, 6540, 6579, 6535, 6423, 6260, 6060, 5838, }, - /* LAT: -40 */ { 5389, 5142, 4895, 4654, 4419, 4181, 3925, 3641, 3327, 3001, 2704, 2483, 2369, 2344, 2363, 2383, 2385, 2371, 2357, 2387, 2523, 2806, 3230, 3748, 4296, 4819, 5283, 5669, 5960, 6146, 6233, 6234, 6164, 6031, 5849, 5629, 5389, }, - /* LAT: -30 */ { 4876, 4633, 4393, 4157, 3930, 3711, 3491, 3260, 3004, 2728, 2471, 2291, 2224, 2250, 2317, 2387, 2451, 2498, 2517, 2528, 2600, 2807, 3178, 3672, 4204, 4700, 5114, 5427, 5628, 5727, 5752, 5725, 5645, 5511, 5331, 5113, 4876, }, - /* LAT: -20 */ { 4320, 4105, 3895, 3689, 3492, 3310, 3141, 2977, 2798, 2599, 2408, 2277, 2239, 2286, 2376, 2487, 2614, 2739, 2823, 2856, 2882, 2985, 3234, 3624, 4077, 4503, 4847, 5077, 5180, 5186, 5156, 5109, 5027, 4899, 4732, 4534, 4320, }, - /* LAT: -10 */ { 3789, 3627, 3472, 3325, 3190, 3069, 2965, 2872, 2773, 2657, 2535, 2437, 2396, 2424, 2514, 2644, 2799, 2955, 3075, 3134, 3147, 3177, 3307, 3565, 3894, 4216, 4478, 4637, 4669, 4616, 4548, 4485, 4398, 4273, 4123, 3959, 3789, }, - /* LAT: 0 */ { 3412, 3317, 3232, 3159, 3103, 3064, 3037, 3017, 2990, 2941, 2861, 2768, 2690, 2664, 2710, 2815, 2947, 3082, 3194, 3267, 3297, 3320, 3399, 3560, 3772, 3986, 4165, 4268, 4272, 4203, 4115, 4023, 3912, 3781, 3646, 3521, 3412, }, - /* LAT: 10 */ { 3282, 3250, 3229, 3224, 3248, 3294, 3348, 3399, 3432, 3421, 3352, 3238, 3113, 3022, 3000, 3044, 3126, 3225, 3325, 3409, 3473, 3536, 3626, 3746, 3884, 4024, 4143, 4212, 4212, 4149, 4038, 3895, 3733, 3573, 3437, 3339, 3282, }, - /* LAT: 20 */ { 3399, 3400, 3425, 3477, 3568, 3688, 3815, 3930, 4009, 4020, 3946, 3805, 3640, 3504, 3432, 3423, 3460, 3535, 3632, 3730, 3821, 3921, 4033, 4145, 4256, 4369, 4472, 4537, 4546, 4485, 4347, 4143, 3915, 3705, 3541, 3439, 3399, }, - /* LAT: 30 */ { 3722, 3726, 3778, 3876, 4017, 4186, 4361, 4515, 4622, 4648, 4575, 4421, 4234, 4074, 3972, 3929, 3935, 3988, 4077, 4176, 4275, 4382, 4499, 4617, 4737, 4866, 4988, 5074, 5098, 5038, 4880, 4639, 4364, 4109, 3909, 3779, 3722, }, - /* LAT: 40 */ { 4222, 4216, 4278, 4399, 4564, 4750, 4932, 5088, 5192, 5218, 5151, 5004, 4820, 4649, 4524, 4451, 4427, 4452, 4515, 4595, 4683, 4781, 4897, 5030, 5182, 5345, 5497, 5606, 5643, 5586, 5428, 5190, 4916, 4657, 4446, 4299, 4222, }, - /* LAT: 50 */ { 4832, 4820, 4872, 4979, 5123, 5281, 5431, 5552, 5627, 5637, 5575, 5450, 5290, 5128, 4993, 4898, 4845, 4836, 4862, 4914, 4984, 5076, 5196, 5346, 5522, 5707, 5873, 5989, 6030, 5984, 5851, 5656, 5432, 5218, 5038, 4906, 4832, }, - /* LAT: 60 */ { 5393, 5376, 5400, 5459, 5543, 5637, 5724, 5792, 5827, 5820, 5768, 5675, 5556, 5430, 5312, 5218, 5153, 5120, 5119, 5148, 5205, 5293, 5412, 5559, 5726, 5894, 6040, 6142, 6183, 6160, 6077, 5951, 5807, 5665, 5543, 5450, 5393, }, - /* LAT: 70 */ { 5726, 5703, 5697, 5707, 5727, 5753, 5778, 5793, 5795, 5777, 5740, 5684, 5616, 5541, 5468, 5405, 5358, 5331, 5327, 5348, 5393, 5463, 5555, 5664, 5781, 5895, 5993, 6065, 6103, 6106, 6077, 6024, 5957, 5887, 5821, 5766, 5726, }, - /* LAT: 80 */ { 5790, 5772, 5756, 5743, 5733, 5723, 5713, 5702, 5688, 5670, 5649, 5625, 5599, 5573, 5549, 5529, 5516, 5511, 5517, 5532, 5558, 5594, 5636, 5684, 5734, 5782, 5824, 5858, 5882, 5895, 5897, 5889, 5875, 5855, 5833, 5811, 5790, }, - /* LAT: 90 */ { 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, 5685, }, +// Date: 2024.41257, +static constexpr const int16_t totalintensity_table[19][37] { + // LONGITUDE: -180, -170, -160, -150, -140, -130, -120, -110, -100, -90, -80, -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 180, + /* LAT: -90 */ { 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, 26644, }, + /* LAT: -80 */ { 29615, 29299, 28908, 28453, 27945, 27395, 26815, 26218, 25619, 25032, 24474, 23959, 23502, 23115, 22808, 22592, 22476, 22469, 22578, 22807, 23157, 23621, 24187, 24836, 25543, 26279, 27014, 27716, 28358, 28914, 29365, 29700, 29913, 30004, 29979, 29846, 29615, }, + /* LAT: -70 */ { 30814, 30152, 29407, 28592, 27711, 26765, 25759, 24706, 23635, 22584, 21596, 20706, 19938, 19300, 18794, 18422, 18195, 18139, 18285, 18666, 19302, 20195, 21322, 22642, 24092, 25601, 27090, 28480, 29701, 30696, 31432, 31894, 32090, 32046, 31794, 31371, 30814, }, // WARNING! black out zone + /* LAT: -60 */ { 30256, 29303, 28305, 27273, 26195, 25041, 23783, 22419, 20989, 19575, 18274, 17168, 16296, 15644, 15162, 14803, 14555, 14459, 14593, 15046, 15888, 17136, 18753, 20656, 22732, 24862, 26925, 28803, 30388, 31598, 32391, 32767, 32766, 32449, 31882, 31131, 30256, }, // WARNING! black out zone + /* LAT: -50 */ { 28585, 27448, 26301, 25162, 24017, 22813, 21484, 19998, 18389, 16768, 15296, 14132, 13352, 12914, 12677, 12503, 12330, 12195, 12223, 12590, 13464, 14914, 16881, 19207, 21698, 24175, 26497, 28540, 30193, 31368, 32034, 32224, 32006, 31456, 30654, 29673, 28585, }, + /* LAT: -40 */ { 26388, 25175, 23965, 22783, 21629, 20463, 19212, 17819, 16281, 14687, 13231, 12153, 11593, 11476, 11568, 11662, 11671, 11598, 11530, 11680, 12349, 13743, 15828, 18371, 21056, 23615, 25886, 27774, 29196, 30107, 30531, 30536, 30188, 29538, 28642, 27566, 26388, }, + /* LAT: -30 */ { 23875, 22687, 21506, 20350, 19238, 18163, 17088, 15953, 14699, 13348, 12090, 11211, 10886, 11019, 11346, 11688, 11997, 12225, 12312, 12367, 12723, 13749, 15575, 17999, 20611, 23034, 25059, 26587, 27567, 28051, 28176, 28039, 27646, 26992, 26106, 25040, 23875, }, + /* LAT: -20 */ { 21154, 20100, 19069, 18060, 17097, 16201, 15373, 14569, 13693, 12716, 11782, 11141, 10963, 11194, 11640, 12182, 12805, 13413, 13818, 13974, 14106, 14617, 15845, 17765, 19985, 22068, 23750, 24872, 25370, 25402, 25252, 25023, 24621, 23994, 23174, 22204, 21154, }, + /* LAT: -10 */ { 18558, 17760, 17002, 16280, 15615, 15025, 14516, 14058, 13572, 13001, 12403, 11927, 11727, 11873, 12314, 12952, 13712, 14475, 15055, 15339, 15405, 15556, 16199, 17471, 19086, 20662, 21941, 22713, 22869, 22606, 22275, 21968, 21540, 20930, 20196, 19388, 18558, }, + /* LAT: 0 */ { 16709, 16246, 15828, 15466, 15193, 15003, 14869, 14765, 14634, 14389, 14000, 13543, 13167, 13043, 13274, 13791, 14440, 15095, 15645, 15999, 16143, 16257, 16647, 17443, 18484, 19534, 20407, 20910, 20925, 20587, 20154, 19705, 19162, 18518, 17858, 17244, 16709, }, + /* LAT: 10 */ { 16075, 15916, 15810, 15786, 15900, 16127, 16390, 16638, 16796, 16740, 16399, 15842, 15234, 14793, 14691, 14911, 15314, 15798, 16286, 16698, 17008, 17318, 17762, 18355, 19031, 19718, 20303, 20638, 20637, 20325, 19783, 19078, 18284, 17502, 16834, 16355, 16075, }, + /* LAT: 20 */ { 16646, 16650, 16769, 17024, 17466, 18051, 18672, 19233, 19618, 19672, 19310, 18619, 17813, 17152, 16804, 16764, 16949, 17315, 17793, 18272, 18719, 19208, 19759, 20311, 20853, 21411, 21916, 22235, 22275, 21976, 21295, 20297, 19178, 18148, 17345, 16845, 16646, }, + /* LAT: 30 */ { 18228, 18245, 18498, 18973, 19662, 20491, 21341, 22097, 22620, 22746, 22388, 21634, 20724, 19941, 19447, 19240, 19272, 19535, 19972, 20460, 20944, 21470, 22044, 22622, 23213, 23845, 24444, 24864, 24980, 24684, 23906, 22724, 21376, 20127, 19146, 18510, 18228, }, + /* LAT: 40 */ { 20676, 20646, 20945, 21535, 22339, 23247, 24138, 24900, 25411, 25538, 25208, 24491, 23592, 22759, 22150, 21796, 21685, 21808, 22117, 22515, 22946, 23429, 23995, 24649, 25392, 26192, 26939, 27472, 27650, 27367, 26593, 25423, 24081, 22812, 21778, 21055, 20676, }, + /* LAT: 50 */ { 23666, 23603, 23852, 24371, 25074, 25848, 26580, 27175, 27541, 27593, 27291, 26681, 25898, 25111, 24452, 23986, 23733, 23688, 23819, 24073, 24420, 24871, 25459, 26197, 27059, 27964, 28776, 29343, 29542, 29310, 28661, 27703, 26610, 25561, 24680, 24034, 23666, }, + /* LAT: 60 */ { 26412, 26324, 26436, 26723, 27132, 27589, 28019, 28351, 28524, 28493, 28240, 27789, 27209, 26590, 26018, 25556, 25239, 25081, 25078, 25221, 25503, 25932, 26515, 27239, 28055, 28877, 29590, 30087, 30289, 30171, 29764, 29152, 28446, 27753, 27153, 26695, 26412, }, + /* LAT: 70 */ { 28043, 27927, 27896, 27940, 28040, 28166, 28285, 28364, 28372, 28290, 28109, 27838, 27503, 27138, 26784, 26477, 26247, 26116, 26097, 26198, 26422, 26766, 27217, 27750, 28323, 28879, 29358, 29708, 29894, 29908, 29765, 29507, 29181, 28836, 28513, 28242, 28043, }, // WARNING! black out zone + /* LAT: 80 */ { 28358, 28266, 28189, 28125, 28072, 28025, 27977, 27922, 27854, 27769, 27667, 27549, 27422, 27295, 27178, 27083, 27020, 26999, 27025, 27102, 27229, 27402, 27613, 27847, 28090, 28324, 28531, 28697, 28813, 28875, 28885, 28848, 28776, 28680, 28572, 28462, 28358, }, // WARNING! black out zone + /* LAT: 90 */ { 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, 27849, }, // WARNING! black out zone }; -static constexpr float WMM_STRENGTH_MIN_GS = 22.2; // latitude: -30, longitude: -60 -static constexpr float WMM_STRENGTH_MAX_GS = 66.9; // latitude: -60, longitude: 140 -static constexpr float WMM_STRENGTH_MEAN_GS = 46.4; -static constexpr float WMM_STRENGTH_MEDIAN_GS = 48.8; +static constexpr float WMM_TOTALINTENSITY_SCALE_TO_NANOTESLA = 2.04183477f; +static constexpr float WMM_TOTALINTENSITY_MIN_NANOTESLA = 22226.9f; // latitude: -30, longitude: -60 +static constexpr float WMM_TOTALINTENSITY_MAX_NANOTESLA = 66904.8f; // latitude: -60, longitude: 130 diff --git a/src/lib/world_magnetic_model/test_geo_lookup.cpp b/src/lib/world_magnetic_model/test_geo_lookup.cpp index f8dfe3e45bb3..674d4252f14c 100644 --- a/src/lib/world_magnetic_model/test_geo_lookup.cpp +++ b/src/lib/world_magnetic_model/test_geo_lookup.cpp @@ -40,15 +40,15 @@ TEST(GeoLookupTest, declination) { - EXPECT_NEAR(get_mag_declination_degrees(-50, -180), 31.6, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -180), 31.7, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -175), 31.8, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -170), 31.8, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -165), 31.7, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -160), 31.4, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -160), 31.5, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -155), 31.2, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -150), 30.9, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -145), 30.6, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -140), 30.4, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -145), 30.7, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -140), 30.5, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -135), 30.3, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -130), 30.2, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -125), 30.1, 0.36 + 1.0); @@ -57,70 +57,70 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-50, -110), 29.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -105), 28.4, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -100), 27.2, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -95), 25.6, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -95), 25.5, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -90), 23.4, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -85), 20.7, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -80), 17.6, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -80), 17.5, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -75), 14.0, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -70), 10.3, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -70), 10.2, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -65), 6.4, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -60), 2.6, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -55), -0.9, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -55), -1.0, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -50), -4.1, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -45), -6.8, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -40), -9.0, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -35), -10.7, 0.48 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -30), -12.1, 0.49 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -25), -13.3, 0.51 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -25), -13.2, 0.51 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, -20), -14.3, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -15), -15.5, 0.53 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -10), -16.9, 0.53 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, -5), -18.7, 0.53 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -15), -15.4, 0.53 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -10), -16.8, 0.53 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, -5), -18.6, 0.53 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 0), -20.9, 0.53 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 5), -23.7, 0.52 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 10), -26.9, 0.51 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 15), -30.4, 0.49 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 20), -34.1, 0.47 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 20), -34.2, 0.47 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 25), -37.9, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 30), -41.5, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 35), -44.9, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 30), -41.6, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 35), -45.0, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 40), -48.1, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 45), -50.8, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 50), -53.2, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 55), -55.1, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 45), -50.9, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 50), -53.3, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 55), -55.2, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 60), -56.6, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 65), -57.5, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 70), -57.9, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 75), -57.6, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 75), -57.7, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 80), -56.7, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 85), -54.9, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 90), -52.3, 0.47 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 95), -48.5, 0.50 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 100), -43.6, 0.52 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 100), -43.5, 0.52 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 105), -37.3, 0.55 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 110), -30.0, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 115), -21.8, 0.59 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 110), -29.9, 0.57 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 115), -21.7, 0.59 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 120), -13.3, 0.59 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 125), -5.1, 0.59 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 125), -5.0, 0.59 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 130), 2.5, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 135), 9.0, 0.55 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 135), 9.1, 0.55 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 140), 14.6, 0.52 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 145), 19.1, 0.50 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 150), 22.7, 0.48 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 150), 22.8, 0.48 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 155), 25.6, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 160), 27.7, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 165), 29.3, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 170), 30.4, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 160), 27.8, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 165), 29.4, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 170), 30.5, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-50, 175), 31.2, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-50, 180), 31.6, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -180), 26.6, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -175), 26.9, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-50, 180), 31.7, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -180), 26.7, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -175), 27.0, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -170), 27.1, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -165), 27.0, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -160), 26.9, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -165), 27.1, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -160), 27.0, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -155), 26.8, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -150), 26.5, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -145), 26.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -150), 26.6, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -145), 26.4, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -140), 26.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -135), 26.1, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -130), 26.0, 0.36 + 1.0); @@ -128,72 +128,72 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-45, -120), 26.0, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -115), 26.0, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -110), 25.8, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -105), 25.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -105), 25.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -100), 24.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -95), 22.9, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -90), 20.9, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -85), 18.3, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -85), 18.2, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -80), 15.0, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -75), 11.3, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -70), 7.2, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -75), 11.2, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -70), 7.1, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -65), 2.9, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -60), -1.2, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -55), -5.0, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -55), -5.1, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -50), -8.4, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -45), -11.1, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -40), -13.3, 0.48 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -35), -14.9, 0.50 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, -30), -16.0, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -25), -16.8, 0.53 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -20), -17.5, 0.55 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -15), -18.1, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -10), -18.8, 0.58 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, -5), -19.9, 0.59 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 0), -21.5, 0.58 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -25), -16.8, 0.54 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -20), -17.4, 0.55 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -15), -18.0, 0.57 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -10), -18.7, 0.58 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, -5), -19.8, 0.59 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 0), -21.4, 0.58 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 5), -23.7, 0.57 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 10), -26.5, 0.56 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 15), -29.7, 0.53 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 20), -33.2, 0.51 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 25), -36.7, 0.49 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 30), -40.1, 0.47 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 35), -43.2, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 25), -36.8, 0.49 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 30), -40.2, 0.47 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 35), -43.3, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 40), -46.0, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 45), -48.2, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 50), -50.0, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 45), -48.3, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 50), -50.1, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 55), -51.3, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 60), -51.9, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 65), -51.9, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 60), -52.0, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 65), -52.0, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 70), -51.3, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 75), -49.9, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 80), -47.7, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 85), -44.7, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 90), -40.8, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 95), -36.1, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 100), -30.6, 0.47 + 1.8); - EXPECT_NEAR(get_mag_declination_degrees(-45, 105), -24.6, 0.48 + 1.8); - EXPECT_NEAR(get_mag_declination_degrees(-45, 110), -18.4, 0.48 + 1.8); + EXPECT_NEAR(get_mag_declination_degrees(-45, 95), -36.0, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 100), -30.5, 0.47 + 1.8); + EXPECT_NEAR(get_mag_declination_degrees(-45, 105), -24.5, 0.48 + 1.8); + EXPECT_NEAR(get_mag_declination_degrees(-45, 110), -18.3, 0.48 + 1.8); EXPECT_NEAR(get_mag_declination_degrees(-45, 115), -12.2, 0.48 + 1.8); EXPECT_NEAR(get_mag_declination_degrees(-45, 120), -6.4, 0.47 + 1.8); - EXPECT_NEAR(get_mag_declination_degrees(-45, 125), -1.1, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 125), -1.0, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 130), 3.8, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 135), 8.2, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 140), 12.0, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 145), 15.4, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 140), 12.1, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 145), 15.5, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 150), 18.3, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 155), 20.7, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 160), 22.7, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 165), 24.2, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 170), 25.3, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-45, 175), 26.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-45, 180), 26.6, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-45, 180), 26.7, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -180), 22.8, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -175), 23.1, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -175), 23.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -170), 23.3, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -165), 23.4, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -160), 23.3, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -160), 23.4, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -155), 23.2, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -150), 23.0, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -145), 22.8, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -150), 23.1, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -145), 22.9, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -140), 22.7, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -135), 22.5, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -130), 22.4, 0.35 + 1.0); @@ -201,68 +201,68 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-40, -120), 22.5, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -115), 22.5, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -110), 22.4, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -105), 22.1, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -100), 21.4, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -105), 22.0, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -100), 21.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -95), 20.1, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -90), 18.2, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -85), 15.6, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -80), 12.3, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -75), 8.4, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -75), 8.3, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -70), 4.0, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -65), -0.5, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -60), -4.9, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -55), -8.9, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -65), -0.6, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -60), -5.0, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -55), -9.0, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -50), -12.4, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -45), -15.1, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, -40), -17.2, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -35), -18.7, 0.50 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -30), -19.6, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -25), -20.3, 0.55 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -20), -20.6, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -15), -20.8, 0.60 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -10), -20.9, 0.62 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, -5), -21.2, 0.63 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -35), -18.6, 0.50 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -30), -19.6, 0.53 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -25), -20.2, 0.55 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -20), -20.5, 0.57 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -15), -20.7, 0.60 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -10), -20.8, 0.62 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, -5), -21.1, 0.63 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 0), -21.9, 0.63 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 5), -23.3, 0.62 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 10), -25.4, 0.61 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 15), -28.1, 0.58 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 20), -31.2, 0.55 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 25), -34.4, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 30), -37.5, 0.49 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 35), -40.2, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 40), -42.5, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 45), -44.3, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 15), -28.2, 0.58 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 20), -31.3, 0.55 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 25), -34.5, 0.52 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 30), -37.6, 0.49 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 35), -40.3, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 40), -42.6, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 45), -44.4, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 50), -45.6, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 55), -46.1, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 55), -46.2, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 60), -46.1, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 65), -45.3, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 70), -43.8, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 75), -41.5, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 80), -38.6, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 80), -38.5, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 85), -34.9, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 90), -30.6, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 90), -30.5, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 95), -25.8, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 100), -20.8, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 105), -15.8, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 110), -11.1, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 115), -6.8, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 115), -6.7, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 120), -2.8, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 125), 0.8, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 125), 0.9, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 130), 4.2, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 135), 7.3, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 140), 10.2, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 140), 10.2, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 145), 12.8, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 150), 15.2, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 155), 17.2, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 155), 17.3, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 160), 19.0, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 165), 20.4, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 170), 21.5, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-40, 175), 22.2, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-40, 175), 22.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-40, 180), 22.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -180), 19.7, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -175), 20.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -170), 20.2, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -165), 20.3, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -175), 20.1, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -170), 20.3, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -165), 20.4, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -160), 20.4, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -155), 20.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -150), 20.2, 0.34 + 1.0); @@ -275,34 +275,34 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-35, -115), 19.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -110), 19.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -105), 18.9, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -100), 18.4, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -95), 17.3, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -90), 15.5, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -100), 18.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -95), 17.2, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -90), 15.4, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -85), 12.9, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -80), 9.5, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -75), 5.4, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -70), 0.9, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -65), -3.8, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -60), -8.3, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -70), 0.8, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -65), -3.9, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -60), -8.4, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -55), -12.4, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -50), -15.7, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -50), -15.8, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -45), -18.4, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -40), -20.3, 0.48 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -35), -21.6, 0.50 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -30), -22.5, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -25), -23.0, 0.54 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -20), -23.2, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -15), -23.0, 0.60 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, -10), -22.6, 0.62 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -25), -22.9, 0.54 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -20), -23.1, 0.57 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -15), -22.9, 0.60 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, -10), -22.5, 0.63 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, -5), -22.1, 0.65 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, 0), -21.9, 0.66 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, 0), -21.8, 0.66 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 5), -22.2, 0.66 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 10), -23.3, 0.64 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 15), -25.2, 0.61 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, 20), -27.6, 0.58 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, 20), -27.7, 0.58 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 25), -30.4, 0.54 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, 30), -33.0, 0.50 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, 35), -35.4, 0.47 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, 30), -33.1, 0.50 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, 35), -35.5, 0.47 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 40), -37.4, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 45), -38.8, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 50), -39.6, 0.42 + 1.0); @@ -324,19 +324,19 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-35, 130), 4.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 135), 6.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 140), 8.7, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, 145), 10.8, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, 145), 10.9, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 150), 12.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 155), 14.6, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 160), 16.2, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, 165), 17.4, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-35, 170), 18.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, 165), 17.5, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-35, 170), 18.5, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 175), 19.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-35, 180), 19.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -180), 17.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -175), 17.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -170), 17.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -165), 17.8, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -160), 17.8, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -160), 17.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -155), 17.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -150), 17.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -145), 17.6, 0.33 + 1.0); @@ -348,67 +348,67 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-30, -115), 16.4, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -110), 16.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -105), 16.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -100), 15.6, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -100), 15.5, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -95), 14.5, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -90), 12.8, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -85), 10.2, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -80), 6.8, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -75), 2.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -70), -2.0, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -65), -6.7, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -60), -11.2, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -55), -15.1, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -90), 12.7, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -85), 10.1, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -80), 6.7, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -75), 2.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -70), -2.1, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -65), -6.8, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -60), -11.3, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -55), -15.2, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -50), -18.3, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -45), -20.7, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -40), -22.4, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -35), -23.5, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -30), -24.3, 0.50 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -30), -24.2, 0.50 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, -25), -24.6, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -20), -24.6, 0.55 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -15), -24.1, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -10), -23.3, 0.60 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, -5), -22.0, 0.63 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -20), -24.5, 0.55 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -15), -24.1, 0.58 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -10), -23.2, 0.60 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, -5), -21.9, 0.63 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 0), -20.7, 0.64 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 5), -19.8, 0.65 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 10), -19.7, 0.63 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 10), -19.7, 0.64 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 15), -20.5, 0.61 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 20), -22.1, 0.58 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 25), -24.2, 0.54 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 30), -26.5, 0.50 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 25), -24.3, 0.54 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 30), -26.6, 0.50 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 35), -28.7, 0.47 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 40), -30.5, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 45), -31.7, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 50), -32.3, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 45), -31.8, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 50), -32.4, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 55), -32.3, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 60), -31.5, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 65), -30.1, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 65), -30.0, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 70), -28.0, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 75), -25.4, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 80), -22.4, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 85), -19.1, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 85), -19.0, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 90), -15.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 95), -12.0, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 100), -8.7, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 105), -5.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 110), -3.4, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 115), -1.3, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 120), 0.5, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 125), 2.2, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 120), 0.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 125), 2.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 130), 3.9, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 135), 5.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 140), 7.5, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 145), 9.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 150), 11.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 155), 12.6, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 160), 13.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 160), 14.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 165), 15.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 170), 16.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-30, 175), 16.7, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 170), 16.1, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-30, 175), 16.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-30, 180), 17.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -180), 15.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -175), 15.4, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -170), 15.6, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -165), 15.6, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -165), 15.7, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -160), 15.7, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -155), 15.7, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -150), 15.6, 0.32 + 1.0); @@ -416,47 +416,47 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-25, -140), 15.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -135), 15.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -130), 14.7, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -125), 14.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -125), 14.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -120), 14.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -115), 14.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -110), 13.9, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -110), 13.8, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -105), 13.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -100), 13.1, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -95), 12.1, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -95), 12.0, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -90), 10.3, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -85), 7.7, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -80), 4.2, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -75), 0.0, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -85), 7.6, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -80), 4.1, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -75), -0.0, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -70), -4.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -65), -9.2, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -65), -9.3, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -60), -13.5, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -55), -17.1, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -50), -20.0, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -55), -17.2, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -50), -20.1, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -45), -22.2, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -40), -23.6, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -35), -24.5, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -30), -24.9, 0.47 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -25), -25.0, 0.49 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -25), -24.9, 0.49 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -20), -24.6, 0.51 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, -15), -23.7, 0.53 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -10), -22.3, 0.55 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, -5), -20.4, 0.57 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -10), -22.2, 0.55 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, -5), -20.3, 0.57 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 0), -18.2, 0.59 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 5), -16.3, 0.59 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 5), -16.2, 0.59 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 10), -15.0, 0.58 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 15), -14.7, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 20), -15.3, 0.54 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 20), -15.4, 0.54 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 25), -16.8, 0.51 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 30), -18.7, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 35), -20.7, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 35), -20.8, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 40), -22.6, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 45), -23.9, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 45), -24.0, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 50), -24.7, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 55), -24.8, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 60), -24.2, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 60), -24.1, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 65), -22.9, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 70), -21.2, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 75), -19.0, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 70), -21.1, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 75), -18.9, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 80), -16.4, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 85), -13.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 90), -10.7, 0.34 + 1.0); @@ -465,7 +465,7 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-25, 105), -3.1, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 110), -1.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 115), -0.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 120), 1.1, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 120), 1.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 125), 2.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 130), 3.5, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 135), 4.9, 0.32 + 1.0); @@ -475,47 +475,47 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-25, 155), 10.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 160), 12.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 165), 13.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-25, 170), 14.1, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-25, 170), 14.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 175), 14.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-25, 180), 15.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -180), 13.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -175), 13.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -170), 13.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -165), 13.8, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -160), 13.8, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -155), 13.8, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -160), 13.9, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -155), 13.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -150), 13.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -145), 13.7, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -140), 13.5, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -135), 13.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -130), 13.0, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -130), 12.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -125), 12.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -120), 12.3, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -115), 12.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -110), 11.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -115), 12.0, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -110), 11.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -105), 11.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -100), 11.0, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -95), 9.9, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -90), 8.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -85), 5.5, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -80), 2.0, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -75), -2.1, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -70), -6.6, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -65), -11.0, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -85), 5.4, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -80), 1.9, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -75), -2.2, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -70), -6.7, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -65), -11.1, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -60), -15.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -55), -18.4, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -50), -21.0, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -45), -22.8, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -55), -18.5, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -50), -21.1, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -45), -22.9, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -40), -23.9, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -35), -24.4, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -30), -24.5, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -30), -24.4, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -25), -24.0, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -20), -23.2, 0.47 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -15), -21.8, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, -10), -19.8, 0.49 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -20), -23.1, 0.47 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -15), -21.7, 0.48 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, -10), -19.7, 0.49 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, -5), -17.4, 0.50 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 0), -14.9, 0.51 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 5), -12.4, 0.51 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 0), -14.8, 0.51 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 5), -12.3, 0.51 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 10), -10.4, 0.51 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 15), -9.3, 0.49 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 20), -9.1, 0.48 + 1.0); @@ -523,22 +523,22 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-20, 30), -11.3, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 35), -13.2, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 40), -15.1, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 45), -16.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 50), -17.6, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 55), -18.0, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 45), -16.7, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 50), -17.7, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 55), -18.0, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 60), -17.7, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 65), -16.9, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 70), -15.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 75), -13.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 80), -11.9, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 85), -9.7, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 90), -7.3, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 85), -9.6, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 90), -7.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 95), -4.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 100), -2.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 105), -1.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 110), -0.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 115), 0.6, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-20, 120), 1.3, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-20, 120), 1.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 125), 2.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 130), 3.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 135), 4.2, 0.31 + 1.0); @@ -551,9 +551,9 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-20, 170), 12.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 175), 13.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-20, 180), 13.5, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -180), 12.2, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -175), 12.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -170), 12.3, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -180), 12.3, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -175), 12.4, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -170), 12.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -165), 12.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -160), 12.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -155), 12.3, 0.31 + 1.0); @@ -566,37 +566,37 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-15, -120), 10.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -115), 10.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -110), 10.3, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -105), 10.0, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -105), 9.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -100), 9.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -95), 8.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -90), 6.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -85), 3.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -80), 0.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -75), -3.9, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -70), -8.2, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -65), -12.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -75), -4.0, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -70), -8.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -65), -12.4, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -60), -16.1, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -55), -19.1, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -55), -19.2, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -50), -21.4, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -45), -22.8, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -40), -23.5, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -35), -23.6, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -30), -23.1, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -25), -22.1, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -20), -20.7, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -15), -18.8, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -35), -23.5, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -30), -23.0, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -25), -22.0, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -20), -20.6, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -15), -18.7, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, -10), -16.5, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, -5), -14.0, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 0), -11.4, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, -5), -13.9, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 0), -11.3, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 5), -8.8, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 10), -6.7, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 15), -5.2, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 20), -4.5, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 25), -4.7, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 30), -5.6, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 30), -5.7, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 35), -7.2, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 40), -9.0, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 45), -10.6, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 40), -9.0, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 45), -10.7, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 50), -11.9, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 55), -12.5, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 60), -12.6, 0.33 + 1.0); @@ -604,30 +604,30 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-15, 70), -11.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 75), -10.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 80), -8.6, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 85), -6.9, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 85), -6.8, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 90), -4.9, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 95), -3.1, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 100), -1.5, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 100), -1.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 105), -0.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 110), 0.5, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 110), 0.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 115), 0.9, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 120), 1.2, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 125), 1.7, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 125), 1.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 130), 2.4, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 135), 3.5, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 135), 3.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 140), 4.7, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 145), 6.1, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 145), 6.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 150), 7.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 155), 8.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 160), 9.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 165), 10.7, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 170), 11.4, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 170), 11.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-15, 175), 12.0, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-15, 180), 12.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-15, 180), 12.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -180), 11.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -175), 11.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -170), 11.2, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -165), 11.1, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -170), 11.3, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -165), 11.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -160), 11.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -155), 11.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -150), 11.0, 0.31 + 1.0); @@ -638,37 +638,37 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-10, -125), 9.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -120), 9.6, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -115), 9.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -110), 9.1, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -110), 9.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -105), 8.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -100), 8.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -95), 6.8, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -95), 6.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -90), 4.8, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -85), 2.1, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -85), 2.0, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -80), -1.4, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -75), -5.3, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -70), -9.3, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -70), -9.4, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -65), -13.2, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -60), -16.5, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -60), -16.6, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -55), -19.3, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -50), -21.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -45), -22.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -40), -22.5, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -35), -22.1, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -30), -21.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -25), -19.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -20), -17.7, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -15), -15.5, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -30), -21.0, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -25), -19.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -20), -17.6, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -15), -15.4, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, -10), -13.1, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, -5), -10.7, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 0), -8.3, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 5), -6.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 10), -4.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 15), -2.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, -5), -10.6, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 0), -8.2, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 5), -6.0, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 10), -4.0, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 15), -2.4, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 20), -1.5, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 25), -1.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 30), -1.9, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 35), -3.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 40), -4.6, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 40), -4.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 45), -6.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 50), -7.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 55), -8.3, 0.32 + 1.0); @@ -676,7 +676,7 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-10, 65), -8.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 70), -8.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 75), -7.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 80), -6.3, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 80), -6.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 85), -4.9, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 90), -3.4, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 95), -1.9, 0.30 + 1.0); @@ -685,22 +685,22 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-10, 110), 0.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 115), 0.8, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 120), 0.9, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 125), 1.2, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 125), 1.1, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 130), 1.8, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 135), 2.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 140), 3.9, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 145), 5.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 150), 6.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 155), 7.7, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 160), 8.8, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 160), 8.9, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 165), 9.8, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 170), 10.6, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-10, 175), 11.0, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-10, 175), 11.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-10, 180), 11.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -180), 10.6, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -175), 10.5, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -175), 10.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -170), 10.4, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -165), 10.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -165), 10.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -160), 10.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -155), 10.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -150), 10.0, 0.31 + 1.0); @@ -708,35 +708,35 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-5, -140), 9.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -135), 9.7, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -130), 9.4, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -125), 9.1, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -125), 9.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -120), 8.7, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -115), 8.5, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -110), 8.2, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -115), 8.4, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -110), 8.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -105), 7.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -100), 6.9, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -95), 5.6, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -95), 5.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -90), 3.5, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -85), 0.8, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -85), 0.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -80), -2.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -75), -6.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -70), -10.1, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -65), -13.6, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -65), -13.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -60), -16.7, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -55), -19.0, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -55), -19.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -50), -20.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -45), -21.3, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -40), -21.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -35), -20.3, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -35), -20.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -30), -18.8, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, -25), -16.9, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, -25), -16.8, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -20), -14.7, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -15), -12.4, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -10), -10.1, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, -5), -7.9, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 0), -5.9, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 5), -4.0, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 0), -5.8, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 5), -3.9, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 10), -2.2, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 15), -0.8, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 15), -0.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 20), 0.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 25), 0.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 30), 0.5, 0.33 + 1.0); @@ -749,68 +749,68 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(-5, 65), -5.8, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 70), -5.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 75), -5.2, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 80), -4.6, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 80), -4.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 85), -3.6, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 90), -2.5, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 90), -2.4, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 95), -1.3, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 100), -0.3, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 105), 0.3, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 110), 0.6, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 115), 0.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 120), 0.4, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 125), 0.6, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 130), 1.1, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 135), 2.0, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 140), 3.2, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 125), 0.5, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 130), 1.0, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 135), 1.9, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 140), 3.1, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 145), 4.4, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 150), 5.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 155), 7.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 160), 8.1, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 165), 9.1, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 170), 9.9, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(-5, 175), 10.3, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(-5, 175), 10.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(-5, 180), 10.6, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -180), 10.0, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -180), 10.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -175), 10.0, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -170), 9.8, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -165), 9.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -170), 9.9, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -165), 9.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -160), 9.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -155), 9.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -150), 9.4, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -145), 9.4, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -140), 9.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -135), 9.1, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -130), 8.9, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -130), 8.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -125), 8.5, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -120), 8.2, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -115), 7.9, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -115), 7.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -110), 7.5, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -105), 7.0, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -105), 6.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -100), 6.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -95), 4.6, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -90), 2.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -95), 4.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -90), 2.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -85), -0.3, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -80), -3.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -80), -3.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -75), -7.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -70), -10.6, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -65), -13.8, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -60), -16.5, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -65), -13.9, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -60), -16.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -55), -18.6, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -50), -19.8, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -50), -19.8, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -45), -20.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -40), -19.6, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -35), -18.4, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -30), -16.6, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -25), -14.5, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -20), -12.2, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -15), -9.9, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, -10), -7.7, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -35), -18.3, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -30), -16.5, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -25), -14.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -20), -12.1, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -15), -9.8, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, -10), -7.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, -5), -5.7, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 0), -4.0, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 0), -3.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 5), -2.4, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 10), -1.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 15), 0.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 20), 1.3, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 10), -0.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 15), 0.4, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 20), 1.4, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 25), 1.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 30), 1.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 35), 1.3, 0.32 + 1.0); @@ -819,7 +819,7 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(0, 50), -2.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 55), -3.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 60), -3.6, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 65), -3.9, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 65), -3.8, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 70), -3.9, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 75), -3.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 80), -3.3, 0.30 + 1.0); @@ -829,12 +829,12 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(0, 100), -0.2, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 105), 0.2, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 110), 0.2, 0.29 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 115), 0.0, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 115), -0.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 120), -0.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 125), -0.2, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 130), 0.3, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 130), 0.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 135), 1.1, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 140), 2.3, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 140), 2.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 145), 3.6, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 150), 4.9, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 155), 6.2, 0.30 + 1.0); @@ -842,9 +842,9 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(0, 165), 8.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 170), 9.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(0, 175), 9.8, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(0, 180), 10.0, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -180), 9.6, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -175), 9.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(0, 180), 10.1, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -180), 9.7, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -175), 9.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -170), 9.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -165), 9.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -160), 9.1, 0.32 + 1.0); @@ -859,12 +859,12 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(5, -115), 7.6, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -110), 7.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -105), 6.4, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -100), 5.4, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -100), 5.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -95), 3.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -90), 1.5, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -85), -1.2, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -85), -1.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -80), -4.4, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -75), -7.7, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -75), -7.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -70), -11.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -65), -13.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -60), -16.3, 0.33 + 1.0); @@ -874,17 +874,17 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(5, -40), -18.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -35), -16.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -30), -14.6, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -25), -12.4, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -20), -10.1, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -25), -12.3, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -20), -10.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -15), -7.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, -10), -5.8, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, -5), -4.1, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 0), -2.6, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 5), -1.3, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, -5), -4.0, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 0), -2.5, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 5), -1.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 10), -0.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 15), 1.1, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 20), 2.0, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 25), 2.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 20), 2.1, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 25), 2.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 30), 2.8, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 35), 2.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 40), 1.5, 0.31 + 1.0); @@ -894,7 +894,7 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(5, 60), -2.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 65), -2.4, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 70), -2.5, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 75), -2.6, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 75), -2.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 80), -2.4, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 85), -2.0, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 90), -1.5, 0.29 + 1.0); @@ -902,12 +902,12 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(5, 100), -0.4, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 105), -0.2, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 110), -0.3, 0.29 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 115), -0.6, 0.29 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 120), -0.9, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 115), -0.7, 0.29 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 120), -1.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 125), -1.0, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 130), -0.6, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 135), 0.2, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 140), 1.3, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 130), -0.7, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 135), 0.1, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 140), 1.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 145), 2.6, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 150), 3.9, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 155), 5.3, 0.30 + 1.0); @@ -915,8 +915,8 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(5, 165), 7.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 170), 8.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(5, 175), 9.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(5, 180), 9.6, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -180), 9.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(5, 180), 9.7, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -180), 9.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -175), 9.4, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -170), 9.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -165), 9.1, 0.32 + 1.0); @@ -926,11 +926,11 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(10, -145), 9.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -140), 9.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -135), 9.1, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -130), 8.9, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -130), 8.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -125), 8.5, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -120), 8.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -115), 7.6, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -110), 7.0, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -110), 6.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -105), 6.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -100), 4.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -95), 3.0, 0.33 + 1.0); @@ -940,22 +940,22 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(10, -75), -8.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -70), -11.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -65), -13.9, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -60), -15.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -60), -16.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -55), -17.3, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -50), -17.8, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -45), -17.5, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -40), -16.5, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -35), -14.9, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -30), -12.9, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -25), -10.7, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -50), -17.8, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -45), -17.4, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -40), -16.4, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -35), -14.8, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -30), -12.8, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -25), -10.6, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -20), -8.4, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -15), -6.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, -10), -4.4, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -15), -6.2, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, -10), -4.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, -5), -2.8, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 0), -1.5, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 5), -0.4, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 0), -1.4, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 5), -0.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 10), 0.7, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 15), 1.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 15), 1.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 20), 2.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 25), 3.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 30), 3.3, 0.30 + 1.0); @@ -964,7 +964,7 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(10, 45), 1.4, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 50), 0.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 55), -0.3, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 60), -0.9, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 60), -0.8, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 65), -1.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 70), -1.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 75), -1.6, 0.29 + 1.0); @@ -972,12 +972,12 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(10, 85), -1.5, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 90), -1.2, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 95), -0.9, 0.29 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 100), -0.6, 0.29 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 100), -0.7, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 105), -0.7, 0.29 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 110), -0.9, 0.29 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 110), -1.0, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 115), -1.4, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 120), -1.8, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 125), -1.9, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 125), -2.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 130), -1.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 135), -1.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 140), 0.1, 0.30 + 1.0); @@ -988,27 +988,27 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(10, 165), 6.9, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 170), 8.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(10, 175), 8.8, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(10, 180), 9.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(10, 180), 9.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -180), 8.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -175), 9.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -170), 9.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -165), 9.1, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -160), 9.1, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -160), 9.1, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -155), 9.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -150), 9.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -145), 9.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -140), 9.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -135), 9.6, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -130), 9.4, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -130), 9.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -125), 9.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -120), 8.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -115), 7.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -110), 7.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -105), 6.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -100), 4.5, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -95), 2.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -105), 5.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -100), 4.4, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -95), 2.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -90), -0.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -85), -2.8, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -85), -2.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -80), -5.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -75), -8.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -70), -11.6, 0.33 + 1.0); @@ -1019,9 +1019,9 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(15, -45), -16.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -40), -15.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -35), -13.4, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -30), -11.5, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -30), -11.4, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -25), -9.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, -20), -7.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, -20), -7.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -15), -5.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -10), -3.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, -5), -1.8, 0.31 + 1.0); @@ -1033,7 +1033,7 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(15, 25), 3.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 30), 3.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 35), 3.5, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, 40), 2.9, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, 40), 3.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 45), 2.1, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 50), 1.3, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 55), 0.6, 0.30 + 1.0); @@ -1045,27 +1045,27 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(15, 85), -1.0, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 90), -1.0, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 95), -0.9, 0.29 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, 100), -0.9, 0.29 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, 100), -1.0, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 105), -1.2, 0.29 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, 110), -1.6, 0.29 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, 110), -1.7, 0.29 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 115), -2.2, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, 120), -2.7, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, 120), -2.8, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 125), -3.0, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, 130), -2.8, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, 130), -2.9, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 135), -2.2, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, 140), -1.2, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, 140), -1.3, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 145), 0.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 150), 1.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 155), 2.9, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 160), 4.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 165), 5.9, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(15, 170), 7.1, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(15, 170), 7.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 175), 8.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(15, 180), 8.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -180), 8.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -175), 8.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -170), 9.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -165), 9.1, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -165), 9.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -160), 9.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -155), 9.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -150), 9.8, 0.33 + 1.0); @@ -1073,43 +1073,43 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(20, -140), 10.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -135), 10.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -130), 10.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -125), 9.8, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -125), 9.7, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -120), 9.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -115), 8.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -110), 7.4, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -105), 6.1, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -105), 6.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -100), 4.3, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -95), 2.1, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -95), 2.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -90), -0.6, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -85), -3.5, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -85), -3.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -80), -6.6, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -75), -9.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -75), -9.5, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -70), -12.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -65), -13.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -65), -14.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -60), -15.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -55), -15.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -50), -15.8, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -45), -15.1, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -45), -15.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -40), -13.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -35), -12.2, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -30), -10.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -25), -8.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -20), -6.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -15), -4.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, -10), -2.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -30), -10.3, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -25), -8.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -20), -6.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -15), -4.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, -10), -2.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, -5), -1.1, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 0), 0.0, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 0), 0.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 5), 1.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 10), 1.8, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 15), 2.5, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 20), 3.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 15), 2.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 20), 3.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 25), 3.8, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 30), 4.0, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 35), 3.9, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 30), 4.1, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 35), 4.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 40), 3.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 45), 2.8, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 50), 2.1, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 55), 1.4, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 55), 1.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 60), 1.0, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 65), 0.6, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 70), 0.3, 0.30 + 1.0); @@ -1123,13 +1123,13 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(20, 110), -2.4, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 115), -3.1, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 120), -3.8, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 125), -4.1, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 125), -4.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 130), -4.1, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 135), -3.6, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 140), -2.7, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 145), -1.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 150), -0.1, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(20, 155), 1.5, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(20, 155), 1.4, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 160), 3.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 165), 4.6, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(20, 170), 6.1, 0.32 + 1.0); @@ -1141,39 +1141,39 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(25, -165), 9.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -160), 9.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -155), 10.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -150), 10.5, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -145), 10.9, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -150), 10.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -145), 10.8, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -140), 11.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -135), 11.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -130), 11.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -125), 10.7, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -120), 10.1, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -115), 9.2, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -120), 10.0, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -115), 9.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -110), 7.9, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -105), 6.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -100), 4.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -95), 1.8, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -90), -1.1, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -85), -4.1, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -85), -4.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -80), -7.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -75), -10.0, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -70), -12.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -65), -14.0, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -60), -15.1, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -55), -15.4, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -50), -15.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -45), -14.2, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -40), -12.9, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -35), -11.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -30), -9.5, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -25), -7.6, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -20), -5.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -50), -15.0, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -45), -14.1, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -40), -12.8, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -35), -11.2, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -30), -9.4, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -25), -7.5, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -20), -5.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -15), -3.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, -10), -2.0, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, -5), -0.6, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, -5), -0.5, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 0), 0.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 5), 1.5, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, 10), 2.2, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, 10), 2.3, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 15), 3.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 20), 3.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 25), 4.1, 0.31 + 1.0); @@ -1194,8 +1194,8 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(25, 100), -1.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 105), -2.2, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 110), -3.1, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, 115), -4.0, 0.30 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(25, 120), -4.8, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, 115), -4.1, 0.30 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(25, 120), -4.9, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 125), -5.4, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 130), -5.5, 0.30 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(25, 135), -5.1, 0.31 + 1.0); @@ -1222,7 +1222,7 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(30, -125), 11.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -120), 11.0, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -115), 10.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, -110), 8.6, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, -110), 8.5, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -105), 6.7, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -100), 4.4, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -95), 1.6, 0.35 + 1.0); @@ -1236,13 +1236,13 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(30, -55), -15.1, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -50), -14.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -45), -13.6, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, -40), -12.3, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, -35), -10.7, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, -40), -12.2, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, -35), -10.6, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -30), -8.9, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, -25), -7.1, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, -20), -5.2, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, -25), -7.0, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, -20), -5.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -15), -3.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, -10), -1.7, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, -10), -1.6, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, -5), -0.2, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 0), 1.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 5), 1.9, 0.32 + 1.0); @@ -1251,23 +1251,23 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(30, 20), 4.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 25), 4.5, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 30), 4.8, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, 35), 4.8, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, 40), 4.6, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, 45), 4.2, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, 35), 4.9, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, 40), 4.7, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, 45), 4.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 50), 3.8, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 55), 3.3, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, 60), 2.9, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, 60), 3.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 65), 2.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 70), 2.2, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 75), 1.8, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 80), 1.3, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, 85), 0.7, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, 85), 0.6, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 90), -0.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 95), -0.8, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 100), -1.7, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, 105), -2.7, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, 105), -2.8, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 110), -3.9, 0.31 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(30, 115), -5.0, 0.31 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(30, 115), -5.1, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 120), -6.0, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 125), -6.7, 0.31 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 130), -6.9, 0.31 + 1.0); @@ -1281,11 +1281,11 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(30, 170), 3.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 175), 4.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(30, 180), 6.3, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -180), 5.3, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -180), 5.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -175), 6.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -170), 8.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -165), 9.2, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -160), 10.2, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -165), 9.1, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -160), 10.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -155), 11.1, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -150), 11.9, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -145), 12.6, 0.35 + 1.0); @@ -1295,39 +1295,39 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(35, -125), 12.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -120), 12.0, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -115), 10.9, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -110), 9.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -110), 9.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -105), 7.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -100), 4.6, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -95), 1.6, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -95), 1.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -90), -1.8, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -85), -5.2, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -85), -5.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -80), -8.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -75), -11.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -70), -13.3, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -65), -14.7, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -60), -15.3, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -55), -15.2, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -65), -14.6, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -60), -15.2, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -55), -15.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -50), -14.5, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -45), -13.5, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -40), -12.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -35), -10.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -45), -13.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -40), -12.0, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -35), -10.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -30), -8.7, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -25), -6.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -25), -6.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, -20), -5.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -15), -3.2, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -10), -1.5, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, -5), -0.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 0), 1.2, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 5), 2.2, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -15), -3.1, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -10), -1.4, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, -5), 0.0, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 0), 1.3, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 5), 2.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 10), 3.1, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 15), 3.8, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 20), 4.4, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 25), 4.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 20), 4.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 25), 5.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 30), 5.3, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 35), 5.5, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 40), 5.4, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 45), 5.2, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 50), 4.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 40), 5.5, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 45), 5.3, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 50), 5.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 55), 4.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 60), 4.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 65), 3.9, 0.32 + 1.0); @@ -1335,13 +1335,13 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(35, 75), 3.0, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 80), 2.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 85), 1.4, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 90), 0.5, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 95), -0.6, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 90), 0.4, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 95), -0.7, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 100), -1.9, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 105), -3.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 110), -4.7, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 115), -6.1, 0.32 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 120), -7.2, 0.32 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 120), -7.3, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 125), -8.1, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 130), -8.4, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 135), -8.3, 0.32 + 1.0); @@ -1351,9 +1351,9 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(35, 155), -3.6, 0.32 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 160), -1.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 165), 0.0, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 170), 1.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 170), 1.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(35, 175), 3.6, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(35, 180), 5.3, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(35, 180), 5.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -180), 4.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -175), 5.9, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -170), 7.5, 0.35 + 1.0); @@ -1362,48 +1362,48 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(40, -155), 11.6, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -150), 12.6, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -145), 13.5, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -140), 14.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -135), 14.4, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -140), 14.0, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -135), 14.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -130), 14.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -125), 13.9, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -120), 13.1, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -120), 13.0, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -115), 11.8, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -110), 10.0, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -105), 7.7, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -100), 4.8, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -95), 1.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -95), 1.4, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -90), -2.2, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -85), -5.8, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -80), -9.2, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -75), -12.0, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -70), -14.1, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -70), -14.0, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -65), -15.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -60), -15.8, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -55), -15.6, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -50), -14.9, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -50), -14.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -45), -13.7, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -40), -12.3, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -35), -10.7, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -30), -8.9, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -25), -7.1, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -20), -5.2, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -35), -10.6, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -30), -8.8, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -25), -7.0, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -20), -5.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, -15), -3.3, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -10), -1.6, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, -5), -0.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 0), 1.3, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 5), 2.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -10), -1.5, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, -5), 0.0, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 0), 1.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 5), 2.5, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 10), 3.4, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 15), 4.2, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 20), 4.9, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 25), 5.5, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 20), 5.0, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 25), 5.6, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 30), 6.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 35), 6.3, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 35), 6.4, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 40), 6.5, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 45), 6.5, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 50), 6.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 45), 6.6, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 50), 6.5, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 55), 6.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 60), 6.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 65), 5.6, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 65), 5.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 70), 5.1, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 75), 4.4, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 80), 3.5, 0.33 + 1.0); @@ -1411,12 +1411,12 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(40, 90), 1.1, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 95), -0.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 100), -2.1, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 105), -3.8, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 105), -3.9, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 110), -5.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 115), -7.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 120), -8.6, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 125), -9.5, 0.33 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 130), -9.9, 0.33 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 130), -10.0, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 135), -9.8, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 140), -9.2, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 145), -8.2, 0.33 + 1.0); @@ -1425,24 +1425,24 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(40, 160), -3.4, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 165), -1.5, 0.33 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 170), 0.4, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(40, 175), 2.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(40, 175), 2.3, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(40, 180), 4.2, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -180), 3.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -175), 5.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -170), 7.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -165), 8.9, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -165), 8.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -160), 10.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -155), 12.0, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -150), 13.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -150), 13.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -145), 14.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -140), 15.0, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -135), 15.4, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -130), 15.4, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -125), 15.0, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -120), 14.2, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -115), 12.8, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -110), 10.8, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -105), 8.2, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -120), 14.1, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -115), 12.7, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -110), 10.7, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -105), 8.1, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -100), 5.0, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -95), 1.3, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -90), -2.7, 0.41 + 1.0); @@ -1451,164 +1451,164 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(45, -75), -13.0, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -70), -15.1, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -65), -16.3, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -60), -16.8, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -60), -16.7, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -55), -16.5, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -50), -15.7, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -45), -14.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -40), -13.0, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -35), -11.3, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -30), -9.5, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -25), -7.6, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -30), -9.4, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -25), -7.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -20), -5.6, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -15), -3.7, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, -10), -1.9, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, -10), -1.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, -5), -0.2, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 0), 1.2, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 5), 2.5, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 10), 3.6, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 15), 4.6, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 0), 1.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 5), 2.6, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 10), 3.7, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 15), 4.7, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 20), 5.5, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 25), 6.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 30), 7.0, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 35), 7.5, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 40), 7.9, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 35), 7.6, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 40), 8.0, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 45), 8.2, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 50), 8.3, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 55), 8.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 50), 8.4, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 55), 8.4, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 60), 8.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 65), 7.8, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 70), 7.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 75), 6.3, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 80), 5.1, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 85), 3.6, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 90), 1.9, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 90), 1.8, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 95), -0.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 100), -2.2, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 100), -2.3, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 105), -4.4, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 110), -6.5, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 110), -6.6, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 115), -8.4, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 120), -9.9, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 120), -10.0, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 125), -11.0, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 130), -11.4, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 135), -11.3, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 140), -10.7, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 130), -11.5, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 135), -11.4, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 140), -10.8, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 145), -9.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 150), -8.3, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 155), -6.6, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 155), -6.7, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 160), -4.8, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 165), -2.8, 0.34 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(45, 170), -0.8, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 165), -2.9, 0.34 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(45, 170), -0.9, 0.34 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 175), 1.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(45, 180), 3.2, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -180), 2.4, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -175), 4.6, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -170), 6.7, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -175), 4.5, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -170), 6.6, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -165), 8.7, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -160), 10.6, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -155), 12.3, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -150), 13.8, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -145), 15.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -140), 16.0, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -135), 16.5, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -130), 16.6, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -145), 15.0, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -140), 15.9, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -135), 16.4, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -130), 16.5, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -125), 16.2, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -120), 15.3, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -115), 13.8, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -110), 11.6, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -105), 8.7, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -115), 13.7, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -110), 11.5, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -105), 8.6, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -100), 5.1, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -95), 1.0, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -90), -3.4, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -85), -7.7, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -85), -7.6, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -80), -11.4, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -75), -14.4, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -70), -16.6, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -65), -17.8, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -60), -18.2, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -55), -17.9, 0.40 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -50), -17.1, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -70), -16.5, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -65), -17.7, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -60), -18.1, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -55), -17.8, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -50), -17.0, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, -45), -15.8, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -40), -14.3, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -35), -12.5, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -30), -10.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -25), -8.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -20), -6.5, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -15), -4.5, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -10), -2.5, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, -5), -0.7, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 0), 1.0, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 5), 2.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -40), -14.2, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -35), -12.4, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -30), -10.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -25), -8.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -20), -6.4, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -15), -4.4, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -10), -2.4, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, -5), -0.6, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 0), 1.1, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 5), 2.6, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 10), 3.9, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 15), 5.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 20), 6.2, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 15), 5.2, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 20), 6.3, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 25), 7.3, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 30), 8.2, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 30), 8.3, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 35), 9.1, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 40), 9.8, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 45), 10.4, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 50), 10.7, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 50), 10.8, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 55), 10.9, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 60), 10.8, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 65), 10.4, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 60), 10.9, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 65), 10.5, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 70), 9.7, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 75), 8.6, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 80), 7.1, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 85), 5.2, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 85), 5.1, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 90), 2.9, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 95), 0.4, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 95), 0.3, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 100), -2.3, 0.39 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 105), -5.0, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 110), -7.5, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 115), -9.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 120), -11.3, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 125), -12.4, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 115), -9.7, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 120), -11.4, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 125), -12.5, 0.37 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 130), -12.9, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 135), -12.8, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 140), -12.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 145), -11.1, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 150), -9.6, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 155), -7.9, 0.35 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 160), -6.0, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 150), -9.7, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 155), -8.0, 0.35 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 160), -6.1, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 165), -4.0, 0.35 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 170), -1.9, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(50, 175), 0.3, 0.36 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(50, 175), 0.2, 0.36 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(50, 180), 2.4, 0.36 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -180), 1.8, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -175), 4.1, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -180), 1.7, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -175), 4.0, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -170), 6.3, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -165), 8.6, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -160), 10.7, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -155), 12.6, 0.39 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -150), 14.3, 0.40 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -165), 8.5, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -160), 10.6, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -155), 12.5, 0.39 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -150), 14.2, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -145), 15.7, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -140), 16.8, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -135), 17.5, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -130), 17.8, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -130), 17.7, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -125), 17.4, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -120), 16.5, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -115), 14.9, 0.48 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -115), 14.8, 0.48 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -110), 12.4, 0.49 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -105), 9.1, 0.51 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -100), 5.0, 0.52 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -95), 0.4, 0.53 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -90), -4.5, 0.53 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -85), -9.2, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -80), -13.3, 0.51 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -75), -16.5, 0.49 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -70), -18.7, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -65), -19.9, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -60), -20.3, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -55), -19.9, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -50), -19.0, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -45), -17.7, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -40), -16.0, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -80), -13.2, 0.51 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -75), -16.4, 0.49 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -70), -18.6, 0.48 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -65), -19.8, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -60), -20.2, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -55), -19.8, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -50), -18.9, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -45), -17.6, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -40), -15.9, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -35), -14.1, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -30), -12.1, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -30), -12.0, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, -25), -9.9, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -20), -7.8, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -15), -5.6, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -10), -3.4, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, -5), -1.4, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -20), -7.7, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -15), -5.5, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -10), -3.3, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, -5), -1.3, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 0), 0.6, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 5), 2.4, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 10), 4.1, 0.41 + 1.0); @@ -1617,8 +1617,8 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(55, 25), 8.6, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 30), 9.9, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 35), 11.1, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 40), 12.1, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 45), 13.0, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 40), 12.2, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 45), 13.1, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 50), 13.7, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 55), 14.1, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 60), 14.1, 0.43 + 1.0); @@ -1627,13 +1627,13 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(55, 75), 11.5, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 80), 9.6, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 85), 7.2, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 90), 4.4, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 95), 1.2, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 90), 4.3, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 95), 1.1, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 100), -2.2, 0.44 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 105), -5.5, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 110), -8.4, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 110), -8.5, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 115), -10.9, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 120), -12.7, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 120), -12.8, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 125), -13.9, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 130), -14.4, 0.40 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 135), -14.2, 0.39 + 1.0); @@ -1641,60 +1641,60 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(55, 145), -12.4, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 150), -10.9, 0.38 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(55, 155), -9.1, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 160), -7.1, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 165), -5.0, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 170), -2.8, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 175), -0.5, 0.37 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(55, 180), 1.8, 0.38 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -180), 1.2, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -175), 3.6, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -170), 6.0, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -165), 8.4, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 160), -7.2, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 165), -5.1, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 170), -2.9, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 175), -0.6, 0.37 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(55, 180), 1.7, 0.38 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -180), 1.1, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -175), 3.5, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -170), 5.9, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -165), 8.3, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, -160), 10.6, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -155), 12.8, 0.43 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -150), 14.7, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -145), 16.3, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -140), 17.6, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -135), 18.5, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -130), 18.9, 0.50 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -125), 18.7, 0.52 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -155), 12.7, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -150), 14.6, 0.44 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -145), 16.2, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -140), 17.5, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -135), 18.4, 0.48 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -130), 18.8, 0.50 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -125), 18.6, 0.52 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, -120), 17.7, 0.54 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, -115), 15.9, 0.57 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -110), 13.2, 0.59 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -110), 13.1, 0.59 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, -105), 9.4, 0.62 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, -100), 4.7, 0.64 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -95), -0.8, 0.65 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -90), -6.4, 0.65 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -85), -11.6, 0.64 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -80), -16.0, 0.62 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -75), -19.4, 0.59 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -70), -21.6, 0.56 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -65), -22.8, 0.54 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -60), -23.0, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -55), -22.6, 0.50 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -50), -21.6, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -45), -20.1, 0.47 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -40), -18.3, 0.47 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -35), -16.3, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -30), -14.1, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -25), -11.7, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -20), -9.3, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -15), -6.9, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -95), -0.7, 0.65 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -90), -6.3, 0.65 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -85), -11.5, 0.64 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -80), -16.0, 0.61 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -75), -19.3, 0.59 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -70), -21.5, 0.56 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -65), -22.7, 0.54 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -60), -22.9, 0.52 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -55), -22.5, 0.50 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -50), -21.5, 0.48 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -45), -20.0, 0.47 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -40), -18.2, 0.47 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -35), -16.2, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -30), -14.0, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -25), -11.6, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -20), -9.2, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -15), -6.8, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, -10), -4.5, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, -5), -2.2, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, -5), -2.1, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 0), 0.1, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 5), 2.3, 0.45 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 10), 4.3, 0.45 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 10), 4.4, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 15), 6.4, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 20), 8.3, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 25), 10.1, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 20), 8.4, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 25), 10.2, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 30), 11.9, 0.46 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 35), 13.5, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 35), 13.6, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 40), 15.0, 0.47 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 45), 16.2, 0.47 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 45), 16.3, 0.47 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 50), 17.2, 0.47 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 55), 17.8, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 60), 18.0, 0.49 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 55), 17.9, 0.48 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 60), 18.1, 0.49 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 65), 17.8, 0.49 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 70), 16.9, 0.50 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 75), 15.3, 0.51 + 1.0); @@ -1704,21 +1704,21 @@ TEST(GeoLookupTest, declination) EXPECT_NEAR(get_mag_declination_degrees(60, 95), 2.5, 0.54 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 100), -1.7, 0.53 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 105), -5.7, 0.52 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 110), -9.2, 0.51 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 115), -12.0, 0.50 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 110), -9.3, 0.51 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 115), -12.1, 0.50 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 120), -14.1, 0.48 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 125), -15.3, 0.46 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 125), -15.4, 0.46 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 130), -15.8, 0.45 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 135), -15.6, 0.44 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 140), -14.8, 0.43 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 140), -14.9, 0.43 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 145), -13.6, 0.42 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 150), -12.0, 0.42 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 150), -12.1, 0.42 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 155), -10.2, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 160), -8.1, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 165), -5.9, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 170), -3.6, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 160), -8.2, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 165), -6.0, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 170), -3.7, 0.41 + 1.0); EXPECT_NEAR(get_mag_declination_degrees(60, 175), -1.3, 0.41 + 1.0); - EXPECT_NEAR(get_mag_declination_degrees(60, 180), 1.2, 0.41 + 1.0); + EXPECT_NEAR(get_mag_declination_degrees(60, 180), 1.1, 0.41 + 1.0); } TEST(GeoLookupTest, inclination) @@ -1729,7 +1729,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-50, -165), -68.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, -160), -67.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, -155), -66.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-50, -150), -65.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-50, -150), -65.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, -145), -64.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, -140), -64.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, -135), -63.0, 0.21 + 1.2); @@ -1759,10 +1759,10 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-50, -15), -60.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, -10), -61.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, -5), -61.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-50, 0), -60.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-50, 0), -60.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, 5), -60.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, 10), -59.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-50, 15), -59.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-50, 15), -59.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, 20), -59.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, 25), -58.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-50, 30), -59.1, 0.21 + 1.2); @@ -1820,27 +1820,27 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-45, -75), -44.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, -70), -45.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, -65), -45.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, -60), -46.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, -55), -48.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, -50), -50.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, -60), -47.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, -55), -48.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, -50), -50.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, -45), -52.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, -40), -54.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, -35), -56.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, -30), -58.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, -25), -60.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, -40), -55.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, -35), -57.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, -30), -58.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, -25), -60.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, -20), -61.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, -15), -62.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, -10), -63.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, -5), -63.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, 0), -63.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, 0), -63.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 5), -62.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 10), -62.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 15), -61.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 20), -60.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 25), -60.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 30), -59.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, 35), -60.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, 40), -60.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, 35), -60.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, 40), -60.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 45), -61.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 50), -62.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 55), -64.3, 0.21 + 1.2); @@ -1848,9 +1848,9 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-45, 65), -67.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 70), -69.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 75), -70.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, 80), -72.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, 80), -72.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 85), -73.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-45, 90), -74.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-45, 90), -74.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 95), -75.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 100), -76.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-45, 105), -76.9, 0.21 + 1.2); @@ -1881,7 +1881,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-40, -135), -55.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -130), -54.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -125), -53.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, -120), -52.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, -120), -52.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -115), -51.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -110), -50.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -105), -48.6, 0.21 + 1.2); @@ -1890,15 +1890,15 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-40, -90), -43.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -85), -42.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -80), -41.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, -75), -41.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, -75), -41.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -70), -41.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, -65), -42.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, -60), -44.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, -65), -42.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, -60), -44.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -55), -46.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, -50), -48.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, -50), -48.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -45), -51.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -40), -54.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, -35), -56.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, -35), -56.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -30), -58.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -25), -60.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, -20), -62.5, 0.21 + 1.2); @@ -1909,10 +1909,10 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-40, 5), -65.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 10), -64.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 15), -63.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, 20), -62.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, 25), -61.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, 30), -61.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, 35), -60.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, 20), -62.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, 25), -61.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, 30), -60.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, 35), -60.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 40), -61.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 45), -61.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 50), -62.7, 0.21 + 1.2); @@ -1920,9 +1920,9 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-40, 60), -65.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 65), -66.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 70), -68.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, 75), -69.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, 75), -69.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 80), -70.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, 85), -71.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, 85), -71.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 90), -72.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 95), -73.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 100), -73.5, 0.21 + 1.2); @@ -1933,7 +1933,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-40, 125), -72.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 130), -72.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 135), -71.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-40, 140), -71.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-40, 140), -71.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 145), -70.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 150), -69.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-40, 155), -69.1, 0.21 + 1.2); @@ -1966,24 +1966,24 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-35, -75), -36.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -70), -36.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -65), -38.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, -60), -40.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, -55), -43.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, -50), -46.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, -60), -40.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, -55), -43.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, -50), -46.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -45), -49.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, -40), -52.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, -40), -52.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -35), -55.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, -30), -58.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, -30), -58.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -25), -60.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -20), -62.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, -15), -64.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, -15), -64.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -10), -65.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, -5), -66.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, 0), -67.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, 0), -67.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, 5), -67.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, 10), -66.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, 15), -65.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, 15), -65.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, 20), -64.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-35, 25), -63.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-35, 25), -63.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, 30), -62.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, 35), -61.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-35, 40), -61.1, 0.21 + 1.2); @@ -2036,28 +2036,28 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-30, -90), -33.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, -85), -31.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, -80), -30.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -75), -30.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -70), -31.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -75), -30.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -70), -31.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, -65), -33.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -60), -36.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -55), -39.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -50), -43.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -45), -46.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -40), -50.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -35), -53.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -30), -56.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -25), -59.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -20), -61.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -60), -36.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -55), -39.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -50), -43.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -45), -46.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -40), -50.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -35), -53.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -30), -56.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -25), -59.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -20), -61.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, -15), -63.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, -10), -65.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, -5), -66.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, -5), -66.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 0), -67.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 5), -67.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 10), -67.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 15), -66.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, 20), -65.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, 20), -65.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 25), -63.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, 30), -62.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, 30), -62.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 35), -61.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 40), -60.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 45), -60.2, 0.21 + 1.2); @@ -2084,7 +2084,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-30, 150), -60.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 155), -60.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 160), -59.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-30, 165), -58.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-30, 165), -58.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 170), -57.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 175), -56.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-30, 180), -55.0, 0.21 + 1.2); @@ -2092,11 +2092,11 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-25, -175), -47.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -170), -46.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -165), -45.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -160), -44.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -160), -44.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -155), -43.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -150), -42.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -145), -40.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -140), -39.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -140), -39.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -135), -38.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -130), -37.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -125), -36.3, 0.21 + 1.2); @@ -2110,28 +2110,28 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-25, -85), -24.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -80), -23.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, -75), -23.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -70), -24.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -65), -27.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -60), -30.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -55), -34.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -50), -38.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -45), -42.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -40), -46.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -35), -50.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -30), -53.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -25), -56.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -20), -59.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -15), -61.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -10), -63.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, -5), -65.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -70), -25.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -65), -27.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -60), -30.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -55), -34.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -50), -38.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -45), -43.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -40), -46.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -35), -50.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -30), -53.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -25), -56.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -20), -59.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -15), -61.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -10), -63.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, -5), -65.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 0), -66.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 5), -66.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 10), -66.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 15), -65.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, 20), -64.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, 20), -64.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 25), -62.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, 30), -60.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, 35), -59.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, 30), -60.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, 35), -59.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 40), -58.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 45), -57.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 50), -57.5, 0.21 + 1.2); @@ -2154,26 +2154,26 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-25, 135), -56.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 140), -56.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 145), -56.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, 150), -55.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, 150), -55.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 155), -54.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 160), -53.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-25, 165), -52.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-25, 165), -52.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 170), -51.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 175), -50.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-25, 180), -49.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -180), -42.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -180), -42.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -175), -40.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -170), -39.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -165), -38.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -160), -37.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -155), -36.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -150), -34.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -150), -34.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -145), -33.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -140), -32.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -135), -31.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -135), -30.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -130), -29.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -125), -28.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -120), -27.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -120), -27.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -115), -26.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -110), -25.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -105), -23.8, 0.21 + 1.2); @@ -2181,21 +2181,21 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-20, -95), -20.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -90), -18.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -85), -16.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -80), -15.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -75), -15.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -70), -17.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -65), -20.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -60), -23.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -55), -28.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -50), -33.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -45), -38.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -40), -42.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -35), -46.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -30), -50.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -25), -53.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -20), -56.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -80), -15.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -75), -15.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -70), -17.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -65), -20.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -60), -24.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -55), -28.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -50), -33.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -45), -38.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -40), -42.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -35), -46.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -30), -50.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -25), -53.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -20), -56.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -15), -58.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, -10), -60.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, -10), -60.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, -5), -62.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 0), -63.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 5), -63.3, 0.21 + 1.2); @@ -2203,7 +2203,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-20, 15), -62.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 20), -60.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 25), -59.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, 30), -57.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, 30), -57.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 35), -55.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 40), -54.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 45), -53.2, 0.21 + 1.2); @@ -2211,7 +2211,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-20, 55), -52.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 60), -53.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 65), -53.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, 70), -54.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, 70), -54.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 75), -54.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 80), -54.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 85), -55.0, 0.21 + 1.2); @@ -2221,7 +2221,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-20, 105), -53.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 110), -52.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 115), -51.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, 120), -51.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, 120), -51.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 125), -51.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 130), -50.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 135), -50.6, 0.21 + 1.2); @@ -2233,17 +2233,17 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-20, 165), -46.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 170), -44.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-20, 175), -43.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-20, 180), -42.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-20, 180), -42.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -180), -34.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -175), -32.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -170), -31.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -165), -30.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -170), -31.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -165), -30.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -160), -28.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -155), -27.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -150), -26.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -145), -25.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -140), -23.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -135), -22.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -150), -26.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -145), -25.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -140), -23.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -135), -22.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -130), -21.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -125), -20.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -120), -18.9, 0.21 + 1.2); @@ -2253,22 +2253,22 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-15, -100), -13.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -95), -11.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -90), -9.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -85), -7.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -80), -6.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -85), -7.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -80), -6.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -75), -7.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -70), -9.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -65), -12.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -60), -16.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -55), -21.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -50), -26.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -45), -32.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -40), -37.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -35), -41.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -30), -45.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -25), -48.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -20), -51.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -65), -12.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -60), -16.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -55), -21.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -50), -26.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -45), -32.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -40), -37.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -35), -41.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -30), -45.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -25), -49.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -20), -51.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -15), -54.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, -10), -55.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, -10), -55.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, -5), -57.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 0), -57.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 5), -57.9, 0.21 + 1.2); @@ -2276,35 +2276,35 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-15, 15), -56.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 20), -55.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 25), -53.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 30), -51.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 35), -49.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 40), -47.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 45), -46.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 50), -46.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 30), -51.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 35), -49.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 40), -47.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 45), -46.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 50), -46.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 55), -46.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 60), -46.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 65), -46.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 70), -46.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 75), -47.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 80), -47.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 85), -47.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 85), -47.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 90), -47.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 95), -47.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 100), -46.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 105), -45.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 110), -44.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 105), -45.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 110), -44.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 115), -44.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 120), -43.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 120), -43.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 125), -43.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 130), -43.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 135), -43.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 140), -43.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 145), -42.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 150), -42.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 155), -41.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 160), -40.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 145), -42.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 150), -42.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 155), -41.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 160), -40.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 165), -38.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-15, 170), -37.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-15, 170), -37.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 175), -35.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-15, 180), -34.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -180), -25.3, 0.21 + 1.2); @@ -2312,37 +2312,37 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-10, -170), -22.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -165), -20.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -160), -19.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -155), -18.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -150), -17.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -145), -15.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -140), -14.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -155), -18.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -150), -16.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -145), -15.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -140), -14.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -135), -13.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -130), -11.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -125), -10.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -120), -9.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -115), -8.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -115), -8.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -110), -6.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -105), -5.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -100), -3.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -95), -1.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -90), 0.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -85), 2.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -80), 2.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -75), 1.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -70), -0.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -65), -3.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -60), -8.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -55), -13.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -50), -19.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -45), -24.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -40), -30.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -35), -35.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -30), -39.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -25), -42.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -20), -45.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -15), -47.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -80), 2.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -75), 1.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -70), -0.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -65), -3.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -60), -8.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -55), -13.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -50), -19.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -45), -25.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -40), -30.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -35), -35.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -30), -39.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -25), -42.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -20), -45.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -15), -47.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, -10), -49.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, -5), -49.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, -5), -50.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 0), -50.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 5), -50.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 10), -49.9, 0.21 + 1.2); @@ -2350,7 +2350,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-10, 20), -47.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 25), -45.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 30), -43.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, 35), -41.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, 35), -41.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 40), -39.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 45), -38.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 50), -37.7, 0.21 + 1.2); @@ -2364,14 +2364,14 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-10, 90), -38.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 95), -38.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 100), -37.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, 105), -36.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, 110), -36.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, 105), -36.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, 110), -36.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 115), -35.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 120), -35.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 125), -35.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 130), -35.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 135), -35.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-10, 140), -35.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-10, 140), -35.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 145), -34.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 150), -34.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-10, 155), -33.1, 0.21 + 1.2); @@ -2382,11 +2382,11 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-10, 180), -25.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -180), -15.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -175), -13.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -170), -12.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -170), -12.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -165), -10.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -160), -9.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -155), -8.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -150), -6.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -150), -6.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -145), -5.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -140), -4.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -135), -3.0, 0.21 + 1.2); @@ -2394,25 +2394,25 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-5, -125), -0.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -120), 0.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -115), 1.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -110), 3.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -110), 3.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -105), 4.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -100), 6.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -95), 8.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -90), 10.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -85), 11.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -80), 11.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -80), 11.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -75), 10.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -70), 8.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -65), 5.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -60), 0.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -55), -4.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -50), -10.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -45), -16.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -40), -22.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -35), -27.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -30), -31.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -25), -35.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, -20), -37.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -70), 8.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -65), 5.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -60), 0.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -55), -4.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -50), -10.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -45), -16.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -40), -22.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -35), -27.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -30), -31.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -25), -35.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, -20), -37.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -15), -39.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -10), -40.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, -5), -41.0, 0.21 + 1.2); @@ -2421,70 +2421,70 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(-5, 10), -40.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 15), -39.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 20), -37.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 25), -35.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 30), -33.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 25), -35.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 30), -33.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 35), -31.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 40), -29.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 40), -29.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 45), -28.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 50), -27.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 55), -27.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 50), -27.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 55), -27.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 60), -27.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 65), -27.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 65), -27.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 70), -27.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 75), -28.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 75), -28.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 80), -28.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 85), -28.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 90), -28.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 90), -28.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 95), -28.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 100), -27.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 105), -27.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 100), -27.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 105), -26.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 110), -26.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 115), -25.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 120), -25.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 125), -25.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 125), -25.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 130), -26.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 135), -26.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 140), -26.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 145), -25.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 140), -26.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 145), -26.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 150), -25.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 155), -24.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 155), -24.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 160), -22.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(-5, 165), -21.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(-5, 165), -21.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 170), -19.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 175), -17.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(-5, 180), -15.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -180), -5.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -175), -3.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -170), -1.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -170), -1.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -165), -0.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -160), 1.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -155), 2.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -150), 3.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -150), 3.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -145), 4.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -140), 5.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -135), 7.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -140), 6.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -135), 7.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -130), 8.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -125), 9.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -120), 10.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -115), 11.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -115), 11.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -110), 13.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -105), 14.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -100), 16.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -95), 18.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -90), 19.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -90), 19.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -85), 20.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -80), 20.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -75), 19.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -70), 17.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -65), 14.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -60), 9.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -55), 4.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -50), -1.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -45), -7.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -40), -12.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -35), -18.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -30), -22.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, -25), -25.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -75), 19.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -70), 17.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -65), 14.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -60), 9.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -55), 4.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -50), -1.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -45), -7.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -40), -13.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -35), -18.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -30), -22.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, -25), -25.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -20), -27.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -15), -29.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, -10), -30.1, 0.21 + 1.2); @@ -2495,48 +2495,48 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(0, 15), -28.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 20), -26.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 25), -24.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 30), -22.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 30), -22.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 35), -20.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 40), -18.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 40), -18.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 45), -17.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 50), -16.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 55), -16.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 60), -16.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 60), -15.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 65), -16.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 70), -16.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 75), -16.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 75), -16.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 80), -17.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 85), -17.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 90), -17.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 95), -17.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 100), -16.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 105), -16.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 110), -15.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 100), -16.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 105), -15.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 110), -15.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 115), -15.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 120), -15.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 125), -15.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 130), -16.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 135), -16.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 140), -16.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 145), -16.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 150), -15.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 145), -16.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 150), -15.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 155), -14.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 160), -13.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 165), -11.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 170), -9.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(0, 175), -7.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(0, 175), -7.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(0, 180), -5.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -180), 5.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -175), 7.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -170), 8.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -170), 8.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -165), 10.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -160), 11.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -155), 12.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -150), 13.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -145), 14.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -140), 15.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -135), 16.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -130), 18.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -135), 17.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -130), 18.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -125), 19.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -120), 20.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -115), 21.2, 0.21 + 1.2); @@ -2548,52 +2548,52 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(5, -85), 28.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -80), 28.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -75), 27.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -70), 25.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -65), 22.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -60), 18.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -55), 13.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -50), 8.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -45), 2.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -40), -2.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -35), -7.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -30), -11.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -25), -14.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -70), 25.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -65), 22.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -60), 18.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -55), 13.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -50), 8.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -45), 2.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -40), -2.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -35), -7.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -30), -11.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -25), -14.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -20), -16.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -15), -17.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, -10), -18.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, -5), -18.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 0), -18.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, -5), -18.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 0), -18.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 5), -17.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 10), -16.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 15), -15.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 20), -14.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 25), -12.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 25), -12.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 30), -10.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 35), -8.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 40), -6.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 35), -7.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 40), -6.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 45), -4.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 50), -4.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 55), -3.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 50), -4.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 55), -3.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 60), -3.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 65), -3.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 70), -4.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 75), -4.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 80), -4.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 80), -4.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 85), -5.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 90), -5.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 95), -5.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 100), -4.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 105), -4.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 90), -5.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 95), -5.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 100), -4.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 105), -4.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 110), -3.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 115), -3.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 115), -3.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 120), -3.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 125), -4.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 125), -4.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 130), -5.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 135), -5.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 140), -6.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 140), -6.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 145), -6.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 150), -5.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(5, 155), -4.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(5, 155), -4.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 160), -3.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 165), -1.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(5, 170), 0.6, 0.21 + 1.2); @@ -2605,10 +2605,10 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(10, -165), 19.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -160), 20.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -155), 21.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -150), 22.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -145), 23.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -150), 22.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -145), 23.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -140), 24.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -135), 25.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -135), 26.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -130), 27.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -125), 28.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -120), 29.0, 0.21 + 1.2); @@ -2617,21 +2617,21 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(10, -105), 32.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -100), 33.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -95), 34.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -90), 35.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -90), 35.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -85), 36.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -80), 35.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -80), 35.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -75), 34.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -70), 32.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -65), 30.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -60), 26.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -55), 22.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -50), 17.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -45), 12.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -40), 7.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -35), 3.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -30), -0.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -70), 32.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -65), 30.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -60), 26.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -55), 22.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -50), 17.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -45), 12.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -40), 7.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -35), 3.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -30), -0.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -25), -2.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, -20), -4.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, -20), -4.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -15), -5.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -10), -5.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, -5), -5.5, 0.21 + 1.2); @@ -2640,32 +2640,32 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(10, 10), -3.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 15), -2.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 20), -1.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 25), 0.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 30), 2.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 25), 0.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 30), 2.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 35), 4.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 40), 6.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 45), 7.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 50), 8.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 55), 8.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 40), 6.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 45), 7.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 50), 8.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 55), 8.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 60), 8.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 65), 8.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 65), 8.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 70), 8.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 75), 7.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 80), 7.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 85), 7.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 90), 7.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 95), 7.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 100), 7.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 75), 8.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 80), 7.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 85), 7.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 90), 7.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 95), 7.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 100), 7.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 105), 7.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 110), 7.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 115), 7.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 115), 7.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 120), 7.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 125), 6.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 130), 5.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 135), 5.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 140), 4.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 145), 4.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(10, 150), 4.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 145), 4.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(10, 150), 4.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 155), 5.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 160), 6.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(10, 165), 8.5, 0.21 + 1.2); @@ -2677,34 +2677,34 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(15, -170), 26.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -165), 28.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -160), 29.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -155), 30.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -150), 31.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -145), 31.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -140), 32.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -135), 33.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -130), 34.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -155), 30.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -150), 31.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -145), 32.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -140), 33.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -135), 34.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -130), 35.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -125), 35.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -120), 36.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -115), 37.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -115), 37.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -110), 38.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -105), 39.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -100), 41.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -95), 41.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -90), 42.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -85), 42.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -85), 42.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -80), 42.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -75), 41.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -70), 39.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -65), 36.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -60), 33.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -55), 30.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -50), 26.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -45), 21.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -40), 18.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -35), 14.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -30), 11.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -70), 39.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -65), 36.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -60), 33.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -55), 30.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -50), 25.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -45), 21.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -40), 17.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -35), 14.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -30), 11.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -25), 9.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, -20), 7.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, -20), 7.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -15), 7.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -10), 7.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, -5), 7.3, 0.21 + 1.2); @@ -2716,10 +2716,10 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(15, 25), 13.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 30), 14.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 35), 16.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, 40), 17.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, 40), 18.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 45), 19.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, 50), 19.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, 55), 19.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, 50), 19.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, 55), 20.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 60), 20.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 65), 20.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 70), 19.9, 0.21 + 1.2); @@ -2727,8 +2727,8 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(15, 80), 19.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 85), 19.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 90), 19.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, 95), 18.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, 100), 19.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, 95), 19.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, 100), 19.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 105), 19.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 110), 19.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 115), 19.0, 0.21 + 1.2); @@ -2736,9 +2736,9 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(15, 125), 17.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 130), 16.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 135), 15.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, 140), 15.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, 140), 14.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 145), 14.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(15, 150), 14.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(15, 150), 14.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 155), 15.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 160), 16.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(15, 165), 17.8, 0.21 + 1.2); @@ -2753,7 +2753,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(20, -155), 37.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -150), 38.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -145), 38.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -140), 39.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -140), 39.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -135), 40.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -130), 41.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -125), 42.8, 0.21 + 1.2); @@ -2767,18 +2767,18 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(20, -85), 48.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -80), 48.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -75), 46.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -70), 45.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -65), 43.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -60), 40.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -55), 37.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -50), 34.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -45), 30.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -40), 27.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -35), 24.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -30), 22.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -70), 45.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -65), 43.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -60), 40.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -55), 37.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -50), 33.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -45), 30.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -40), 27.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -35), 24.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -30), 22.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -25), 20.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -20), 19.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, -15), 19.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, -15), 19.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -10), 19.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, -5), 19.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 0), 20.0, 0.21 + 1.2); @@ -2786,24 +2786,24 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(20, 10), 21.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 15), 22.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 20), 23.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, 25), 24.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, 25), 24.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 30), 26.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 35), 27.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 40), 28.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 45), 29.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 50), 30.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, 55), 30.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, 55), 30.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 60), 30.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 65), 30.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, 70), 30.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, 75), 30.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, 70), 30.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, 75), 30.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 80), 30.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, 85), 30.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, 85), 30.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 90), 29.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 95), 29.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 100), 29.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 105), 29.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(20, 110), 29.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(20, 110), 29.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 115), 29.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 120), 28.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(20, 125), 27.6, 0.21 + 1.2); @@ -2823,8 +2823,8 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(25, -170), 40.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -165), 41.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -160), 42.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -155), 43.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -150), 43.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -155), 43.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -150), 44.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -145), 44.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -140), 45.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -135), 46.7, 0.21 + 1.2); @@ -2840,16 +2840,16 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(25, -85), 53.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -80), 53.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -75), 52.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -70), 50.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -70), 50.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -65), 48.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -60), 46.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -60), 46.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -55), 43.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -50), 41.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -45), 38.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -40), 36.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -35), 34.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -45), 38.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -40), 36.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -35), 34.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -30), 32.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, -25), 31.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, -25), 31.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -20), 30.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -15), 29.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, -10), 29.9, 0.21 + 1.2); @@ -2863,20 +2863,20 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(25, 30), 36.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 35), 37.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 40), 38.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 45), 38.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 45), 39.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 50), 39.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 55), 39.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 60), 39.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 65), 39.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 70), 39.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 55), 39.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 60), 39.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 65), 39.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 70), 39.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 75), 39.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 80), 39.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 85), 39.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 90), 39.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 80), 39.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 85), 39.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 90), 39.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 95), 39.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 100), 39.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 105), 39.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 110), 38.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 110), 39.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 115), 38.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 120), 37.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 125), 36.8, 0.21 + 1.2); @@ -2885,8 +2885,8 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(25, 140), 33.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 145), 33.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 150), 32.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 155), 32.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(25, 160), 33.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 155), 32.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(25, 160), 33.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 165), 33.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 170), 34.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(25, 175), 36.2, 0.21 + 1.2); @@ -2898,10 +2898,10 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(30, -160), 47.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -155), 48.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -150), 49.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -145), 49.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -145), 49.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -140), 50.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -135), 51.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -130), 52.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -130), 52.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -125), 53.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -120), 54.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -115), 55.8, 0.21 + 1.2); @@ -2912,45 +2912,45 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(30, -90), 58.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -85), 58.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -80), 57.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -75), 56.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -70), 55.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -75), 56.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -70), 55.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -65), 53.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -60), 51.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -55), 49.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -55), 49.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -50), 47.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -45), 45.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -40), 44.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -35), 42.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -45), 45.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -40), 43.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -35), 42.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -30), 41.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -25), 40.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -20), 39.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, -15), 39.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, -15), 39.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -10), 39.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, -5), 39.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 0), 40.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 5), 40.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 10), 41.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 15), 42.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 15), 42.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 20), 42.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 25), 43.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 30), 44.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 35), 45.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 25), 43.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 30), 44.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 35), 45.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 40), 46.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 45), 46.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 50), 47.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 55), 47.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 60), 47.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 55), 47.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 60), 47.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 65), 47.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 70), 47.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 75), 47.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 80), 47.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 85), 47.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 90), 47.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 90), 47.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 95), 47.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 100), 47.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 105), 47.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 110), 47.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 115), 46.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 115), 46.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 120), 45.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 125), 44.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 130), 43.7, 0.21 + 1.2); @@ -2961,7 +2961,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(30, 155), 40.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 160), 40.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 165), 40.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(30, 170), 41.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(30, 170), 41.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 175), 42.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(30, 180), 43.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -180), 48.4, 0.21 + 1.2); @@ -2988,15 +2988,15 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(35, -75), 61.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -70), 60.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -65), 58.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, -60), 56.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, -55), 55.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, -50), 53.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, -45), 52.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, -60), 56.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, -55), 55.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, -50), 53.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, -45), 52.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -40), 50.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -35), 49.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -30), 48.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -25), 47.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, -20), 47.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, -20), 47.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -15), 47.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -10), 47.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, -5), 47.7, 0.21 + 1.2); @@ -3011,20 +3011,20 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(35, 40), 53.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 45), 53.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 50), 54.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, 55), 54.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, 55), 54.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 60), 54.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 65), 54.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 70), 54.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 75), 54.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 80), 54.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, 85), 54.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, 85), 54.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 90), 54.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, 95), 54.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, 95), 54.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 100), 54.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 105), 54.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 110), 54.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, 115), 53.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(35, 120), 52.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, 115), 53.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(35, 120), 52.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 125), 51.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 130), 50.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(35, 135), 49.6, 0.21 + 1.2); @@ -3056,13 +3056,13 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(40, -100), 66.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -95), 67.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -90), 67.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, -85), 67.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, -85), 66.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -80), 66.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -75), 65.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, -70), 64.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, -70), 64.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -65), 62.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -60), 61.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, -55), 60.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, -55), 60.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -50), 58.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -45), 57.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, -40), 56.6, 0.21 + 1.2); @@ -3075,14 +3075,14 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(40, -5), 54.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 0), 54.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 5), 55.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, 10), 55.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, 10), 55.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 15), 56.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 20), 56.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 25), 57.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, 30), 57.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, 30), 58.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 35), 58.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, 40), 58.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, 45), 59.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, 40), 59.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, 45), 59.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 50), 59.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 55), 59.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 60), 60.1, 0.21 + 1.2); @@ -3090,15 +3090,15 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(40, 70), 60.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 75), 60.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 80), 60.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, 85), 60.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, 85), 61.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 90), 61.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 95), 61.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 100), 60.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, 105), 60.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, 105), 60.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 110), 60.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 115), 59.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 120), 58.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(40, 125), 57.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(40, 125), 57.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 130), 56.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 135), 55.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(40, 140), 54.6, 0.21 + 1.2); @@ -3132,16 +3132,16 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(45, -85), 70.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -80), 70.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -75), 69.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, -70), 68.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, -70), 68.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -65), 67.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, -60), 65.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, -60), 65.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -55), 64.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -50), 63.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -45), 62.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -40), 61.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -35), 61.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -30), 60.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, -25), 60.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, -25), 60.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -20), 59.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -15), 59.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, -10), 60.0, 0.21 + 1.2); @@ -3150,25 +3150,25 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(45, 5), 60.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 10), 61.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 15), 61.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 20), 62.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 20), 62.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 25), 62.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 30), 63.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 35), 63.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 40), 63.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 45), 64.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 50), 64.4, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 55), 64.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 45), 64.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 50), 64.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 55), 64.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 60), 65.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 65), 65.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 70), 65.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 70), 65.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 75), 65.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 80), 66.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 85), 66.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 90), 66.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 80), 66.1, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 85), 66.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 90), 66.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 95), 66.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 100), 66.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 105), 66.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(45, 110), 65.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(45, 110), 65.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 115), 64.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 120), 64.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(45, 125), 63.2, 0.21 + 1.2); @@ -3205,8 +3205,8 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(50, -85), 74.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, -80), 73.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, -75), 72.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(50, -70), 72.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(50, -65), 71.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(50, -70), 71.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(50, -65), 70.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, -60), 69.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, -55), 68.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, -50), 67.9, 0.21 + 1.2); @@ -3226,20 +3226,20 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(50, 20), 66.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 25), 66.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 30), 67.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(50, 35), 67.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(50, 35), 67.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 40), 67.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 45), 68.2, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(50, 50), 68.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(50, 50), 68.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 55), 68.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 60), 69.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 65), 69.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(50, 70), 69.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(50, 70), 70.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 75), 70.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 80), 70.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 85), 70.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 90), 71.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 95), 71.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(50, 100), 70.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(50, 100), 71.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 105), 70.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 110), 70.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 115), 69.6, 0.21 + 1.2); @@ -3248,7 +3248,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(50, 130), 66.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 135), 65.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 140), 64.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(50, 145), 64.0, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(50, 145), 64.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 150), 63.3, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 155), 62.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(50, 160), 62.2, 0.21 + 1.2); @@ -3273,18 +3273,18 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(55, -110), 76.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -105), 77.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -100), 77.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, -95), 77.8, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, -90), 77.8, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, -95), 77.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, -90), 77.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -85), 77.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, -80), 77.0, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, -75), 76.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, -80), 76.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, -75), 76.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -70), 75.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -65), 74.5, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, -60), 73.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, -55), 72.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, -60), 73.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, -55), 72.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -50), 71.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -45), 71.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, -40), 70.5, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, -40), 70.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -35), 69.9, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -30), 69.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, -25), 69.2, 0.21 + 1.2); @@ -3305,7 +3305,7 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(55, 50), 72.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, 55), 72.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, 60), 72.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(55, 65), 73.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(55, 65), 73.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, 70), 73.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, 75), 74.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(55, 80), 74.6, 0.21 + 1.2); @@ -3350,13 +3350,13 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(60, -90), 80.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -85), 80.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -80), 79.9, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, -75), 79.3, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, -75), 79.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -70), 78.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -65), 77.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, -60), 76.9, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, -60), 76.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -55), 76.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -50), 75.3, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, -45), 74.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, -45), 74.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -40), 74.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -35), 73.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, -30), 73.2, 0.21 + 1.2); @@ -3373,20 +3373,20 @@ TEST(GeoLookupTest, inclination) EXPECT_NEAR(get_mag_inclination_degrees(60, 25), 73.6, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 30), 73.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 35), 74.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, 40), 74.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, 40), 74.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 45), 74.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 50), 75.2, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 55), 75.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, 60), 76.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, 65), 76.6, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, 70), 77.1, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, 75), 77.6, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, 60), 76.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, 65), 76.7, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, 70), 77.2, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, 75), 77.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 80), 78.1, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 85), 78.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 90), 78.7, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 95), 78.8, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 100), 78.7, 0.21 + 1.2); - EXPECT_NEAR(get_mag_inclination_degrees(60, 105), 78.4, 0.21 + 1.2); + EXPECT_NEAR(get_mag_inclination_degrees(60, 105), 78.5, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 110), 78.0, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 115), 77.4, 0.21 + 1.2); EXPECT_NEAR(get_mag_inclination_degrees(60, 120), 76.7, 0.21 + 1.2); @@ -3406,1683 +3406,1683 @@ TEST(GeoLookupTest, inclination) TEST(GeoLookupTest, strength) { - EXPECT_NEAR(get_mag_strength_tesla(-50, -180) * 1e9, 58381, 145 + 584); - EXPECT_NEAR(get_mag_strength_tesla(-50, -175) * 1e9, 57229, 145 + 572); - EXPECT_NEAR(get_mag_strength_tesla(-50, -170) * 1e9, 56063, 145 + 561); - EXPECT_NEAR(get_mag_strength_tesla(-50, -165) * 1e9, 54893, 145 + 549); - EXPECT_NEAR(get_mag_strength_tesla(-50, -160) * 1e9, 53726, 145 + 537); - EXPECT_NEAR(get_mag_strength_tesla(-50, -155) * 1e9, 52562, 145 + 526); - EXPECT_NEAR(get_mag_strength_tesla(-50, -150) * 1e9, 51404, 145 + 514); - EXPECT_NEAR(get_mag_strength_tesla(-50, -145) * 1e9, 50243, 145 + 502); - EXPECT_NEAR(get_mag_strength_tesla(-50, -140) * 1e9, 49068, 145 + 491); - EXPECT_NEAR(get_mag_strength_tesla(-50, -135) * 1e9, 47864, 145 + 479); - EXPECT_NEAR(get_mag_strength_tesla(-50, -130) * 1e9, 46612, 145 + 466); - EXPECT_NEAR(get_mag_strength_tesla(-50, -125) * 1e9, 45295, 145 + 453); - EXPECT_NEAR(get_mag_strength_tesla(-50, -120) * 1e9, 43900, 145 + 439); - EXPECT_NEAR(get_mag_strength_tesla(-50, -115) * 1e9, 42422, 145 + 424); - EXPECT_NEAR(get_mag_strength_tesla(-50, -110) * 1e9, 40865, 145 + 409); - EXPECT_NEAR(get_mag_strength_tesla(-50, -105) * 1e9, 39243, 145 + 392); - EXPECT_NEAR(get_mag_strength_tesla(-50, -100) * 1e9, 37579, 145 + 376); - EXPECT_NEAR(get_mag_strength_tesla(-50, -95) * 1e9, 35908, 145 + 359); - EXPECT_NEAR(get_mag_strength_tesla(-50, -90) * 1e9, 34268, 145 + 343); - EXPECT_NEAR(get_mag_strength_tesla(-50, -85) * 1e9, 32705, 145 + 327); - EXPECT_NEAR(get_mag_strength_tesla(-50, -80) * 1e9, 31261, 145 + 313); - EXPECT_NEAR(get_mag_strength_tesla(-50, -75) * 1e9, 29976, 145 + 300); - EXPECT_NEAR(get_mag_strength_tesla(-50, -70) * 1e9, 28878, 145 + 289); - EXPECT_NEAR(get_mag_strength_tesla(-50, -65) * 1e9, 27982, 145 + 280); - EXPECT_NEAR(get_mag_strength_tesla(-50, -60) * 1e9, 27283, 145 + 273); - EXPECT_NEAR(get_mag_strength_tesla(-50, -55) * 1e9, 26762, 145 + 268); - EXPECT_NEAR(get_mag_strength_tesla(-50, -50) * 1e9, 26384, 145 + 264); - EXPECT_NEAR(get_mag_strength_tesla(-50, -45) * 1e9, 26111, 145 + 261); - EXPECT_NEAR(get_mag_strength_tesla(-50, -40) * 1e9, 25901, 145 + 259); - EXPECT_NEAR(get_mag_strength_tesla(-50, -35) * 1e9, 25721, 145 + 257); - EXPECT_NEAR(get_mag_strength_tesla(-50, -30) * 1e9, 25548, 145 + 255); - EXPECT_NEAR(get_mag_strength_tesla(-50, -25) * 1e9, 25373, 145 + 254); - EXPECT_NEAR(get_mag_strength_tesla(-50, -20) * 1e9, 25198, 145 + 252); - EXPECT_NEAR(get_mag_strength_tesla(-50, -15) * 1e9, 25040, 145 + 250); - EXPECT_NEAR(get_mag_strength_tesla(-50, -10) * 1e9, 24925, 145 + 249); - EXPECT_NEAR(get_mag_strength_tesla(-50, -5) * 1e9, 24890, 145 + 249); - EXPECT_NEAR(get_mag_strength_tesla(-50, 0) * 1e9, 24979, 145 + 250); - EXPECT_NEAR(get_mag_strength_tesla(-50, 5) * 1e9, 25242, 145 + 252); - EXPECT_NEAR(get_mag_strength_tesla(-50, 10) * 1e9, 25725, 145 + 257); - EXPECT_NEAR(get_mag_strength_tesla(-50, 15) * 1e9, 26469, 145 + 265); - EXPECT_NEAR(get_mag_strength_tesla(-50, 20) * 1e9, 27500, 145 + 275); - EXPECT_NEAR(get_mag_strength_tesla(-50, 25) * 1e9, 28830, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(-50, 30) * 1e9, 30449, 145 + 304); - EXPECT_NEAR(get_mag_strength_tesla(-50, 35) * 1e9, 32336, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(-50, 40) * 1e9, 34454, 145 + 345); - EXPECT_NEAR(get_mag_strength_tesla(-50, 45) * 1e9, 36757, 145 + 368); - EXPECT_NEAR(get_mag_strength_tesla(-50, 50) * 1e9, 39196, 145 + 392); - EXPECT_NEAR(get_mag_strength_tesla(-50, 55) * 1e9, 41719, 145 + 417); - EXPECT_NEAR(get_mag_strength_tesla(-50, 60) * 1e9, 44280, 145 + 443); - EXPECT_NEAR(get_mag_strength_tesla(-50, 65) * 1e9, 46832, 145 + 468); - EXPECT_NEAR(get_mag_strength_tesla(-50, 70) * 1e9, 49338, 145 + 493); - EXPECT_NEAR(get_mag_strength_tesla(-50, 75) * 1e9, 51765, 145 + 518); - EXPECT_NEAR(get_mag_strength_tesla(-50, 80) * 1e9, 54080, 145 + 541); - EXPECT_NEAR(get_mag_strength_tesla(-50, 85) * 1e9, 56254, 145 + 563); - EXPECT_NEAR(get_mag_strength_tesla(-50, 90) * 1e9, 58256, 145 + 583); - EXPECT_NEAR(get_mag_strength_tesla(-50, 95) * 1e9, 60058, 145 + 601); - EXPECT_NEAR(get_mag_strength_tesla(-50, 100) * 1e9, 61633, 145 + 616); - EXPECT_NEAR(get_mag_strength_tesla(-50, 105) * 1e9, 62963, 145 + 630); - EXPECT_NEAR(get_mag_strength_tesla(-50, 110) * 1e9, 64035, 145 + 640); - EXPECT_NEAR(get_mag_strength_tesla(-50, 115) * 1e9, 64845, 145 + 648); - EXPECT_NEAR(get_mag_strength_tesla(-50, 120) * 1e9, 65399, 145 + 654); - EXPECT_NEAR(get_mag_strength_tesla(-50, 125) * 1e9, 65709, 145 + 657); - EXPECT_NEAR(get_mag_strength_tesla(-50, 130) * 1e9, 65791, 145 + 658); - EXPECT_NEAR(get_mag_strength_tesla(-50, 135) * 1e9, 65664, 145 + 657); - EXPECT_NEAR(get_mag_strength_tesla(-50, 140) * 1e9, 65349, 145 + 653); + EXPECT_NEAR(get_mag_strength_tesla(-50, -180) * 1e9, 58366, 145 + 584); + EXPECT_NEAR(get_mag_strength_tesla(-50, -175) * 1e9, 57212, 145 + 572); + EXPECT_NEAR(get_mag_strength_tesla(-50, -170) * 1e9, 56045, 145 + 560); + EXPECT_NEAR(get_mag_strength_tesla(-50, -165) * 1e9, 54873, 145 + 549); + EXPECT_NEAR(get_mag_strength_tesla(-50, -160) * 1e9, 53703, 145 + 537); + EXPECT_NEAR(get_mag_strength_tesla(-50, -155) * 1e9, 52538, 145 + 525); + EXPECT_NEAR(get_mag_strength_tesla(-50, -150) * 1e9, 51377, 145 + 514); + EXPECT_NEAR(get_mag_strength_tesla(-50, -145) * 1e9, 50215, 145 + 502); + EXPECT_NEAR(get_mag_strength_tesla(-50, -140) * 1e9, 49039, 145 + 490); + EXPECT_NEAR(get_mag_strength_tesla(-50, -135) * 1e9, 47834, 145 + 478); + EXPECT_NEAR(get_mag_strength_tesla(-50, -130) * 1e9, 46581, 145 + 466); + EXPECT_NEAR(get_mag_strength_tesla(-50, -125) * 1e9, 45263, 145 + 453); + EXPECT_NEAR(get_mag_strength_tesla(-50, -120) * 1e9, 43868, 145 + 439); + EXPECT_NEAR(get_mag_strength_tesla(-50, -115) * 1e9, 42390, 145 + 424); + EXPECT_NEAR(get_mag_strength_tesla(-50, -110) * 1e9, 40832, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(-50, -105) * 1e9, 39210, 145 + 392); + EXPECT_NEAR(get_mag_strength_tesla(-50, -100) * 1e9, 37547, 145 + 375); + EXPECT_NEAR(get_mag_strength_tesla(-50, -95) * 1e9, 35876, 145 + 359); + EXPECT_NEAR(get_mag_strength_tesla(-50, -90) * 1e9, 34237, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(-50, -85) * 1e9, 32675, 145 + 327); + EXPECT_NEAR(get_mag_strength_tesla(-50, -80) * 1e9, 31233, 145 + 312); + EXPECT_NEAR(get_mag_strength_tesla(-50, -75) * 1e9, 29950, 145 + 300); + EXPECT_NEAR(get_mag_strength_tesla(-50, -70) * 1e9, 28854, 145 + 289); + EXPECT_NEAR(get_mag_strength_tesla(-50, -65) * 1e9, 27960, 145 + 280); + EXPECT_NEAR(get_mag_strength_tesla(-50, -60) * 1e9, 27263, 145 + 273); + EXPECT_NEAR(get_mag_strength_tesla(-50, -55) * 1e9, 26744, 145 + 267); + EXPECT_NEAR(get_mag_strength_tesla(-50, -50) * 1e9, 26368, 145 + 264); + EXPECT_NEAR(get_mag_strength_tesla(-50, -45) * 1e9, 26095, 145 + 261); + EXPECT_NEAR(get_mag_strength_tesla(-50, -40) * 1e9, 25885, 145 + 259); + EXPECT_NEAR(get_mag_strength_tesla(-50, -35) * 1e9, 25704, 145 + 257); + EXPECT_NEAR(get_mag_strength_tesla(-50, -30) * 1e9, 25530, 145 + 255); + EXPECT_NEAR(get_mag_strength_tesla(-50, -25) * 1e9, 25353, 145 + 254); + EXPECT_NEAR(get_mag_strength_tesla(-50, -20) * 1e9, 25176, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-50, -15) * 1e9, 25017, 145 + 250); + EXPECT_NEAR(get_mag_strength_tesla(-50, -10) * 1e9, 24901, 145 + 249); + EXPECT_NEAR(get_mag_strength_tesla(-50, -5) * 1e9, 24866, 145 + 249); + EXPECT_NEAR(get_mag_strength_tesla(-50, 0) * 1e9, 24956, 145 + 250); + EXPECT_NEAR(get_mag_strength_tesla(-50, 5) * 1e9, 25221, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-50, 10) * 1e9, 25707, 145 + 257); + EXPECT_NEAR(get_mag_strength_tesla(-50, 15) * 1e9, 26455, 145 + 265); + EXPECT_NEAR(get_mag_strength_tesla(-50, 20) * 1e9, 27492, 145 + 275); + EXPECT_NEAR(get_mag_strength_tesla(-50, 25) * 1e9, 28827, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(-50, 30) * 1e9, 30453, 145 + 305); + EXPECT_NEAR(get_mag_strength_tesla(-50, 35) * 1e9, 32345, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(-50, 40) * 1e9, 34467, 145 + 345); + EXPECT_NEAR(get_mag_strength_tesla(-50, 45) * 1e9, 36775, 145 + 368); + EXPECT_NEAR(get_mag_strength_tesla(-50, 50) * 1e9, 39216, 145 + 392); + EXPECT_NEAR(get_mag_strength_tesla(-50, 55) * 1e9, 41742, 145 + 417); + EXPECT_NEAR(get_mag_strength_tesla(-50, 60) * 1e9, 44303, 145 + 443); + EXPECT_NEAR(get_mag_strength_tesla(-50, 65) * 1e9, 46856, 145 + 469); + EXPECT_NEAR(get_mag_strength_tesla(-50, 70) * 1e9, 49362, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(-50, 75) * 1e9, 51788, 145 + 518); + EXPECT_NEAR(get_mag_strength_tesla(-50, 80) * 1e9, 54102, 145 + 541); + EXPECT_NEAR(get_mag_strength_tesla(-50, 85) * 1e9, 56274, 145 + 563); + EXPECT_NEAR(get_mag_strength_tesla(-50, 90) * 1e9, 58275, 145 + 583); + EXPECT_NEAR(get_mag_strength_tesla(-50, 95) * 1e9, 60075, 145 + 601); + EXPECT_NEAR(get_mag_strength_tesla(-50, 100) * 1e9, 61649, 145 + 616); + EXPECT_NEAR(get_mag_strength_tesla(-50, 105) * 1e9, 62978, 145 + 630); + EXPECT_NEAR(get_mag_strength_tesla(-50, 110) * 1e9, 64047, 145 + 640); + EXPECT_NEAR(get_mag_strength_tesla(-50, 115) * 1e9, 64856, 145 + 649); + EXPECT_NEAR(get_mag_strength_tesla(-50, 120) * 1e9, 65408, 145 + 654); + EXPECT_NEAR(get_mag_strength_tesla(-50, 125) * 1e9, 65716, 145 + 657); + EXPECT_NEAR(get_mag_strength_tesla(-50, 130) * 1e9, 65796, 145 + 658); + EXPECT_NEAR(get_mag_strength_tesla(-50, 135) * 1e9, 65667, 145 + 657); + EXPECT_NEAR(get_mag_strength_tesla(-50, 140) * 1e9, 65350, 145 + 654); EXPECT_NEAR(get_mag_strength_tesla(-50, 145) * 1e9, 64864, 145 + 649); - EXPECT_NEAR(get_mag_strength_tesla(-50, 150) * 1e9, 64231, 145 + 642); - EXPECT_NEAR(get_mag_strength_tesla(-50, 155) * 1e9, 63468, 145 + 635); - EXPECT_NEAR(get_mag_strength_tesla(-50, 160) * 1e9, 62596, 145 + 626); - EXPECT_NEAR(get_mag_strength_tesla(-50, 165) * 1e9, 61633, 145 + 616); - EXPECT_NEAR(get_mag_strength_tesla(-50, 170) * 1e9, 60598, 145 + 606); - EXPECT_NEAR(get_mag_strength_tesla(-50, 175) * 1e9, 59508, 145 + 595); - EXPECT_NEAR(get_mag_strength_tesla(-50, 180) * 1e9, 58381, 145 + 584); - EXPECT_NEAR(get_mag_strength_tesla(-45, -180) * 1e9, 56229, 145 + 956); - EXPECT_NEAR(get_mag_strength_tesla(-45, -175) * 1e9, 55022, 145 + 935); - EXPECT_NEAR(get_mag_strength_tesla(-45, -170) * 1e9, 53807, 145 + 915); - EXPECT_NEAR(get_mag_strength_tesla(-45, -165) * 1e9, 52592, 145 + 894); - EXPECT_NEAR(get_mag_strength_tesla(-45, -160) * 1e9, 51384, 145 + 874); - EXPECT_NEAR(get_mag_strength_tesla(-45, -155) * 1e9, 50188, 145 + 853); - EXPECT_NEAR(get_mag_strength_tesla(-45, -150) * 1e9, 49004, 145 + 833); - EXPECT_NEAR(get_mag_strength_tesla(-45, -145) * 1e9, 47828, 145 + 813); - EXPECT_NEAR(get_mag_strength_tesla(-45, -140) * 1e9, 46650, 145 + 793); - EXPECT_NEAR(get_mag_strength_tesla(-45, -135) * 1e9, 45453, 145 + 773); - EXPECT_NEAR(get_mag_strength_tesla(-45, -130) * 1e9, 44217, 145 + 752); - EXPECT_NEAR(get_mag_strength_tesla(-45, -125) * 1e9, 42923, 145 + 730); - EXPECT_NEAR(get_mag_strength_tesla(-45, -120) * 1e9, 41554, 145 + 706); - EXPECT_NEAR(get_mag_strength_tesla(-45, -115) * 1e9, 40100, 145 + 682); - EXPECT_NEAR(get_mag_strength_tesla(-45, -110) * 1e9, 38562, 145 + 656); - EXPECT_NEAR(get_mag_strength_tesla(-45, -105) * 1e9, 36949, 145 + 628); - EXPECT_NEAR(get_mag_strength_tesla(-45, -100) * 1e9, 35284, 145 + 600); - EXPECT_NEAR(get_mag_strength_tesla(-45, -95) * 1e9, 33598, 145 + 571); - EXPECT_NEAR(get_mag_strength_tesla(-45, -90) * 1e9, 31937, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(-45, -85) * 1e9, 30351, 145 + 516); - EXPECT_NEAR(get_mag_strength_tesla(-45, -80) * 1e9, 28896, 145 + 491); - EXPECT_NEAR(get_mag_strength_tesla(-45, -75) * 1e9, 27622, 145 + 470); - EXPECT_NEAR(get_mag_strength_tesla(-45, -70) * 1e9, 26568, 145 + 452); - EXPECT_NEAR(get_mag_strength_tesla(-45, -65) * 1e9, 25754, 145 + 438); - EXPECT_NEAR(get_mag_strength_tesla(-45, -60) * 1e9, 25177, 145 + 428); - EXPECT_NEAR(get_mag_strength_tesla(-45, -55) * 1e9, 24809, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(-45, -50) * 1e9, 24603, 145 + 418); - EXPECT_NEAR(get_mag_strength_tesla(-45, -45) * 1e9, 24505, 145 + 417); - EXPECT_NEAR(get_mag_strength_tesla(-45, -40) * 1e9, 24462, 145 + 416); - EXPECT_NEAR(get_mag_strength_tesla(-45, -35) * 1e9, 24429, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(-45, -30) * 1e9, 24379, 145 + 414); - EXPECT_NEAR(get_mag_strength_tesla(-45, -25) * 1e9, 24298, 145 + 413); - EXPECT_NEAR(get_mag_strength_tesla(-45, -20) * 1e9, 24185, 145 + 411); - EXPECT_NEAR(get_mag_strength_tesla(-45, -15) * 1e9, 24053, 145 + 409); - EXPECT_NEAR(get_mag_strength_tesla(-45, -10) * 1e9, 23926, 145 + 407); - EXPECT_NEAR(get_mag_strength_tesla(-45, -5) * 1e9, 23840, 145 + 405); - EXPECT_NEAR(get_mag_strength_tesla(-45, 0) * 1e9, 23846, 145 + 405); - EXPECT_NEAR(get_mag_strength_tesla(-45, 5) * 1e9, 24003, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(-45, 10) * 1e9, 24375, 145 + 414); - EXPECT_NEAR(get_mag_strength_tesla(-45, 15) * 1e9, 25024, 145 + 425); - EXPECT_NEAR(get_mag_strength_tesla(-45, 20) * 1e9, 25994, 145 + 442); - EXPECT_NEAR(get_mag_strength_tesla(-45, 25) * 1e9, 27307, 145 + 464); - EXPECT_NEAR(get_mag_strength_tesla(-45, 30) * 1e9, 28961, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(-45, 35) * 1e9, 30928, 145 + 526); - EXPECT_NEAR(get_mag_strength_tesla(-45, 40) * 1e9, 33162, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(-45, 45) * 1e9, 35604, 145 + 605); - EXPECT_NEAR(get_mag_strength_tesla(-45, 50) * 1e9, 38189, 145 + 649); - EXPECT_NEAR(get_mag_strength_tesla(-45, 55) * 1e9, 40851, 145 + 694); - EXPECT_NEAR(get_mag_strength_tesla(-45, 60) * 1e9, 43529, 145 + 740); - EXPECT_NEAR(get_mag_strength_tesla(-45, 65) * 1e9, 46171, 145 + 785); - EXPECT_NEAR(get_mag_strength_tesla(-45, 70) * 1e9, 48733, 145 + 828); - EXPECT_NEAR(get_mag_strength_tesla(-45, 75) * 1e9, 51183, 145 + 870); - EXPECT_NEAR(get_mag_strength_tesla(-45, 80) * 1e9, 53492, 145 + 909); - EXPECT_NEAR(get_mag_strength_tesla(-45, 85) * 1e9, 55634, 145 + 946); - EXPECT_NEAR(get_mag_strength_tesla(-45, 90) * 1e9, 57582, 145 + 979); - EXPECT_NEAR(get_mag_strength_tesla(-45, 95) * 1e9, 59309, 145 + 1008); - EXPECT_NEAR(get_mag_strength_tesla(-45, 100) * 1e9, 60794, 145 + 1033); - EXPECT_NEAR(get_mag_strength_tesla(-45, 105) * 1e9, 62019, 145 + 1054); - EXPECT_NEAR(get_mag_strength_tesla(-45, 110) * 1e9, 62979, 145 + 1071); - EXPECT_NEAR(get_mag_strength_tesla(-45, 115) * 1e9, 63675, 145 + 1082); - EXPECT_NEAR(get_mag_strength_tesla(-45, 120) * 1e9, 64118, 145 + 1090); - EXPECT_NEAR(get_mag_strength_tesla(-45, 125) * 1e9, 64325, 145 + 1094); - EXPECT_NEAR(get_mag_strength_tesla(-45, 130) * 1e9, 64313, 145 + 1093); - EXPECT_NEAR(get_mag_strength_tesla(-45, 135) * 1e9, 64102, 145 + 1090); - EXPECT_NEAR(get_mag_strength_tesla(-45, 140) * 1e9, 63711, 145 + 1083); + EXPECT_NEAR(get_mag_strength_tesla(-50, 150) * 1e9, 64229, 145 + 642); + EXPECT_NEAR(get_mag_strength_tesla(-50, 155) * 1e9, 63464, 145 + 635); + EXPECT_NEAR(get_mag_strength_tesla(-50, 160) * 1e9, 62590, 145 + 626); + EXPECT_NEAR(get_mag_strength_tesla(-50, 165) * 1e9, 61624, 145 + 616); + EXPECT_NEAR(get_mag_strength_tesla(-50, 170) * 1e9, 60587, 145 + 606); + EXPECT_NEAR(get_mag_strength_tesla(-50, 175) * 1e9, 59496, 145 + 595); + EXPECT_NEAR(get_mag_strength_tesla(-50, 180) * 1e9, 58366, 145 + 584); + EXPECT_NEAR(get_mag_strength_tesla(-45, -180) * 1e9, 56216, 145 + 956); + EXPECT_NEAR(get_mag_strength_tesla(-45, -175) * 1e9, 55008, 145 + 935); + EXPECT_NEAR(get_mag_strength_tesla(-45, -170) * 1e9, 53791, 145 + 914); + EXPECT_NEAR(get_mag_strength_tesla(-45, -165) * 1e9, 52574, 145 + 894); + EXPECT_NEAR(get_mag_strength_tesla(-45, -160) * 1e9, 51364, 145 + 873); + EXPECT_NEAR(get_mag_strength_tesla(-45, -155) * 1e9, 50166, 145 + 853); + EXPECT_NEAR(get_mag_strength_tesla(-45, -150) * 1e9, 48980, 145 + 833); + EXPECT_NEAR(get_mag_strength_tesla(-45, -145) * 1e9, 47803, 145 + 813); + EXPECT_NEAR(get_mag_strength_tesla(-45, -140) * 1e9, 46624, 145 + 793); + EXPECT_NEAR(get_mag_strength_tesla(-45, -135) * 1e9, 45425, 145 + 772); + EXPECT_NEAR(get_mag_strength_tesla(-45, -130) * 1e9, 44189, 145 + 751); + EXPECT_NEAR(get_mag_strength_tesla(-45, -125) * 1e9, 42894, 145 + 729); + EXPECT_NEAR(get_mag_strength_tesla(-45, -120) * 1e9, 41524, 145 + 706); + EXPECT_NEAR(get_mag_strength_tesla(-45, -115) * 1e9, 40070, 145 + 681); + EXPECT_NEAR(get_mag_strength_tesla(-45, -110) * 1e9, 38532, 145 + 655); + EXPECT_NEAR(get_mag_strength_tesla(-45, -105) * 1e9, 36919, 145 + 628); + EXPECT_NEAR(get_mag_strength_tesla(-45, -100) * 1e9, 35253, 145 + 599); + EXPECT_NEAR(get_mag_strength_tesla(-45, -95) * 1e9, 33568, 145 + 571); + EXPECT_NEAR(get_mag_strength_tesla(-45, -90) * 1e9, 31908, 145 + 542); + EXPECT_NEAR(get_mag_strength_tesla(-45, -85) * 1e9, 30323, 145 + 515); + EXPECT_NEAR(get_mag_strength_tesla(-45, -80) * 1e9, 28870, 145 + 491); + EXPECT_NEAR(get_mag_strength_tesla(-45, -75) * 1e9, 27598, 145 + 469); + EXPECT_NEAR(get_mag_strength_tesla(-45, -70) * 1e9, 26546, 145 + 451); + EXPECT_NEAR(get_mag_strength_tesla(-45, -65) * 1e9, 25735, 145 + 437); + EXPECT_NEAR(get_mag_strength_tesla(-45, -60) * 1e9, 25160, 145 + 428); + EXPECT_NEAR(get_mag_strength_tesla(-45, -55) * 1e9, 24794, 145 + 421); + EXPECT_NEAR(get_mag_strength_tesla(-45, -50) * 1e9, 24590, 145 + 418); + EXPECT_NEAR(get_mag_strength_tesla(-45, -45) * 1e9, 24492, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(-45, -40) * 1e9, 24448, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(-45, -35) * 1e9, 24414, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(-45, -30) * 1e9, 24362, 145 + 414); + EXPECT_NEAR(get_mag_strength_tesla(-45, -25) * 1e9, 24278, 145 + 413); + EXPECT_NEAR(get_mag_strength_tesla(-45, -20) * 1e9, 24163, 145 + 411); + EXPECT_NEAR(get_mag_strength_tesla(-45, -15) * 1e9, 24029, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(-45, -10) * 1e9, 23900, 145 + 406); + EXPECT_NEAR(get_mag_strength_tesla(-45, -5) * 1e9, 23814, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(-45, 0) * 1e9, 23820, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(-45, 5) * 1e9, 23978, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(-45, 10) * 1e9, 24354, 145 + 414); + EXPECT_NEAR(get_mag_strength_tesla(-45, 15) * 1e9, 25008, 145 + 425); + EXPECT_NEAR(get_mag_strength_tesla(-45, 20) * 1e9, 25984, 145 + 442); + EXPECT_NEAR(get_mag_strength_tesla(-45, 25) * 1e9, 27304, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(-45, 30) * 1e9, 28965, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(-45, 35) * 1e9, 30939, 145 + 526); + EXPECT_NEAR(get_mag_strength_tesla(-45, 40) * 1e9, 33179, 145 + 564); + EXPECT_NEAR(get_mag_strength_tesla(-45, 45) * 1e9, 35626, 145 + 606); + EXPECT_NEAR(get_mag_strength_tesla(-45, 50) * 1e9, 38215, 145 + 650); + EXPECT_NEAR(get_mag_strength_tesla(-45, 55) * 1e9, 40879, 145 + 695); + EXPECT_NEAR(get_mag_strength_tesla(-45, 60) * 1e9, 43558, 145 + 740); + EXPECT_NEAR(get_mag_strength_tesla(-45, 65) * 1e9, 46199, 145 + 785); + EXPECT_NEAR(get_mag_strength_tesla(-45, 70) * 1e9, 48760, 145 + 829); + EXPECT_NEAR(get_mag_strength_tesla(-45, 75) * 1e9, 51209, 145 + 871); + EXPECT_NEAR(get_mag_strength_tesla(-45, 80) * 1e9, 53516, 145 + 910); + EXPECT_NEAR(get_mag_strength_tesla(-45, 85) * 1e9, 55655, 145 + 946); + EXPECT_NEAR(get_mag_strength_tesla(-45, 90) * 1e9, 57601, 145 + 979); + EXPECT_NEAR(get_mag_strength_tesla(-45, 95) * 1e9, 59327, 145 + 1009); + EXPECT_NEAR(get_mag_strength_tesla(-45, 100) * 1e9, 60810, 145 + 1034); + EXPECT_NEAR(get_mag_strength_tesla(-45, 105) * 1e9, 62034, 145 + 1055); + EXPECT_NEAR(get_mag_strength_tesla(-45, 110) * 1e9, 62992, 145 + 1071); + EXPECT_NEAR(get_mag_strength_tesla(-45, 115) * 1e9, 63686, 145 + 1083); + EXPECT_NEAR(get_mag_strength_tesla(-45, 120) * 1e9, 64127, 145 + 1090); + EXPECT_NEAR(get_mag_strength_tesla(-45, 125) * 1e9, 64332, 145 + 1094); + EXPECT_NEAR(get_mag_strength_tesla(-45, 130) * 1e9, 64319, 145 + 1093); + EXPECT_NEAR(get_mag_strength_tesla(-45, 135) * 1e9, 64106, 145 + 1090); + EXPECT_NEAR(get_mag_strength_tesla(-45, 140) * 1e9, 63714, 145 + 1083); EXPECT_NEAR(get_mag_strength_tesla(-45, 145) * 1e9, 63158, 145 + 1074); - EXPECT_NEAR(get_mag_strength_tesla(-45, 150) * 1e9, 62458, 145 + 1062); - EXPECT_NEAR(get_mag_strength_tesla(-45, 155) * 1e9, 61631, 145 + 1048); - EXPECT_NEAR(get_mag_strength_tesla(-45, 160) * 1e9, 60693, 145 + 1032); - EXPECT_NEAR(get_mag_strength_tesla(-45, 165) * 1e9, 59665, 145 + 1014); - EXPECT_NEAR(get_mag_strength_tesla(-45, 170) * 1e9, 58566, 145 + 996); - EXPECT_NEAR(get_mag_strength_tesla(-45, 175) * 1e9, 57415, 145 + 976); - EXPECT_NEAR(get_mag_strength_tesla(-45, 180) * 1e9, 56229, 145 + 956); - EXPECT_NEAR(get_mag_strength_tesla(-40, -180) * 1e9, 53891, 145 + 916); - EXPECT_NEAR(get_mag_strength_tesla(-40, -175) * 1e9, 52657, 145 + 895); - EXPECT_NEAR(get_mag_strength_tesla(-40, -170) * 1e9, 51417, 145 + 874); - EXPECT_NEAR(get_mag_strength_tesla(-40, -165) * 1e9, 50180, 145 + 853); - EXPECT_NEAR(get_mag_strength_tesla(-40, -160) * 1e9, 48951, 145 + 832); - EXPECT_NEAR(get_mag_strength_tesla(-40, -155) * 1e9, 47737, 145 + 812); - EXPECT_NEAR(get_mag_strength_tesla(-40, -150) * 1e9, 46540, 145 + 791); - EXPECT_NEAR(get_mag_strength_tesla(-40, -145) * 1e9, 45359, 145 + 771); - EXPECT_NEAR(get_mag_strength_tesla(-40, -140) * 1e9, 44187, 145 + 751); - EXPECT_NEAR(get_mag_strength_tesla(-40, -135) * 1e9, 43009, 145 + 731); - EXPECT_NEAR(get_mag_strength_tesla(-40, -130) * 1e9, 41807, 145 + 711); - EXPECT_NEAR(get_mag_strength_tesla(-40, -125) * 1e9, 40562, 145 + 690); - EXPECT_NEAR(get_mag_strength_tesla(-40, -120) * 1e9, 39255, 145 + 667); - EXPECT_NEAR(get_mag_strength_tesla(-40, -115) * 1e9, 37873, 145 + 644); - EXPECT_NEAR(get_mag_strength_tesla(-40, -110) * 1e9, 36411, 145 + 619); - EXPECT_NEAR(get_mag_strength_tesla(-40, -105) * 1e9, 34872, 145 + 593); - EXPECT_NEAR(get_mag_strength_tesla(-40, -100) * 1e9, 33271, 145 + 566); - EXPECT_NEAR(get_mag_strength_tesla(-40, -95) * 1e9, 31637, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(-40, -90) * 1e9, 30015, 145 + 510); - EXPECT_NEAR(get_mag_strength_tesla(-40, -85) * 1e9, 28461, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(-40, -80) * 1e9, 27040, 145 + 460); - EXPECT_NEAR(get_mag_strength_tesla(-40, -75) * 1e9, 25814, 145 + 439); - EXPECT_NEAR(get_mag_strength_tesla(-40, -70) * 1e9, 24834, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(-40, -65) * 1e9, 24126, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(-40, -60) * 1e9, 23686, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(-40, -55) * 1e9, 23477, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(-40, -50) * 1e9, 23442, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(-40, -45) * 1e9, 23514, 145 + 400); - EXPECT_NEAR(get_mag_strength_tesla(-40, -40) * 1e9, 23631, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(-40, -35) * 1e9, 23745, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(-40, -30) * 1e9, 23827, 145 + 405); - EXPECT_NEAR(get_mag_strength_tesla(-40, -25) * 1e9, 23864, 145 + 406); - EXPECT_NEAR(get_mag_strength_tesla(-40, -20) * 1e9, 23851, 145 + 405); - EXPECT_NEAR(get_mag_strength_tesla(-40, -15) * 1e9, 23794, 145 + 405); - EXPECT_NEAR(get_mag_strength_tesla(-40, -10) * 1e9, 23708, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(-40, -5) * 1e9, 23618, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(-40, 0) * 1e9, 23571, 145 + 401); - EXPECT_NEAR(get_mag_strength_tesla(-40, 5) * 1e9, 23630, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(-40, 10) * 1e9, 23874, 145 + 406); - EXPECT_NEAR(get_mag_strength_tesla(-40, 15) * 1e9, 24383, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(-40, 20) * 1e9, 25228, 145 + 429); - EXPECT_NEAR(get_mag_strength_tesla(-40, 25) * 1e9, 26449, 145 + 450); - EXPECT_NEAR(get_mag_strength_tesla(-40, 30) * 1e9, 28055, 145 + 477); - EXPECT_NEAR(get_mag_strength_tesla(-40, 35) * 1e9, 30022, 145 + 510); - EXPECT_NEAR(get_mag_strength_tesla(-40, 40) * 1e9, 32298, 145 + 549); - EXPECT_NEAR(get_mag_strength_tesla(-40, 45) * 1e9, 34811, 145 + 592); - EXPECT_NEAR(get_mag_strength_tesla(-40, 50) * 1e9, 37480, 145 + 637); - EXPECT_NEAR(get_mag_strength_tesla(-40, 55) * 1e9, 40222, 145 + 684); - EXPECT_NEAR(get_mag_strength_tesla(-40, 60) * 1e9, 42960, 145 + 730); - EXPECT_NEAR(get_mag_strength_tesla(-40, 65) * 1e9, 45631, 145 + 776); - EXPECT_NEAR(get_mag_strength_tesla(-40, 70) * 1e9, 48187, 145 + 819); - EXPECT_NEAR(get_mag_strength_tesla(-40, 75) * 1e9, 50596, 145 + 860); - EXPECT_NEAR(get_mag_strength_tesla(-40, 80) * 1e9, 52831, 145 + 898); - EXPECT_NEAR(get_mag_strength_tesla(-40, 85) * 1e9, 54870, 145 + 933); - EXPECT_NEAR(get_mag_strength_tesla(-40, 90) * 1e9, 56691, 145 + 964); - EXPECT_NEAR(get_mag_strength_tesla(-40, 95) * 1e9, 58272, 145 + 991); - EXPECT_NEAR(get_mag_strength_tesla(-40, 100) * 1e9, 59598, 145 + 1013); - EXPECT_NEAR(get_mag_strength_tesla(-40, 105) * 1e9, 60660, 145 + 1031); - EXPECT_NEAR(get_mag_strength_tesla(-40, 110) * 1e9, 61461, 145 + 1045); - EXPECT_NEAR(get_mag_strength_tesla(-40, 115) * 1e9, 62012, 145 + 1054); - EXPECT_NEAR(get_mag_strength_tesla(-40, 120) * 1e9, 62330, 145 + 1060); - EXPECT_NEAR(get_mag_strength_tesla(-40, 125) * 1e9, 62435, 145 + 1061); - EXPECT_NEAR(get_mag_strength_tesla(-40, 130) * 1e9, 62344, 145 + 1060); - EXPECT_NEAR(get_mag_strength_tesla(-40, 135) * 1e9, 62073, 145 + 1055); - EXPECT_NEAR(get_mag_strength_tesla(-40, 140) * 1e9, 61636, 145 + 1048); - EXPECT_NEAR(get_mag_strength_tesla(-40, 145) * 1e9, 61045, 145 + 1038); - EXPECT_NEAR(get_mag_strength_tesla(-40, 150) * 1e9, 60313, 145 + 1025); - EXPECT_NEAR(get_mag_strength_tesla(-40, 155) * 1e9, 59455, 145 + 1011); - EXPECT_NEAR(get_mag_strength_tesla(-40, 160) * 1e9, 58486, 145 + 994); - EXPECT_NEAR(get_mag_strength_tesla(-40, 165) * 1e9, 57425, 145 + 976); - EXPECT_NEAR(get_mag_strength_tesla(-40, 170) * 1e9, 56292, 145 + 957); - EXPECT_NEAR(get_mag_strength_tesla(-40, 175) * 1e9, 55108, 145 + 937); - EXPECT_NEAR(get_mag_strength_tesla(-40, 180) * 1e9, 53891, 145 + 916); - EXPECT_NEAR(get_mag_strength_tesla(-35, -180) * 1e9, 51395, 145 + 874); - EXPECT_NEAR(get_mag_strength_tesla(-35, -175) * 1e9, 50159, 145 + 853); - EXPECT_NEAR(get_mag_strength_tesla(-35, -170) * 1e9, 48920, 145 + 832); - EXPECT_NEAR(get_mag_strength_tesla(-35, -165) * 1e9, 47684, 145 + 811); - EXPECT_NEAR(get_mag_strength_tesla(-35, -160) * 1e9, 46457, 145 + 790); - EXPECT_NEAR(get_mag_strength_tesla(-35, -155) * 1e9, 45244, 145 + 769); - EXPECT_NEAR(get_mag_strength_tesla(-35, -150) * 1e9, 44050, 145 + 749); - EXPECT_NEAR(get_mag_strength_tesla(-35, -145) * 1e9, 42876, 145 + 729); - EXPECT_NEAR(get_mag_strength_tesla(-35, -140) * 1e9, 41719, 145 + 709); - EXPECT_NEAR(get_mag_strength_tesla(-35, -135) * 1e9, 40571, 145 + 690); - EXPECT_NEAR(get_mag_strength_tesla(-35, -130) * 1e9, 39417, 145 + 670); - EXPECT_NEAR(get_mag_strength_tesla(-35, -125) * 1e9, 38241, 145 + 650); - EXPECT_NEAR(get_mag_strength_tesla(-35, -120) * 1e9, 37025, 145 + 629); - EXPECT_NEAR(get_mag_strength_tesla(-35, -115) * 1e9, 35754, 145 + 608); - EXPECT_NEAR(get_mag_strength_tesla(-35, -110) * 1e9, 34415, 145 + 585); - EXPECT_NEAR(get_mag_strength_tesla(-35, -105) * 1e9, 33004, 145 + 561); - EXPECT_NEAR(get_mag_strength_tesla(-35, -100) * 1e9, 31525, 145 + 536); - EXPECT_NEAR(get_mag_strength_tesla(-35, -95) * 1e9, 30000, 145 + 510); - EXPECT_NEAR(get_mag_strength_tesla(-35, -90) * 1e9, 28473, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(-35, -85) * 1e9, 27001, 145 + 459); - EXPECT_NEAR(get_mag_strength_tesla(-35, -80) * 1e9, 25658, 145 + 436); - EXPECT_NEAR(get_mag_strength_tesla(-35, -75) * 1e9, 24516, 145 + 417); - EXPECT_NEAR(get_mag_strength_tesla(-35, -70) * 1e9, 23633, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(-35, -65) * 1e9, 23041, 145 + 392); - EXPECT_NEAR(get_mag_strength_tesla(-35, -60) * 1e9, 22734, 145 + 386); - EXPECT_NEAR(get_mag_strength_tesla(-35, -55) * 1e9, 22669, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(-35, -50) * 1e9, 22780, 145 + 387); - EXPECT_NEAR(get_mag_strength_tesla(-35, -45) * 1e9, 22992, 145 + 391); - EXPECT_NEAR(get_mag_strength_tesla(-35, -40) * 1e9, 23243, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(-35, -35) * 1e9, 23488, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(-35, -30) * 1e9, 23703, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(-35, -25) * 1e9, 23879, 145 + 406); - EXPECT_NEAR(get_mag_strength_tesla(-35, -20) * 1e9, 24009, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(-35, -15) * 1e9, 24089, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(-35, -10) * 1e9, 24115, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(-35, -5) * 1e9, 24097, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(-35, 0) * 1e9, 24065, 145 + 409); - EXPECT_NEAR(get_mag_strength_tesla(-35, 5) * 1e9, 24076, 145 + 409); - EXPECT_NEAR(get_mag_strength_tesla(-35, 10) * 1e9, 24213, 145 + 412); - EXPECT_NEAR(get_mag_strength_tesla(-35, 15) * 1e9, 24572, 145 + 418); - EXPECT_NEAR(get_mag_strength_tesla(-35, 20) * 1e9, 25246, 145 + 429); - EXPECT_NEAR(get_mag_strength_tesla(-35, 25) * 1e9, 26301, 145 + 447); - EXPECT_NEAR(get_mag_strength_tesla(-35, 30) * 1e9, 27767, 145 + 472); - EXPECT_NEAR(get_mag_strength_tesla(-35, 35) * 1e9, 29634, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(-35, 40) * 1e9, 31853, 145 + 541); - EXPECT_NEAR(get_mag_strength_tesla(-35, 45) * 1e9, 34345, 145 + 584); - EXPECT_NEAR(get_mag_strength_tesla(-35, 50) * 1e9, 37016, 145 + 629); - EXPECT_NEAR(get_mag_strength_tesla(-35, 55) * 1e9, 39765, 145 + 676); - EXPECT_NEAR(get_mag_strength_tesla(-35, 60) * 1e9, 42499, 145 + 722); - EXPECT_NEAR(get_mag_strength_tesla(-35, 65) * 1e9, 45143, 145 + 767); - EXPECT_NEAR(get_mag_strength_tesla(-35, 70) * 1e9, 47642, 145 + 810); - EXPECT_NEAR(get_mag_strength_tesla(-35, 75) * 1e9, 49959, 145 + 849); - EXPECT_NEAR(get_mag_strength_tesla(-35, 80) * 1e9, 52070, 145 + 885); - EXPECT_NEAR(get_mag_strength_tesla(-35, 85) * 1e9, 53955, 145 + 917); - EXPECT_NEAR(get_mag_strength_tesla(-35, 90) * 1e9, 55595, 145 + 945); - EXPECT_NEAR(get_mag_strength_tesla(-35, 95) * 1e9, 56975, 145 + 969); - EXPECT_NEAR(get_mag_strength_tesla(-35, 100) * 1e9, 58088, 145 + 987); - EXPECT_NEAR(get_mag_strength_tesla(-35, 105) * 1e9, 58937, 145 + 1002); - EXPECT_NEAR(get_mag_strength_tesla(-35, 110) * 1e9, 59541, 145 + 1012); - EXPECT_NEAR(get_mag_strength_tesla(-35, 115) * 1e9, 59924, 145 + 1019); - EXPECT_NEAR(get_mag_strength_tesla(-35, 120) * 1e9, 60110, 145 + 1022); - EXPECT_NEAR(get_mag_strength_tesla(-35, 125) * 1e9, 60120, 145 + 1022); - EXPECT_NEAR(get_mag_strength_tesla(-35, 130) * 1e9, 59966, 145 + 1019); - EXPECT_NEAR(get_mag_strength_tesla(-35, 135) * 1e9, 59656, 145 + 1014); - EXPECT_NEAR(get_mag_strength_tesla(-35, 140) * 1e9, 59195, 145 + 1006); - EXPECT_NEAR(get_mag_strength_tesla(-35, 145) * 1e9, 58591, 145 + 996); - EXPECT_NEAR(get_mag_strength_tesla(-35, 150) * 1e9, 57852, 145 + 983); - EXPECT_NEAR(get_mag_strength_tesla(-35, 155) * 1e9, 56990, 145 + 969); - EXPECT_NEAR(get_mag_strength_tesla(-35, 160) * 1e9, 56016, 145 + 952); - EXPECT_NEAR(get_mag_strength_tesla(-35, 165) * 1e9, 54949, 145 + 934); - EXPECT_NEAR(get_mag_strength_tesla(-35, 170) * 1e9, 53808, 145 + 915); - EXPECT_NEAR(get_mag_strength_tesla(-35, 175) * 1e9, 52617, 145 + 894); - EXPECT_NEAR(get_mag_strength_tesla(-35, 180) * 1e9, 51395, 145 + 874); - EXPECT_NEAR(get_mag_strength_tesla(-30, -180) * 1e9, 48756, 145 + 488); - EXPECT_NEAR(get_mag_strength_tesla(-30, -175) * 1e9, 47544, 145 + 475); - EXPECT_NEAR(get_mag_strength_tesla(-30, -170) * 1e9, 46333, 145 + 463); - EXPECT_NEAR(get_mag_strength_tesla(-30, -165) * 1e9, 45126, 145 + 451); - EXPECT_NEAR(get_mag_strength_tesla(-30, -160) * 1e9, 43927, 145 + 439); - EXPECT_NEAR(get_mag_strength_tesla(-30, -155) * 1e9, 42740, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(-30, -150) * 1e9, 41570, 145 + 416); - EXPECT_NEAR(get_mag_strength_tesla(-30, -145) * 1e9, 40422, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(-30, -140) * 1e9, 39299, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(-30, -135) * 1e9, 38196, 145 + 382); - EXPECT_NEAR(get_mag_strength_tesla(-30, -130) * 1e9, 37106, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(-30, -125) * 1e9, 36016, 145 + 360); - EXPECT_NEAR(get_mag_strength_tesla(-30, -120) * 1e9, 34912, 145 + 349); - EXPECT_NEAR(get_mag_strength_tesla(-30, -115) * 1e9, 33779, 145 + 338); - EXPECT_NEAR(get_mag_strength_tesla(-30, -110) * 1e9, 32597, 145 + 326); - EXPECT_NEAR(get_mag_strength_tesla(-30, -105) * 1e9, 31351, 145 + 314); - EXPECT_NEAR(get_mag_strength_tesla(-30, -100) * 1e9, 30036, 145 + 300); - EXPECT_NEAR(get_mag_strength_tesla(-30, -95) * 1e9, 28666, 145 + 287); - EXPECT_NEAR(get_mag_strength_tesla(-30, -90) * 1e9, 27279, 145 + 273); - EXPECT_NEAR(get_mag_strength_tesla(-30, -85) * 1e9, 25935, 145 + 259); - EXPECT_NEAR(get_mag_strength_tesla(-30, -80) * 1e9, 24708, 145 + 247); - EXPECT_NEAR(get_mag_strength_tesla(-30, -75) * 1e9, 23678, 145 + 237); - EXPECT_NEAR(get_mag_strength_tesla(-30, -70) * 1e9, 22907, 145 + 229); - EXPECT_NEAR(get_mag_strength_tesla(-30, -65) * 1e9, 22429, 145 + 224); - EXPECT_NEAR(get_mag_strength_tesla(-30, -60) * 1e9, 22237, 145 + 222); - EXPECT_NEAR(get_mag_strength_tesla(-30, -55) * 1e9, 22285, 145 + 223); - EXPECT_NEAR(get_mag_strength_tesla(-30, -50) * 1e9, 22503, 145 + 225); - EXPECT_NEAR(get_mag_strength_tesla(-30, -45) * 1e9, 22819, 145 + 228); - EXPECT_NEAR(get_mag_strength_tesla(-30, -40) * 1e9, 23172, 145 + 232); - EXPECT_NEAR(get_mag_strength_tesla(-30, -35) * 1e9, 23528, 145 + 235); - EXPECT_NEAR(get_mag_strength_tesla(-30, -30) * 1e9, 23872, 145 + 239); - EXPECT_NEAR(get_mag_strength_tesla(-30, -25) * 1e9, 24202, 145 + 242); - EXPECT_NEAR(get_mag_strength_tesla(-30, -20) * 1e9, 24508, 145 + 245); - EXPECT_NEAR(get_mag_strength_tesla(-30, -15) * 1e9, 24776, 145 + 248); - EXPECT_NEAR(get_mag_strength_tesla(-30, -10) * 1e9, 24980, 145 + 250); - EXPECT_NEAR(get_mag_strength_tesla(-30, -5) * 1e9, 25108, 145 + 251); - EXPECT_NEAR(get_mag_strength_tesla(-30, 0) * 1e9, 25167, 145 + 252); - EXPECT_NEAR(get_mag_strength_tesla(-30, 5) * 1e9, 25198, 145 + 252); - EXPECT_NEAR(get_mag_strength_tesla(-30, 10) * 1e9, 25280, 145 + 253); - EXPECT_NEAR(get_mag_strength_tesla(-30, 15) * 1e9, 25510, 145 + 255); - EXPECT_NEAR(get_mag_strength_tesla(-30, 20) * 1e9, 25997, 145 + 260); - EXPECT_NEAR(get_mag_strength_tesla(-30, 25) * 1e9, 26831, 145 + 268); - EXPECT_NEAR(get_mag_strength_tesla(-30, 30) * 1e9, 28071, 145 + 281); - EXPECT_NEAR(get_mag_strength_tesla(-30, 35) * 1e9, 29731, 145 + 297); - EXPECT_NEAR(get_mag_strength_tesla(-30, 40) * 1e9, 31780, 145 + 318); - EXPECT_NEAR(get_mag_strength_tesla(-30, 45) * 1e9, 34142, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(-30, 50) * 1e9, 36716, 145 + 367); - EXPECT_NEAR(get_mag_strength_tesla(-30, 55) * 1e9, 39386, 145 + 394); - EXPECT_NEAR(get_mag_strength_tesla(-30, 60) * 1e9, 42045, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(-30, 65) * 1e9, 44603, 145 + 446); - EXPECT_NEAR(get_mag_strength_tesla(-30, 70) * 1e9, 46997, 145 + 470); - EXPECT_NEAR(get_mag_strength_tesla(-30, 75) * 1e9, 49186, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(-30, 80) * 1e9, 51141, 145 + 511); - EXPECT_NEAR(get_mag_strength_tesla(-30, 85) * 1e9, 52842, 145 + 528); - EXPECT_NEAR(get_mag_strength_tesla(-30, 90) * 1e9, 54270, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(-30, 95) * 1e9, 55414, 145 + 554); - EXPECT_NEAR(get_mag_strength_tesla(-30, 100) * 1e9, 56277, 145 + 563); - EXPECT_NEAR(get_mag_strength_tesla(-30, 105) * 1e9, 56882, 145 + 569); - EXPECT_NEAR(get_mag_strength_tesla(-30, 110) * 1e9, 57266, 145 + 573); - EXPECT_NEAR(get_mag_strength_tesla(-30, 115) * 1e9, 57469, 145 + 575); - EXPECT_NEAR(get_mag_strength_tesla(-30, 120) * 1e9, 57524, 145 + 575); - EXPECT_NEAR(get_mag_strength_tesla(-30, 125) * 1e9, 57449, 145 + 574); - EXPECT_NEAR(get_mag_strength_tesla(-30, 130) * 1e9, 57246, 145 + 572); - EXPECT_NEAR(get_mag_strength_tesla(-30, 135) * 1e9, 56913, 145 + 569); - EXPECT_NEAR(get_mag_strength_tesla(-30, 140) * 1e9, 56445, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(-30, 145) * 1e9, 55843, 145 + 558); - EXPECT_NEAR(get_mag_strength_tesla(-30, 150) * 1e9, 55113, 145 + 551); - EXPECT_NEAR(get_mag_strength_tesla(-30, 155) * 1e9, 54264, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(-30, 160) * 1e9, 53306, 145 + 533); - EXPECT_NEAR(get_mag_strength_tesla(-30, 165) * 1e9, 52256, 145 + 523); - EXPECT_NEAR(get_mag_strength_tesla(-30, 170) * 1e9, 51132, 145 + 511); - EXPECT_NEAR(get_mag_strength_tesla(-30, 175) * 1e9, 49958, 145 + 500); - EXPECT_NEAR(get_mag_strength_tesla(-30, 180) * 1e9, 48756, 145 + 488); - EXPECT_NEAR(get_mag_strength_tesla(-25, -180) * 1e9, 46003, 145 + 460); - EXPECT_NEAR(get_mag_strength_tesla(-25, -175) * 1e9, 44843, 145 + 448); - EXPECT_NEAR(get_mag_strength_tesla(-25, -170) * 1e9, 43688, 145 + 437); - EXPECT_NEAR(get_mag_strength_tesla(-25, -165) * 1e9, 42540, 145 + 425); - EXPECT_NEAR(get_mag_strength_tesla(-25, -160) * 1e9, 41400, 145 + 414); - EXPECT_NEAR(get_mag_strength_tesla(-25, -155) * 1e9, 40270, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(-25, -150) * 1e9, 39156, 145 + 392); - EXPECT_NEAR(get_mag_strength_tesla(-25, -145) * 1e9, 38065, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(-25, -140) * 1e9, 37002, 145 + 370); - EXPECT_NEAR(get_mag_strength_tesla(-25, -135) * 1e9, 35968, 145 + 360); - EXPECT_NEAR(get_mag_strength_tesla(-25, -130) * 1e9, 34961, 145 + 350); - EXPECT_NEAR(get_mag_strength_tesla(-25, -125) * 1e9, 33976, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(-25, -120) * 1e9, 33002, 145 + 330); - EXPECT_NEAR(get_mag_strength_tesla(-25, -115) * 1e9, 32022, 145 + 320); - EXPECT_NEAR(get_mag_strength_tesla(-25, -110) * 1e9, 31015, 145 + 310); - EXPECT_NEAR(get_mag_strength_tesla(-25, -105) * 1e9, 29956, 145 + 300); - EXPECT_NEAR(get_mag_strength_tesla(-25, -100) * 1e9, 28831, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(-25, -95) * 1e9, 27647, 145 + 276); - EXPECT_NEAR(get_mag_strength_tesla(-25, -90) * 1e9, 26436, 145 + 264); - EXPECT_NEAR(get_mag_strength_tesla(-25, -85) * 1e9, 25254, 145 + 253); - EXPECT_NEAR(get_mag_strength_tesla(-25, -80) * 1e9, 24176, 145 + 242); - EXPECT_NEAR(get_mag_strength_tesla(-25, -75) * 1e9, 23277, 145 + 233); - EXPECT_NEAR(get_mag_strength_tesla(-25, -70) * 1e9, 22621, 145 + 226); - EXPECT_NEAR(get_mag_strength_tesla(-25, -65) * 1e9, 22242, 145 + 222); - EXPECT_NEAR(get_mag_strength_tesla(-25, -60) * 1e9, 22133, 145 + 221); - EXPECT_NEAR(get_mag_strength_tesla(-25, -55) * 1e9, 22255, 145 + 223); - EXPECT_NEAR(get_mag_strength_tesla(-25, -50) * 1e9, 22541, 145 + 225); - EXPECT_NEAR(get_mag_strength_tesla(-25, -45) * 1e9, 22924, 145 + 229); - EXPECT_NEAR(get_mag_strength_tesla(-25, -40) * 1e9, 23354, 145 + 234); - EXPECT_NEAR(get_mag_strength_tesla(-25, -35) * 1e9, 23805, 145 + 238); - EXPECT_NEAR(get_mag_strength_tesla(-25, -30) * 1e9, 24272, 145 + 243); - EXPECT_NEAR(get_mag_strength_tesla(-25, -25) * 1e9, 24757, 145 + 248); - EXPECT_NEAR(get_mag_strength_tesla(-25, -20) * 1e9, 25249, 145 + 252); - EXPECT_NEAR(get_mag_strength_tesla(-25, -15) * 1e9, 25722, 145 + 257); - EXPECT_NEAR(get_mag_strength_tesla(-25, -10) * 1e9, 26133, 145 + 261); - EXPECT_NEAR(get_mag_strength_tesla(-25, -5) * 1e9, 26446, 145 + 264); - EXPECT_NEAR(get_mag_strength_tesla(-25, 0) * 1e9, 26647, 145 + 266); - EXPECT_NEAR(get_mag_strength_tesla(-25, 5) * 1e9, 26756, 145 + 268); - EXPECT_NEAR(get_mag_strength_tesla(-25, 10) * 1e9, 26835, 145 + 268); - EXPECT_NEAR(get_mag_strength_tesla(-25, 15) * 1e9, 26977, 145 + 270); - EXPECT_NEAR(get_mag_strength_tesla(-25, 20) * 1e9, 27290, 145 + 273); - EXPECT_NEAR(get_mag_strength_tesla(-25, 25) * 1e9, 27881, 145 + 279); - EXPECT_NEAR(get_mag_strength_tesla(-25, 30) * 1e9, 28837, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(-25, 35) * 1e9, 30207, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(-25, 40) * 1e9, 31984, 145 + 320); - EXPECT_NEAR(get_mag_strength_tesla(-25, 45) * 1e9, 34111, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(-25, 50) * 1e9, 36486, 145 + 365); - EXPECT_NEAR(get_mag_strength_tesla(-25, 55) * 1e9, 38986, 145 + 390); - EXPECT_NEAR(get_mag_strength_tesla(-25, 60) * 1e9, 41492, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(-25, 65) * 1e9, 43903, 145 + 439); - EXPECT_NEAR(get_mag_strength_tesla(-25, 70) * 1e9, 46147, 145 + 461); - EXPECT_NEAR(get_mag_strength_tesla(-25, 75) * 1e9, 48178, 145 + 482); - EXPECT_NEAR(get_mag_strength_tesla(-25, 80) * 1e9, 49960, 145 + 500); - EXPECT_NEAR(get_mag_strength_tesla(-25, 85) * 1e9, 51465, 145 + 515); - EXPECT_NEAR(get_mag_strength_tesla(-25, 90) * 1e9, 52671, 145 + 527); - EXPECT_NEAR(get_mag_strength_tesla(-25, 95) * 1e9, 53568, 145 + 536); - EXPECT_NEAR(get_mag_strength_tesla(-25, 100) * 1e9, 54171, 145 + 542); - EXPECT_NEAR(get_mag_strength_tesla(-25, 105) * 1e9, 54522, 145 + 545); - EXPECT_NEAR(get_mag_strength_tesla(-25, 110) * 1e9, 54681, 145 + 547); - EXPECT_NEAR(get_mag_strength_tesla(-25, 115) * 1e9, 54707, 145 + 547); - EXPECT_NEAR(get_mag_strength_tesla(-25, 120) * 1e9, 54640, 145 + 546); - EXPECT_NEAR(get_mag_strength_tesla(-25, 125) * 1e9, 54492, 145 + 545); - EXPECT_NEAR(get_mag_strength_tesla(-25, 130) * 1e9, 54255, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(-25, 135) * 1e9, 53910, 145 + 539); - EXPECT_NEAR(get_mag_strength_tesla(-25, 140) * 1e9, 53442, 145 + 534); - EXPECT_NEAR(get_mag_strength_tesla(-25, 145) * 1e9, 52848, 145 + 528); - EXPECT_NEAR(get_mag_strength_tesla(-25, 150) * 1e9, 52135, 145 + 521); - EXPECT_NEAR(get_mag_strength_tesla(-25, 155) * 1e9, 51310, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(-25, 160) * 1e9, 50386, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(-25, 165) * 1e9, 49373, 145 + 494); - EXPECT_NEAR(get_mag_strength_tesla(-25, 170) * 1e9, 48289, 145 + 483); - EXPECT_NEAR(get_mag_strength_tesla(-25, 175) * 1e9, 47158, 145 + 472); - EXPECT_NEAR(get_mag_strength_tesla(-25, 180) * 1e9, 46003, 145 + 460); - EXPECT_NEAR(get_mag_strength_tesla(-20, -180) * 1e9, 43196, 145 + 432); - EXPECT_NEAR(get_mag_strength_tesla(-20, -175) * 1e9, 42117, 145 + 421); - EXPECT_NEAR(get_mag_strength_tesla(-20, -170) * 1e9, 41050, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(-20, -165) * 1e9, 39994, 145 + 400); - EXPECT_NEAR(get_mag_strength_tesla(-20, -160) * 1e9, 38947, 145 + 389); - EXPECT_NEAR(get_mag_strength_tesla(-20, -155) * 1e9, 37911, 145 + 379); - EXPECT_NEAR(get_mag_strength_tesla(-20, -150) * 1e9, 36890, 145 + 369); - EXPECT_NEAR(get_mag_strength_tesla(-20, -145) * 1e9, 35892, 145 + 359); - EXPECT_NEAR(get_mag_strength_tesla(-20, -140) * 1e9, 34924, 145 + 349); - EXPECT_NEAR(get_mag_strength_tesla(-20, -135) * 1e9, 33992, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(-20, -130) * 1e9, 33096, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(-20, -125) * 1e9, 32237, 145 + 322); - EXPECT_NEAR(get_mag_strength_tesla(-20, -120) * 1e9, 31407, 145 + 314); - EXPECT_NEAR(get_mag_strength_tesla(-20, -115) * 1e9, 30591, 145 + 306); - EXPECT_NEAR(get_mag_strength_tesla(-20, -110) * 1e9, 29765, 145 + 298); - EXPECT_NEAR(get_mag_strength_tesla(-20, -105) * 1e9, 28901, 145 + 289); - EXPECT_NEAR(get_mag_strength_tesla(-20, -100) * 1e9, 27980, 145 + 280); - EXPECT_NEAR(get_mag_strength_tesla(-20, -95) * 1e9, 27000, 145 + 270); - EXPECT_NEAR(get_mag_strength_tesla(-20, -90) * 1e9, 25988, 145 + 260); - EXPECT_NEAR(get_mag_strength_tesla(-20, -85) * 1e9, 24993, 145 + 250); - EXPECT_NEAR(get_mag_strength_tesla(-20, -80) * 1e9, 24080, 145 + 241); - EXPECT_NEAR(get_mag_strength_tesla(-20, -75) * 1e9, 23319, 145 + 233); - EXPECT_NEAR(get_mag_strength_tesla(-20, -70) * 1e9, 22766, 145 + 228); - EXPECT_NEAR(get_mag_strength_tesla(-20, -65) * 1e9, 22457, 145 + 225); - EXPECT_NEAR(get_mag_strength_tesla(-20, -60) * 1e9, 22392, 145 + 224); - EXPECT_NEAR(get_mag_strength_tesla(-20, -55) * 1e9, 22542, 145 + 225); - EXPECT_NEAR(get_mag_strength_tesla(-20, -50) * 1e9, 22856, 145 + 229); - EXPECT_NEAR(get_mag_strength_tesla(-20, -45) * 1e9, 23277, 145 + 233); - EXPECT_NEAR(get_mag_strength_tesla(-20, -40) * 1e9, 23763, 145 + 238); - EXPECT_NEAR(get_mag_strength_tesla(-20, -35) * 1e9, 24295, 145 + 243); - EXPECT_NEAR(get_mag_strength_tesla(-20, -30) * 1e9, 24870, 145 + 249); - EXPECT_NEAR(get_mag_strength_tesla(-20, -25) * 1e9, 25491, 145 + 255); - EXPECT_NEAR(get_mag_strength_tesla(-20, -20) * 1e9, 26144, 145 + 261); - EXPECT_NEAR(get_mag_strength_tesla(-20, -15) * 1e9, 26796, 145 + 268); - EXPECT_NEAR(get_mag_strength_tesla(-20, -10) * 1e9, 27393, 145 + 274); - EXPECT_NEAR(get_mag_strength_tesla(-20, -5) * 1e9, 27882, 145 + 279); - EXPECT_NEAR(get_mag_strength_tesla(-20, 0) * 1e9, 28231, 145 + 282); - EXPECT_NEAR(get_mag_strength_tesla(-20, 5) * 1e9, 28442, 145 + 284); - EXPECT_NEAR(get_mag_strength_tesla(-20, 10) * 1e9, 28557, 145 + 286); - EXPECT_NEAR(get_mag_strength_tesla(-20, 15) * 1e9, 28651, 145 + 287); - EXPECT_NEAR(get_mag_strength_tesla(-20, 20) * 1e9, 28824, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(-20, 25) * 1e9, 29189, 145 + 292); - EXPECT_NEAR(get_mag_strength_tesla(-20, 30) * 1e9, 29852, 145 + 299); - EXPECT_NEAR(get_mag_strength_tesla(-20, 35) * 1e9, 30892, 145 + 309); - EXPECT_NEAR(get_mag_strength_tesla(-20, 40) * 1e9, 32337, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(-20, 45) * 1e9, 34151, 145 + 342); - EXPECT_NEAR(get_mag_strength_tesla(-20, 50) * 1e9, 36243, 145 + 362); - EXPECT_NEAR(get_mag_strength_tesla(-20, 55) * 1e9, 38491, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(-20, 60) * 1e9, 40770, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(-20, 65) * 1e9, 42974, 145 + 430); - EXPECT_NEAR(get_mag_strength_tesla(-20, 70) * 1e9, 45026, 145 + 450); - EXPECT_NEAR(get_mag_strength_tesla(-20, 75) * 1e9, 46871, 145 + 469); - EXPECT_NEAR(get_mag_strength_tesla(-20, 80) * 1e9, 48468, 145 + 485); - EXPECT_NEAR(get_mag_strength_tesla(-20, 85) * 1e9, 49779, 145 + 498); - EXPECT_NEAR(get_mag_strength_tesla(-20, 90) * 1e9, 50772, 145 + 508); - EXPECT_NEAR(get_mag_strength_tesla(-20, 95) * 1e9, 51436, 145 + 514); - EXPECT_NEAR(get_mag_strength_tesla(-20, 100) * 1e9, 51796, 145 + 518); - EXPECT_NEAR(get_mag_strength_tesla(-20, 105) * 1e9, 51911, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(-20, 110) * 1e9, 51864, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(-20, 115) * 1e9, 51730, 145 + 517); - EXPECT_NEAR(get_mag_strength_tesla(-20, 120) * 1e9, 51558, 145 + 516); - EXPECT_NEAR(get_mag_strength_tesla(-20, 125) * 1e9, 51352, 145 + 514); - EXPECT_NEAR(get_mag_strength_tesla(-20, 130) * 1e9, 51088, 145 + 511); - EXPECT_NEAR(get_mag_strength_tesla(-20, 135) * 1e9, 50735, 145 + 507); - EXPECT_NEAR(get_mag_strength_tesla(-20, 140) * 1e9, 50269, 145 + 503); - EXPECT_NEAR(get_mag_strength_tesla(-20, 145) * 1e9, 49684, 145 + 497); - EXPECT_NEAR(get_mag_strength_tesla(-20, 150) * 1e9, 48989, 145 + 490); - EXPECT_NEAR(get_mag_strength_tesla(-20, 155) * 1e9, 48197, 145 + 482); - EXPECT_NEAR(get_mag_strength_tesla(-20, 160) * 1e9, 47316, 145 + 473); - EXPECT_NEAR(get_mag_strength_tesla(-20, 165) * 1e9, 46358, 145 + 464); - EXPECT_NEAR(get_mag_strength_tesla(-20, 170) * 1e9, 45338, 145 + 453); - EXPECT_NEAR(get_mag_strength_tesla(-20, 175) * 1e9, 44275, 145 + 443); - EXPECT_NEAR(get_mag_strength_tesla(-20, 180) * 1e9, 43196, 145 + 432); - EXPECT_NEAR(get_mag_strength_tesla(-15, -180) * 1e9, 40441, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(-15, -175) * 1e9, 39475, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(-15, -170) * 1e9, 38527, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(-15, -165) * 1e9, 37595, 145 + 376); - EXPECT_NEAR(get_mag_strength_tesla(-15, -160) * 1e9, 36675, 145 + 367); - EXPECT_NEAR(get_mag_strength_tesla(-15, -155) * 1e9, 35769, 145 + 358); - EXPECT_NEAR(get_mag_strength_tesla(-15, -150) * 1e9, 34880, 145 + 349); - EXPECT_NEAR(get_mag_strength_tesla(-15, -145) * 1e9, 34015, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(-15, -140) * 1e9, 33183, 145 + 332); - EXPECT_NEAR(get_mag_strength_tesla(-15, -135) * 1e9, 32388, 145 + 324); - EXPECT_NEAR(get_mag_strength_tesla(-15, -130) * 1e9, 31635, 145 + 316); - EXPECT_NEAR(get_mag_strength_tesla(-15, -125) * 1e9, 30924, 145 + 309); - EXPECT_NEAR(get_mag_strength_tesla(-15, -120) * 1e9, 30253, 145 + 303); - EXPECT_NEAR(get_mag_strength_tesla(-15, -115) * 1e9, 29607, 145 + 296); - EXPECT_NEAR(get_mag_strength_tesla(-15, -110) * 1e9, 28964, 145 + 290); - EXPECT_NEAR(get_mag_strength_tesla(-15, -105) * 1e9, 28295, 145 + 283); - EXPECT_NEAR(get_mag_strength_tesla(-15, -100) * 1e9, 27580, 145 + 276); - EXPECT_NEAR(get_mag_strength_tesla(-15, -95) * 1e9, 26812, 145 + 268); - EXPECT_NEAR(get_mag_strength_tesla(-15, -90) * 1e9, 26009, 145 + 260); - EXPECT_NEAR(get_mag_strength_tesla(-15, -85) * 1e9, 25208, 145 + 252); - EXPECT_NEAR(get_mag_strength_tesla(-15, -80) * 1e9, 24461, 145 + 245); - EXPECT_NEAR(get_mag_strength_tesla(-15, -75) * 1e9, 23824, 145 + 238); - EXPECT_NEAR(get_mag_strength_tesla(-15, -70) * 1e9, 23349, 145 + 233); - EXPECT_NEAR(get_mag_strength_tesla(-15, -65) * 1e9, 23070, 145 + 231); - EXPECT_NEAR(get_mag_strength_tesla(-15, -60) * 1e9, 23000, 145 + 230); - EXPECT_NEAR(get_mag_strength_tesla(-15, -55) * 1e9, 23130, 145 + 231); + EXPECT_NEAR(get_mag_strength_tesla(-45, 150) * 1e9, 62457, 145 + 1062); + EXPECT_NEAR(get_mag_strength_tesla(-45, 155) * 1e9, 61628, 145 + 1048); + EXPECT_NEAR(get_mag_strength_tesla(-45, 160) * 1e9, 60688, 145 + 1032); + EXPECT_NEAR(get_mag_strength_tesla(-45, 165) * 1e9, 59658, 145 + 1014); + EXPECT_NEAR(get_mag_strength_tesla(-45, 170) * 1e9, 58557, 145 + 995); + EXPECT_NEAR(get_mag_strength_tesla(-45, 175) * 1e9, 57404, 145 + 976); + EXPECT_NEAR(get_mag_strength_tesla(-45, 180) * 1e9, 56216, 145 + 956); + EXPECT_NEAR(get_mag_strength_tesla(-40, -180) * 1e9, 53880, 145 + 916); + EXPECT_NEAR(get_mag_strength_tesla(-40, -175) * 1e9, 52645, 145 + 895); + EXPECT_NEAR(get_mag_strength_tesla(-40, -170) * 1e9, 51403, 145 + 874); + EXPECT_NEAR(get_mag_strength_tesla(-40, -165) * 1e9, 50164, 145 + 853); + EXPECT_NEAR(get_mag_strength_tesla(-40, -160) * 1e9, 48933, 145 + 832); + EXPECT_NEAR(get_mag_strength_tesla(-40, -155) * 1e9, 47717, 145 + 811); + EXPECT_NEAR(get_mag_strength_tesla(-40, -150) * 1e9, 46519, 145 + 791); + EXPECT_NEAR(get_mag_strength_tesla(-40, -145) * 1e9, 45336, 145 + 771); + EXPECT_NEAR(get_mag_strength_tesla(-40, -140) * 1e9, 44163, 145 + 751); + EXPECT_NEAR(get_mag_strength_tesla(-40, -135) * 1e9, 42984, 145 + 731); + EXPECT_NEAR(get_mag_strength_tesla(-40, -130) * 1e9, 41781, 145 + 710); + EXPECT_NEAR(get_mag_strength_tesla(-40, -125) * 1e9, 40535, 145 + 689); + EXPECT_NEAR(get_mag_strength_tesla(-40, -120) * 1e9, 39228, 145 + 667); + EXPECT_NEAR(get_mag_strength_tesla(-40, -115) * 1e9, 37846, 145 + 643); + EXPECT_NEAR(get_mag_strength_tesla(-40, -110) * 1e9, 36383, 145 + 619); + EXPECT_NEAR(get_mag_strength_tesla(-40, -105) * 1e9, 34844, 145 + 592); + EXPECT_NEAR(get_mag_strength_tesla(-40, -100) * 1e9, 33243, 145 + 565); + EXPECT_NEAR(get_mag_strength_tesla(-40, -95) * 1e9, 31609, 145 + 537); + EXPECT_NEAR(get_mag_strength_tesla(-40, -90) * 1e9, 29988, 145 + 510); + EXPECT_NEAR(get_mag_strength_tesla(-40, -85) * 1e9, 28435, 145 + 483); + EXPECT_NEAR(get_mag_strength_tesla(-40, -80) * 1e9, 27015, 145 + 459); + EXPECT_NEAR(get_mag_strength_tesla(-40, -75) * 1e9, 25792, 145 + 438); + EXPECT_NEAR(get_mag_strength_tesla(-40, -70) * 1e9, 24815, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(-40, -65) * 1e9, 24110, 145 + 410); + EXPECT_NEAR(get_mag_strength_tesla(-40, -60) * 1e9, 23672, 145 + 402); + EXPECT_NEAR(get_mag_strength_tesla(-40, -55) * 1e9, 23466, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(-40, -50) * 1e9, 23432, 145 + 398); + EXPECT_NEAR(get_mag_strength_tesla(-40, -45) * 1e9, 23504, 145 + 400); + EXPECT_NEAR(get_mag_strength_tesla(-40, -40) * 1e9, 23620, 145 + 402); + EXPECT_NEAR(get_mag_strength_tesla(-40, -35) * 1e9, 23732, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(-40, -30) * 1e9, 23812, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(-40, -25) * 1e9, 23846, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(-40, -20) * 1e9, 23831, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(-40, -15) * 1e9, 23771, 145 + 404); + EXPECT_NEAR(get_mag_strength_tesla(-40, -10) * 1e9, 23682, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(-40, -5) * 1e9, 23591, 145 + 401); + EXPECT_NEAR(get_mag_strength_tesla(-40, 0) * 1e9, 23542, 145 + 400); + EXPECT_NEAR(get_mag_strength_tesla(-40, 5) * 1e9, 23602, 145 + 401); + EXPECT_NEAR(get_mag_strength_tesla(-40, 10) * 1e9, 23849, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(-40, 15) * 1e9, 24364, 145 + 414); + EXPECT_NEAR(get_mag_strength_tesla(-40, 20) * 1e9, 25215, 145 + 429); + EXPECT_NEAR(get_mag_strength_tesla(-40, 25) * 1e9, 26445, 145 + 450); + EXPECT_NEAR(get_mag_strength_tesla(-40, 30) * 1e9, 28060, 145 + 477); + EXPECT_NEAR(get_mag_strength_tesla(-40, 35) * 1e9, 30036, 145 + 511); + EXPECT_NEAR(get_mag_strength_tesla(-40, 40) * 1e9, 32319, 145 + 549); + EXPECT_NEAR(get_mag_strength_tesla(-40, 45) * 1e9, 34838, 145 + 592); + EXPECT_NEAR(get_mag_strength_tesla(-40, 50) * 1e9, 37511, 145 + 638); + EXPECT_NEAR(get_mag_strength_tesla(-40, 55) * 1e9, 40255, 145 + 684); + EXPECT_NEAR(get_mag_strength_tesla(-40, 60) * 1e9, 42993, 145 + 731); + EXPECT_NEAR(get_mag_strength_tesla(-40, 65) * 1e9, 45663, 145 + 776); + EXPECT_NEAR(get_mag_strength_tesla(-40, 70) * 1e9, 48218, 145 + 820); + EXPECT_NEAR(get_mag_strength_tesla(-40, 75) * 1e9, 50623, 145 + 861); + EXPECT_NEAR(get_mag_strength_tesla(-40, 80) * 1e9, 52855, 145 + 899); + EXPECT_NEAR(get_mag_strength_tesla(-40, 85) * 1e9, 54891, 145 + 933); + EXPECT_NEAR(get_mag_strength_tesla(-40, 90) * 1e9, 56710, 145 + 964); + EXPECT_NEAR(get_mag_strength_tesla(-40, 95) * 1e9, 58289, 145 + 991); + EXPECT_NEAR(get_mag_strength_tesla(-40, 100) * 1e9, 59613, 145 + 1013); + EXPECT_NEAR(get_mag_strength_tesla(-40, 105) * 1e9, 60674, 145 + 1031); + EXPECT_NEAR(get_mag_strength_tesla(-40, 110) * 1e9, 61473, 145 + 1045); + EXPECT_NEAR(get_mag_strength_tesla(-40, 115) * 1e9, 62022, 145 + 1054); + EXPECT_NEAR(get_mag_strength_tesla(-40, 120) * 1e9, 62339, 145 + 1060); + EXPECT_NEAR(get_mag_strength_tesla(-40, 125) * 1e9, 62442, 145 + 1062); + EXPECT_NEAR(get_mag_strength_tesla(-40, 130) * 1e9, 62350, 145 + 1060); + EXPECT_NEAR(get_mag_strength_tesla(-40, 135) * 1e9, 62078, 145 + 1055); + EXPECT_NEAR(get_mag_strength_tesla(-40, 140) * 1e9, 61638, 145 + 1048); + EXPECT_NEAR(get_mag_strength_tesla(-40, 145) * 1e9, 61046, 145 + 1038); + EXPECT_NEAR(get_mag_strength_tesla(-40, 150) * 1e9, 60312, 145 + 1025); + EXPECT_NEAR(get_mag_strength_tesla(-40, 155) * 1e9, 59452, 145 + 1011); + EXPECT_NEAR(get_mag_strength_tesla(-40, 160) * 1e9, 58482, 145 + 994); + EXPECT_NEAR(get_mag_strength_tesla(-40, 165) * 1e9, 57419, 145 + 976); + EXPECT_NEAR(get_mag_strength_tesla(-40, 170) * 1e9, 56285, 145 + 957); + EXPECT_NEAR(get_mag_strength_tesla(-40, 175) * 1e9, 55099, 145 + 937); + EXPECT_NEAR(get_mag_strength_tesla(-40, 180) * 1e9, 53880, 145 + 916); + EXPECT_NEAR(get_mag_strength_tesla(-35, -180) * 1e9, 51386, 145 + 874); + EXPECT_NEAR(get_mag_strength_tesla(-35, -175) * 1e9, 50148, 145 + 853); + EXPECT_NEAR(get_mag_strength_tesla(-35, -170) * 1e9, 48908, 145 + 831); + EXPECT_NEAR(get_mag_strength_tesla(-35, -165) * 1e9, 47670, 145 + 810); + EXPECT_NEAR(get_mag_strength_tesla(-35, -160) * 1e9, 46441, 145 + 790); + EXPECT_NEAR(get_mag_strength_tesla(-35, -155) * 1e9, 45226, 145 + 769); + EXPECT_NEAR(get_mag_strength_tesla(-35, -150) * 1e9, 44030, 145 + 749); + EXPECT_NEAR(get_mag_strength_tesla(-35, -145) * 1e9, 42855, 145 + 729); + EXPECT_NEAR(get_mag_strength_tesla(-35, -140) * 1e9, 41698, 145 + 709); + EXPECT_NEAR(get_mag_strength_tesla(-35, -135) * 1e9, 40549, 145 + 689); + EXPECT_NEAR(get_mag_strength_tesla(-35, -130) * 1e9, 39394, 145 + 670); + EXPECT_NEAR(get_mag_strength_tesla(-35, -125) * 1e9, 38217, 145 + 650); + EXPECT_NEAR(get_mag_strength_tesla(-35, -120) * 1e9, 37000, 145 + 629); + EXPECT_NEAR(get_mag_strength_tesla(-35, -115) * 1e9, 35729, 145 + 607); + EXPECT_NEAR(get_mag_strength_tesla(-35, -110) * 1e9, 34390, 145 + 585); + EXPECT_NEAR(get_mag_strength_tesla(-35, -105) * 1e9, 32978, 145 + 561); + EXPECT_NEAR(get_mag_strength_tesla(-35, -100) * 1e9, 31499, 145 + 535); + EXPECT_NEAR(get_mag_strength_tesla(-35, -95) * 1e9, 29975, 145 + 510); + EXPECT_NEAR(get_mag_strength_tesla(-35, -90) * 1e9, 28447, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(-35, -85) * 1e9, 26977, 145 + 459); + EXPECT_NEAR(get_mag_strength_tesla(-35, -80) * 1e9, 25635, 145 + 436); + EXPECT_NEAR(get_mag_strength_tesla(-35, -75) * 1e9, 24495, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(-35, -70) * 1e9, 23615, 145 + 401); + EXPECT_NEAR(get_mag_strength_tesla(-35, -65) * 1e9, 23026, 145 + 391); + EXPECT_NEAR(get_mag_strength_tesla(-35, -60) * 1e9, 22722, 145 + 386); + EXPECT_NEAR(get_mag_strength_tesla(-35, -55) * 1e9, 22660, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(-35, -50) * 1e9, 22772, 145 + 387); + EXPECT_NEAR(get_mag_strength_tesla(-35, -45) * 1e9, 22985, 145 + 391); + EXPECT_NEAR(get_mag_strength_tesla(-35, -40) * 1e9, 23235, 145 + 395); + EXPECT_NEAR(get_mag_strength_tesla(-35, -35) * 1e9, 23478, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(-35, -30) * 1e9, 23691, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(-35, -25) * 1e9, 23864, 145 + 406); + EXPECT_NEAR(get_mag_strength_tesla(-35, -20) * 1e9, 23992, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(-35, -15) * 1e9, 24068, 145 + 409); + EXPECT_NEAR(get_mag_strength_tesla(-35, -10) * 1e9, 24092, 145 + 410); + EXPECT_NEAR(get_mag_strength_tesla(-35, -5) * 1e9, 24071, 145 + 409); + EXPECT_NEAR(get_mag_strength_tesla(-35, 0) * 1e9, 24036, 145 + 409); + EXPECT_NEAR(get_mag_strength_tesla(-35, 5) * 1e9, 24046, 145 + 409); + EXPECT_NEAR(get_mag_strength_tesla(-35, 10) * 1e9, 24185, 145 + 411); + EXPECT_NEAR(get_mag_strength_tesla(-35, 15) * 1e9, 24550, 145 + 417); + EXPECT_NEAR(get_mag_strength_tesla(-35, 20) * 1e9, 25231, 145 + 429); + EXPECT_NEAR(get_mag_strength_tesla(-35, 25) * 1e9, 26295, 145 + 447); + EXPECT_NEAR(get_mag_strength_tesla(-35, 30) * 1e9, 27772, 145 + 472); + EXPECT_NEAR(get_mag_strength_tesla(-35, 35) * 1e9, 29648, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(-35, 40) * 1e9, 31876, 145 + 542); + EXPECT_NEAR(get_mag_strength_tesla(-35, 45) * 1e9, 34375, 145 + 584); + EXPECT_NEAR(get_mag_strength_tesla(-35, 50) * 1e9, 37050, 145 + 630); + EXPECT_NEAR(get_mag_strength_tesla(-35, 55) * 1e9, 39801, 145 + 677); + EXPECT_NEAR(get_mag_strength_tesla(-35, 60) * 1e9, 42536, 145 + 723); + EXPECT_NEAR(get_mag_strength_tesla(-35, 65) * 1e9, 45178, 145 + 768); + EXPECT_NEAR(get_mag_strength_tesla(-35, 70) * 1e9, 47674, 145 + 810); + EXPECT_NEAR(get_mag_strength_tesla(-35, 75) * 1e9, 49987, 145 + 850); + EXPECT_NEAR(get_mag_strength_tesla(-35, 80) * 1e9, 52094, 145 + 886); + EXPECT_NEAR(get_mag_strength_tesla(-35, 85) * 1e9, 53976, 145 + 918); + EXPECT_NEAR(get_mag_strength_tesla(-35, 90) * 1e9, 55613, 145 + 945); + EXPECT_NEAR(get_mag_strength_tesla(-35, 95) * 1e9, 56990, 145 + 969); + EXPECT_NEAR(get_mag_strength_tesla(-35, 100) * 1e9, 58101, 145 + 988); + EXPECT_NEAR(get_mag_strength_tesla(-35, 105) * 1e9, 58949, 145 + 1002); + EXPECT_NEAR(get_mag_strength_tesla(-35, 110) * 1e9, 59552, 145 + 1012); + EXPECT_NEAR(get_mag_strength_tesla(-35, 115) * 1e9, 59934, 145 + 1019); + EXPECT_NEAR(get_mag_strength_tesla(-35, 120) * 1e9, 60119, 145 + 1022); + EXPECT_NEAR(get_mag_strength_tesla(-35, 125) * 1e9, 60127, 145 + 1022); + EXPECT_NEAR(get_mag_strength_tesla(-35, 130) * 1e9, 59972, 145 + 1020); + EXPECT_NEAR(get_mag_strength_tesla(-35, 135) * 1e9, 59660, 145 + 1014); + EXPECT_NEAR(get_mag_strength_tesla(-35, 140) * 1e9, 59198, 145 + 1006); + EXPECT_NEAR(get_mag_strength_tesla(-35, 145) * 1e9, 58593, 145 + 996); + EXPECT_NEAR(get_mag_strength_tesla(-35, 150) * 1e9, 57853, 145 + 983); + EXPECT_NEAR(get_mag_strength_tesla(-35, 155) * 1e9, 56988, 145 + 969); + EXPECT_NEAR(get_mag_strength_tesla(-35, 160) * 1e9, 56013, 145 + 952); + EXPECT_NEAR(get_mag_strength_tesla(-35, 165) * 1e9, 54945, 145 + 934); + EXPECT_NEAR(get_mag_strength_tesla(-35, 170) * 1e9, 53803, 145 + 915); + EXPECT_NEAR(get_mag_strength_tesla(-35, 175) * 1e9, 52610, 145 + 894); + EXPECT_NEAR(get_mag_strength_tesla(-35, 180) * 1e9, 51386, 145 + 874); + EXPECT_NEAR(get_mag_strength_tesla(-30, -180) * 1e9, 48750, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(-30, -175) * 1e9, 47536, 145 + 475); + EXPECT_NEAR(get_mag_strength_tesla(-30, -170) * 1e9, 46322, 145 + 463); + EXPECT_NEAR(get_mag_strength_tesla(-30, -165) * 1e9, 45113, 145 + 451); + EXPECT_NEAR(get_mag_strength_tesla(-30, -160) * 1e9, 43912, 145 + 439); + EXPECT_NEAR(get_mag_strength_tesla(-30, -155) * 1e9, 42723, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(-30, -150) * 1e9, 41552, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(-30, -145) * 1e9, 40404, 145 + 404); + EXPECT_NEAR(get_mag_strength_tesla(-30, -140) * 1e9, 39280, 145 + 393); + EXPECT_NEAR(get_mag_strength_tesla(-30, -135) * 1e9, 38176, 145 + 382); + EXPECT_NEAR(get_mag_strength_tesla(-30, -130) * 1e9, 37085, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(-30, -125) * 1e9, 35995, 145 + 360); + EXPECT_NEAR(get_mag_strength_tesla(-30, -120) * 1e9, 34891, 145 + 349); + EXPECT_NEAR(get_mag_strength_tesla(-30, -115) * 1e9, 33756, 145 + 338); + EXPECT_NEAR(get_mag_strength_tesla(-30, -110) * 1e9, 32574, 145 + 326); + EXPECT_NEAR(get_mag_strength_tesla(-30, -105) * 1e9, 31328, 145 + 313); + EXPECT_NEAR(get_mag_strength_tesla(-30, -100) * 1e9, 30012, 145 + 300); + EXPECT_NEAR(get_mag_strength_tesla(-30, -95) * 1e9, 28642, 145 + 286); + EXPECT_NEAR(get_mag_strength_tesla(-30, -90) * 1e9, 27255, 145 + 273); + EXPECT_NEAR(get_mag_strength_tesla(-30, -85) * 1e9, 25911, 145 + 259); + EXPECT_NEAR(get_mag_strength_tesla(-30, -80) * 1e9, 24686, 145 + 247); + EXPECT_NEAR(get_mag_strength_tesla(-30, -75) * 1e9, 23658, 145 + 237); + EXPECT_NEAR(get_mag_strength_tesla(-30, -70) * 1e9, 22890, 145 + 229); + EXPECT_NEAR(get_mag_strength_tesla(-30, -65) * 1e9, 22416, 145 + 224); + EXPECT_NEAR(get_mag_strength_tesla(-30, -60) * 1e9, 22227, 145 + 222); + EXPECT_NEAR(get_mag_strength_tesla(-30, -55) * 1e9, 22278, 145 + 223); + EXPECT_NEAR(get_mag_strength_tesla(-30, -50) * 1e9, 22498, 145 + 225); + EXPECT_NEAR(get_mag_strength_tesla(-30, -45) * 1e9, 22814, 145 + 228); + EXPECT_NEAR(get_mag_strength_tesla(-30, -40) * 1e9, 23167, 145 + 232); + EXPECT_NEAR(get_mag_strength_tesla(-30, -35) * 1e9, 23521, 145 + 235); + EXPECT_NEAR(get_mag_strength_tesla(-30, -30) * 1e9, 23864, 145 + 239); + EXPECT_NEAR(get_mag_strength_tesla(-30, -25) * 1e9, 24192, 145 + 242); + EXPECT_NEAR(get_mag_strength_tesla(-30, -20) * 1e9, 24496, 145 + 245); + EXPECT_NEAR(get_mag_strength_tesla(-30, -15) * 1e9, 24760, 145 + 248); + EXPECT_NEAR(get_mag_strength_tesla(-30, -10) * 1e9, 24962, 145 + 250); + EXPECT_NEAR(get_mag_strength_tesla(-30, -5) * 1e9, 25085, 145 + 251); + EXPECT_NEAR(get_mag_strength_tesla(-30, 0) * 1e9, 25140, 145 + 251); + EXPECT_NEAR(get_mag_strength_tesla(-30, 5) * 1e9, 25169, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-30, 10) * 1e9, 25250, 145 + 253); + EXPECT_NEAR(get_mag_strength_tesla(-30, 15) * 1e9, 25485, 145 + 255); + EXPECT_NEAR(get_mag_strength_tesla(-30, 20) * 1e9, 25978, 145 + 260); + EXPECT_NEAR(get_mag_strength_tesla(-30, 25) * 1e9, 26822, 145 + 268); + EXPECT_NEAR(get_mag_strength_tesla(-30, 30) * 1e9, 28072, 145 + 281); + EXPECT_NEAR(get_mag_strength_tesla(-30, 35) * 1e9, 29744, 145 + 297); + EXPECT_NEAR(get_mag_strength_tesla(-30, 40) * 1e9, 31802, 145 + 318); + EXPECT_NEAR(get_mag_strength_tesla(-30, 45) * 1e9, 34173, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(-30, 50) * 1e9, 36752, 145 + 368); + EXPECT_NEAR(get_mag_strength_tesla(-30, 55) * 1e9, 39425, 145 + 394); + EXPECT_NEAR(get_mag_strength_tesla(-30, 60) * 1e9, 42084, 145 + 421); + EXPECT_NEAR(get_mag_strength_tesla(-30, 65) * 1e9, 44640, 145 + 446); + EXPECT_NEAR(get_mag_strength_tesla(-30, 70) * 1e9, 47031, 145 + 470); + EXPECT_NEAR(get_mag_strength_tesla(-30, 75) * 1e9, 49216, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(-30, 80) * 1e9, 51166, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(-30, 85) * 1e9, 52862, 145 + 529); + EXPECT_NEAR(get_mag_strength_tesla(-30, 90) * 1e9, 54286, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(-30, 95) * 1e9, 55427, 145 + 554); + EXPECT_NEAR(get_mag_strength_tesla(-30, 100) * 1e9, 56288, 145 + 563); + EXPECT_NEAR(get_mag_strength_tesla(-30, 105) * 1e9, 56892, 145 + 569); + EXPECT_NEAR(get_mag_strength_tesla(-30, 110) * 1e9, 57275, 145 + 573); + EXPECT_NEAR(get_mag_strength_tesla(-30, 115) * 1e9, 57477, 145 + 575); + EXPECT_NEAR(get_mag_strength_tesla(-30, 120) * 1e9, 57531, 145 + 575); + EXPECT_NEAR(get_mag_strength_tesla(-30, 125) * 1e9, 57454, 145 + 575); + EXPECT_NEAR(get_mag_strength_tesla(-30, 130) * 1e9, 57252, 145 + 573); + EXPECT_NEAR(get_mag_strength_tesla(-30, 135) * 1e9, 56917, 145 + 569); + EXPECT_NEAR(get_mag_strength_tesla(-30, 140) * 1e9, 56448, 145 + 564); + EXPECT_NEAR(get_mag_strength_tesla(-30, 145) * 1e9, 55845, 145 + 558); + EXPECT_NEAR(get_mag_strength_tesla(-30, 150) * 1e9, 55114, 145 + 551); + EXPECT_NEAR(get_mag_strength_tesla(-30, 155) * 1e9, 54263, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(-30, 160) * 1e9, 53305, 145 + 533); + EXPECT_NEAR(get_mag_strength_tesla(-30, 165) * 1e9, 52253, 145 + 523); + EXPECT_NEAR(get_mag_strength_tesla(-30, 170) * 1e9, 51128, 145 + 511); + EXPECT_NEAR(get_mag_strength_tesla(-30, 175) * 1e9, 49953, 145 + 500); + EXPECT_NEAR(get_mag_strength_tesla(-30, 180) * 1e9, 48750, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(-25, -180) * 1e9, 45998, 145 + 460); + EXPECT_NEAR(get_mag_strength_tesla(-25, -175) * 1e9, 44836, 145 + 448); + EXPECT_NEAR(get_mag_strength_tesla(-25, -170) * 1e9, 43679, 145 + 437); + EXPECT_NEAR(get_mag_strength_tesla(-25, -165) * 1e9, 42529, 145 + 425); + EXPECT_NEAR(get_mag_strength_tesla(-25, -160) * 1e9, 41387, 145 + 414); + EXPECT_NEAR(get_mag_strength_tesla(-25, -155) * 1e9, 40255, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(-25, -150) * 1e9, 39140, 145 + 391); + EXPECT_NEAR(get_mag_strength_tesla(-25, -145) * 1e9, 38048, 145 + 380); + EXPECT_NEAR(get_mag_strength_tesla(-25, -140) * 1e9, 36984, 145 + 370); + EXPECT_NEAR(get_mag_strength_tesla(-25, -135) * 1e9, 35950, 145 + 359); + EXPECT_NEAR(get_mag_strength_tesla(-25, -130) * 1e9, 34943, 145 + 349); + EXPECT_NEAR(get_mag_strength_tesla(-25, -125) * 1e9, 33957, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(-25, -120) * 1e9, 32983, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(-25, -115) * 1e9, 32003, 145 + 320); + EXPECT_NEAR(get_mag_strength_tesla(-25, -110) * 1e9, 30994, 145 + 310); + EXPECT_NEAR(get_mag_strength_tesla(-25, -105) * 1e9, 29935, 145 + 299); + EXPECT_NEAR(get_mag_strength_tesla(-25, -100) * 1e9, 28809, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(-25, -95) * 1e9, 27624, 145 + 276); + EXPECT_NEAR(get_mag_strength_tesla(-25, -90) * 1e9, 26412, 145 + 264); + EXPECT_NEAR(get_mag_strength_tesla(-25, -85) * 1e9, 25230, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-25, -80) * 1e9, 24153, 145 + 242); + EXPECT_NEAR(get_mag_strength_tesla(-25, -75) * 1e9, 23257, 145 + 233); + EXPECT_NEAR(get_mag_strength_tesla(-25, -70) * 1e9, 22604, 145 + 226); + EXPECT_NEAR(get_mag_strength_tesla(-25, -65) * 1e9, 22229, 145 + 222); + EXPECT_NEAR(get_mag_strength_tesla(-25, -60) * 1e9, 22125, 145 + 221); + EXPECT_NEAR(get_mag_strength_tesla(-25, -55) * 1e9, 22250, 145 + 222); + EXPECT_NEAR(get_mag_strength_tesla(-25, -50) * 1e9, 22538, 145 + 225); + EXPECT_NEAR(get_mag_strength_tesla(-25, -45) * 1e9, 22923, 145 + 229); + EXPECT_NEAR(get_mag_strength_tesla(-25, -40) * 1e9, 23353, 145 + 234); + EXPECT_NEAR(get_mag_strength_tesla(-25, -35) * 1e9, 23803, 145 + 238); + EXPECT_NEAR(get_mag_strength_tesla(-25, -30) * 1e9, 24270, 145 + 243); + EXPECT_NEAR(get_mag_strength_tesla(-25, -25) * 1e9, 24753, 145 + 248); + EXPECT_NEAR(get_mag_strength_tesla(-25, -20) * 1e9, 25243, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-25, -15) * 1e9, 25713, 145 + 257); + EXPECT_NEAR(get_mag_strength_tesla(-25, -10) * 1e9, 26120, 145 + 261); + EXPECT_NEAR(get_mag_strength_tesla(-25, -5) * 1e9, 26428, 145 + 264); + EXPECT_NEAR(get_mag_strength_tesla(-25, 0) * 1e9, 26624, 145 + 266); + EXPECT_NEAR(get_mag_strength_tesla(-25, 5) * 1e9, 26729, 145 + 267); + EXPECT_NEAR(get_mag_strength_tesla(-25, 10) * 1e9, 26807, 145 + 268); + EXPECT_NEAR(get_mag_strength_tesla(-25, 15) * 1e9, 26950, 145 + 270); + EXPECT_NEAR(get_mag_strength_tesla(-25, 20) * 1e9, 27268, 145 + 273); + EXPECT_NEAR(get_mag_strength_tesla(-25, 25) * 1e9, 27868, 145 + 279); + EXPECT_NEAR(get_mag_strength_tesla(-25, 30) * 1e9, 28836, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(-25, 35) * 1e9, 30216, 145 + 302); + EXPECT_NEAR(get_mag_strength_tesla(-25, 40) * 1e9, 32004, 145 + 320); + EXPECT_NEAR(get_mag_strength_tesla(-25, 45) * 1e9, 34140, 145 + 341); + EXPECT_NEAR(get_mag_strength_tesla(-25, 50) * 1e9, 36520, 145 + 365); + EXPECT_NEAR(get_mag_strength_tesla(-25, 55) * 1e9, 39024, 145 + 390); + EXPECT_NEAR(get_mag_strength_tesla(-25, 60) * 1e9, 41531, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(-25, 65) * 1e9, 43941, 145 + 439); + EXPECT_NEAR(get_mag_strength_tesla(-25, 70) * 1e9, 46182, 145 + 462); + EXPECT_NEAR(get_mag_strength_tesla(-25, 75) * 1e9, 48208, 145 + 482); + EXPECT_NEAR(get_mag_strength_tesla(-25, 80) * 1e9, 49985, 145 + 500); + EXPECT_NEAR(get_mag_strength_tesla(-25, 85) * 1e9, 51484, 145 + 515); + EXPECT_NEAR(get_mag_strength_tesla(-25, 90) * 1e9, 52685, 145 + 527); + EXPECT_NEAR(get_mag_strength_tesla(-25, 95) * 1e9, 53579, 145 + 536); + EXPECT_NEAR(get_mag_strength_tesla(-25, 100) * 1e9, 54179, 145 + 542); + EXPECT_NEAR(get_mag_strength_tesla(-25, 105) * 1e9, 54529, 145 + 545); + EXPECT_NEAR(get_mag_strength_tesla(-25, 110) * 1e9, 54687, 145 + 547); + EXPECT_NEAR(get_mag_strength_tesla(-25, 115) * 1e9, 54713, 145 + 547); + EXPECT_NEAR(get_mag_strength_tesla(-25, 120) * 1e9, 54645, 145 + 546); + EXPECT_NEAR(get_mag_strength_tesla(-25, 125) * 1e9, 54497, 145 + 545); + EXPECT_NEAR(get_mag_strength_tesla(-25, 130) * 1e9, 54260, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(-25, 135) * 1e9, 53914, 145 + 539); + EXPECT_NEAR(get_mag_strength_tesla(-25, 140) * 1e9, 53446, 145 + 534); + EXPECT_NEAR(get_mag_strength_tesla(-25, 145) * 1e9, 52851, 145 + 529); + EXPECT_NEAR(get_mag_strength_tesla(-25, 150) * 1e9, 52137, 145 + 521); + EXPECT_NEAR(get_mag_strength_tesla(-25, 155) * 1e9, 51311, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(-25, 160) * 1e9, 50385, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(-25, 165) * 1e9, 49372, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(-25, 170) * 1e9, 48287, 145 + 483); + EXPECT_NEAR(get_mag_strength_tesla(-25, 175) * 1e9, 47155, 145 + 472); + EXPECT_NEAR(get_mag_strength_tesla(-25, 180) * 1e9, 45998, 145 + 460); + EXPECT_NEAR(get_mag_strength_tesla(-20, -180) * 1e9, 43192, 145 + 432); + EXPECT_NEAR(get_mag_strength_tesla(-20, -175) * 1e9, 42112, 145 + 421); + EXPECT_NEAR(get_mag_strength_tesla(-20, -170) * 1e9, 41042, 145 + 410); + EXPECT_NEAR(get_mag_strength_tesla(-20, -165) * 1e9, 39983, 145 + 400); + EXPECT_NEAR(get_mag_strength_tesla(-20, -160) * 1e9, 38935, 145 + 389); + EXPECT_NEAR(get_mag_strength_tesla(-20, -155) * 1e9, 37897, 145 + 379); + EXPECT_NEAR(get_mag_strength_tesla(-20, -150) * 1e9, 36875, 145 + 369); + EXPECT_NEAR(get_mag_strength_tesla(-20, -145) * 1e9, 35877, 145 + 359); + EXPECT_NEAR(get_mag_strength_tesla(-20, -140) * 1e9, 34909, 145 + 349); + EXPECT_NEAR(get_mag_strength_tesla(-20, -135) * 1e9, 33976, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(-20, -130) * 1e9, 33080, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(-20, -125) * 1e9, 32220, 145 + 322); + EXPECT_NEAR(get_mag_strength_tesla(-20, -120) * 1e9, 31390, 145 + 314); + EXPECT_NEAR(get_mag_strength_tesla(-20, -115) * 1e9, 30574, 145 + 306); + EXPECT_NEAR(get_mag_strength_tesla(-20, -110) * 1e9, 29747, 145 + 297); + EXPECT_NEAR(get_mag_strength_tesla(-20, -105) * 1e9, 28882, 145 + 289); + EXPECT_NEAR(get_mag_strength_tesla(-20, -100) * 1e9, 27959, 145 + 280); + EXPECT_NEAR(get_mag_strength_tesla(-20, -95) * 1e9, 26978, 145 + 270); + EXPECT_NEAR(get_mag_strength_tesla(-20, -90) * 1e9, 25964, 145 + 260); + EXPECT_NEAR(get_mag_strength_tesla(-20, -85) * 1e9, 24968, 145 + 250); + EXPECT_NEAR(get_mag_strength_tesla(-20, -80) * 1e9, 24057, 145 + 241); + EXPECT_NEAR(get_mag_strength_tesla(-20, -75) * 1e9, 23298, 145 + 233); + EXPECT_NEAR(get_mag_strength_tesla(-20, -70) * 1e9, 22748, 145 + 227); + EXPECT_NEAR(get_mag_strength_tesla(-20, -65) * 1e9, 22443, 145 + 224); + EXPECT_NEAR(get_mag_strength_tesla(-20, -60) * 1e9, 22384, 145 + 224); + EXPECT_NEAR(get_mag_strength_tesla(-20, -55) * 1e9, 22538, 145 + 225); + EXPECT_NEAR(get_mag_strength_tesla(-20, -50) * 1e9, 22855, 145 + 229); + EXPECT_NEAR(get_mag_strength_tesla(-20, -45) * 1e9, 23279, 145 + 233); + EXPECT_NEAR(get_mag_strength_tesla(-20, -40) * 1e9, 23766, 145 + 238); + EXPECT_NEAR(get_mag_strength_tesla(-20, -35) * 1e9, 24298, 145 + 243); + EXPECT_NEAR(get_mag_strength_tesla(-20, -30) * 1e9, 24873, 145 + 249); + EXPECT_NEAR(get_mag_strength_tesla(-20, -25) * 1e9, 25493, 145 + 255); + EXPECT_NEAR(get_mag_strength_tesla(-20, -20) * 1e9, 26145, 145 + 261); + EXPECT_NEAR(get_mag_strength_tesla(-20, -15) * 1e9, 26794, 145 + 268); + EXPECT_NEAR(get_mag_strength_tesla(-20, -10) * 1e9, 27386, 145 + 274); + EXPECT_NEAR(get_mag_strength_tesla(-20, -5) * 1e9, 27870, 145 + 279); + EXPECT_NEAR(get_mag_strength_tesla(-20, 0) * 1e9, 28213, 145 + 282); + EXPECT_NEAR(get_mag_strength_tesla(-20, 5) * 1e9, 28420, 145 + 284); + EXPECT_NEAR(get_mag_strength_tesla(-20, 10) * 1e9, 28532, 145 + 285); + EXPECT_NEAR(get_mag_strength_tesla(-20, 15) * 1e9, 28626, 145 + 286); + EXPECT_NEAR(get_mag_strength_tesla(-20, 20) * 1e9, 28803, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(-20, 25) * 1e9, 29174, 145 + 292); + EXPECT_NEAR(get_mag_strength_tesla(-20, 30) * 1e9, 29846, 145 + 298); + EXPECT_NEAR(get_mag_strength_tesla(-20, 35) * 1e9, 30897, 145 + 309); + EXPECT_NEAR(get_mag_strength_tesla(-20, 40) * 1e9, 32352, 145 + 324); + EXPECT_NEAR(get_mag_strength_tesla(-20, 45) * 1e9, 34175, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(-20, 50) * 1e9, 36274, 145 + 363); + EXPECT_NEAR(get_mag_strength_tesla(-20, 55) * 1e9, 38526, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(-20, 60) * 1e9, 40807, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(-20, 65) * 1e9, 43010, 145 + 430); + EXPECT_NEAR(get_mag_strength_tesla(-20, 70) * 1e9, 45060, 145 + 451); + EXPECT_NEAR(get_mag_strength_tesla(-20, 75) * 1e9, 46901, 145 + 469); + EXPECT_NEAR(get_mag_strength_tesla(-20, 80) * 1e9, 48493, 145 + 485); + EXPECT_NEAR(get_mag_strength_tesla(-20, 85) * 1e9, 49798, 145 + 498); + EXPECT_NEAR(get_mag_strength_tesla(-20, 90) * 1e9, 50785, 145 + 508); + EXPECT_NEAR(get_mag_strength_tesla(-20, 95) * 1e9, 51445, 145 + 514); + EXPECT_NEAR(get_mag_strength_tesla(-20, 100) * 1e9, 51802, 145 + 518); + EXPECT_NEAR(get_mag_strength_tesla(-20, 105) * 1e9, 51916, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(-20, 110) * 1e9, 51868, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(-20, 115) * 1e9, 51734, 145 + 517); + EXPECT_NEAR(get_mag_strength_tesla(-20, 120) * 1e9, 51561, 145 + 516); + EXPECT_NEAR(get_mag_strength_tesla(-20, 125) * 1e9, 51355, 145 + 514); + EXPECT_NEAR(get_mag_strength_tesla(-20, 130) * 1e9, 51092, 145 + 511); + EXPECT_NEAR(get_mag_strength_tesla(-20, 135) * 1e9, 50739, 145 + 507); + EXPECT_NEAR(get_mag_strength_tesla(-20, 140) * 1e9, 50273, 145 + 503); + EXPECT_NEAR(get_mag_strength_tesla(-20, 145) * 1e9, 49688, 145 + 497); + EXPECT_NEAR(get_mag_strength_tesla(-20, 150) * 1e9, 48992, 145 + 490); + EXPECT_NEAR(get_mag_strength_tesla(-20, 155) * 1e9, 48199, 145 + 482); + EXPECT_NEAR(get_mag_strength_tesla(-20, 160) * 1e9, 47318, 145 + 473); + EXPECT_NEAR(get_mag_strength_tesla(-20, 165) * 1e9, 46359, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(-20, 170) * 1e9, 45337, 145 + 453); + EXPECT_NEAR(get_mag_strength_tesla(-20, 175) * 1e9, 44274, 145 + 443); + EXPECT_NEAR(get_mag_strength_tesla(-20, 180) * 1e9, 43192, 145 + 432); + EXPECT_NEAR(get_mag_strength_tesla(-15, -180) * 1e9, 40439, 145 + 404); + EXPECT_NEAR(get_mag_strength_tesla(-15, -175) * 1e9, 39471, 145 + 395); + EXPECT_NEAR(get_mag_strength_tesla(-15, -170) * 1e9, 38520, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(-15, -165) * 1e9, 37585, 145 + 376); + EXPECT_NEAR(get_mag_strength_tesla(-15, -160) * 1e9, 36664, 145 + 367); + EXPECT_NEAR(get_mag_strength_tesla(-15, -155) * 1e9, 35756, 145 + 358); + EXPECT_NEAR(get_mag_strength_tesla(-15, -150) * 1e9, 34866, 145 + 349); + EXPECT_NEAR(get_mag_strength_tesla(-15, -145) * 1e9, 34002, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(-15, -140) * 1e9, 33169, 145 + 332); + EXPECT_NEAR(get_mag_strength_tesla(-15, -135) * 1e9, 32374, 145 + 324); + EXPECT_NEAR(get_mag_strength_tesla(-15, -130) * 1e9, 31620, 145 + 316); + EXPECT_NEAR(get_mag_strength_tesla(-15, -125) * 1e9, 30910, 145 + 309); + EXPECT_NEAR(get_mag_strength_tesla(-15, -120) * 1e9, 30237, 145 + 302); + EXPECT_NEAR(get_mag_strength_tesla(-15, -115) * 1e9, 29590, 145 + 296); + EXPECT_NEAR(get_mag_strength_tesla(-15, -110) * 1e9, 28946, 145 + 289); + EXPECT_NEAR(get_mag_strength_tesla(-15, -105) * 1e9, 28276, 145 + 283); + EXPECT_NEAR(get_mag_strength_tesla(-15, -100) * 1e9, 27559, 145 + 276); + EXPECT_NEAR(get_mag_strength_tesla(-15, -95) * 1e9, 26790, 145 + 268); + EXPECT_NEAR(get_mag_strength_tesla(-15, -90) * 1e9, 25985, 145 + 260); + EXPECT_NEAR(get_mag_strength_tesla(-15, -85) * 1e9, 25184, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-15, -80) * 1e9, 24437, 145 + 244); + EXPECT_NEAR(get_mag_strength_tesla(-15, -75) * 1e9, 23802, 145 + 238); + EXPECT_NEAR(get_mag_strength_tesla(-15, -70) * 1e9, 23330, 145 + 233); + EXPECT_NEAR(get_mag_strength_tesla(-15, -65) * 1e9, 23055, 145 + 231); + EXPECT_NEAR(get_mag_strength_tesla(-15, -60) * 1e9, 22991, 145 + 230); + EXPECT_NEAR(get_mag_strength_tesla(-15, -55) * 1e9, 23126, 145 + 231); EXPECT_NEAR(get_mag_strength_tesla(-15, -50) * 1e9, 23427, 145 + 234); - EXPECT_NEAR(get_mag_strength_tesla(-15, -45) * 1e9, 23852, 145 + 239); - EXPECT_NEAR(get_mag_strength_tesla(-15, -40) * 1e9, 24370, 145 + 244); - EXPECT_NEAR(get_mag_strength_tesla(-15, -35) * 1e9, 24960, 145 + 250); - EXPECT_NEAR(get_mag_strength_tesla(-15, -30) * 1e9, 25616, 145 + 256); - EXPECT_NEAR(get_mag_strength_tesla(-15, -25) * 1e9, 26332, 145 + 263); - EXPECT_NEAR(get_mag_strength_tesla(-15, -20) * 1e9, 27093, 145 + 271); - EXPECT_NEAR(get_mag_strength_tesla(-15, -15) * 1e9, 27860, 145 + 279); - EXPECT_NEAR(get_mag_strength_tesla(-15, -10) * 1e9, 28579, 145 + 286); - EXPECT_NEAR(get_mag_strength_tesla(-15, -5) * 1e9, 29192, 145 + 292); - EXPECT_NEAR(get_mag_strength_tesla(-15, 0) * 1e9, 29657, 145 + 297); - EXPECT_NEAR(get_mag_strength_tesla(-15, 5) * 1e9, 29963, 145 + 300); - EXPECT_NEAR(get_mag_strength_tesla(-15, 10) * 1e9, 30129, 145 + 301); - EXPECT_NEAR(get_mag_strength_tesla(-15, 15) * 1e9, 30210, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(-15, 20) * 1e9, 30290, 145 + 303); - EXPECT_NEAR(get_mag_strength_tesla(-15, 25) * 1e9, 30476, 145 + 305); - EXPECT_NEAR(get_mag_strength_tesla(-15, 30) * 1e9, 30883, 145 + 309); + EXPECT_NEAR(get_mag_strength_tesla(-15, -45) * 1e9, 23856, 145 + 239); + EXPECT_NEAR(get_mag_strength_tesla(-15, -40) * 1e9, 24376, 145 + 244); + EXPECT_NEAR(get_mag_strength_tesla(-15, -35) * 1e9, 24967, 145 + 250); + EXPECT_NEAR(get_mag_strength_tesla(-15, -30) * 1e9, 25623, 145 + 256); + EXPECT_NEAR(get_mag_strength_tesla(-15, -25) * 1e9, 26339, 145 + 263); + EXPECT_NEAR(get_mag_strength_tesla(-15, -20) * 1e9, 27098, 145 + 271); + EXPECT_NEAR(get_mag_strength_tesla(-15, -15) * 1e9, 27863, 145 + 279); + EXPECT_NEAR(get_mag_strength_tesla(-15, -10) * 1e9, 28578, 145 + 286); + EXPECT_NEAR(get_mag_strength_tesla(-15, -5) * 1e9, 29186, 145 + 292); + EXPECT_NEAR(get_mag_strength_tesla(-15, 0) * 1e9, 29645, 145 + 296); + EXPECT_NEAR(get_mag_strength_tesla(-15, 5) * 1e9, 29945, 145 + 299); + EXPECT_NEAR(get_mag_strength_tesla(-15, 10) * 1e9, 30108, 145 + 301); + EXPECT_NEAR(get_mag_strength_tesla(-15, 15) * 1e9, 30188, 145 + 302); + EXPECT_NEAR(get_mag_strength_tesla(-15, 20) * 1e9, 30270, 145 + 303); + EXPECT_NEAR(get_mag_strength_tesla(-15, 25) * 1e9, 30460, 145 + 305); + EXPECT_NEAR(get_mag_strength_tesla(-15, 30) * 1e9, 30874, 145 + 309); EXPECT_NEAR(get_mag_strength_tesla(-15, 35) * 1e9, 31612, 145 + 316); - EXPECT_NEAR(get_mag_strength_tesla(-15, 40) * 1e9, 32718, 145 + 327); - EXPECT_NEAR(get_mag_strength_tesla(-15, 45) * 1e9, 34189, 145 + 342); - EXPECT_NEAR(get_mag_strength_tesla(-15, 50) * 1e9, 35952, 145 + 360); - EXPECT_NEAR(get_mag_strength_tesla(-15, 55) * 1e9, 37891, 145 + 379); - EXPECT_NEAR(get_mag_strength_tesla(-15, 60) * 1e9, 39886, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(-15, 65) * 1e9, 41832, 145 + 418); - EXPECT_NEAR(get_mag_strength_tesla(-15, 70) * 1e9, 43652, 145 + 437); - EXPECT_NEAR(get_mag_strength_tesla(-15, 75) * 1e9, 45289, 145 + 453); - EXPECT_NEAR(get_mag_strength_tesla(-15, 80) * 1e9, 46694, 145 + 467); - EXPECT_NEAR(get_mag_strength_tesla(-15, 85) * 1e9, 47817, 145 + 478); - EXPECT_NEAR(get_mag_strength_tesla(-15, 90) * 1e9, 48619, 145 + 486); - EXPECT_NEAR(get_mag_strength_tesla(-15, 95) * 1e9, 49084, 145 + 491); - EXPECT_NEAR(get_mag_strength_tesla(-15, 100) * 1e9, 49242, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(-15, 105) * 1e9, 49164, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(-15, 110) * 1e9, 48951, 145 + 490); - EXPECT_NEAR(get_mag_strength_tesla(-15, 115) * 1e9, 48690, 145 + 487); - EXPECT_NEAR(get_mag_strength_tesla(-15, 120) * 1e9, 48432, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(-15, 125) * 1e9, 48176, 145 + 482); - EXPECT_NEAR(get_mag_strength_tesla(-15, 130) * 1e9, 47888, 145 + 479); - EXPECT_NEAR(get_mag_strength_tesla(-15, 135) * 1e9, 47523, 145 + 475); - EXPECT_NEAR(get_mag_strength_tesla(-15, 140) * 1e9, 47053, 145 + 471); - EXPECT_NEAR(get_mag_strength_tesla(-15, 145) * 1e9, 46474, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(-15, 150) * 1e9, 45797, 145 + 458); - EXPECT_NEAR(get_mag_strength_tesla(-15, 155) * 1e9, 45039, 145 + 450); - EXPECT_NEAR(get_mag_strength_tesla(-15, 160) * 1e9, 44210, 145 + 442); - EXPECT_NEAR(get_mag_strength_tesla(-15, 165) * 1e9, 43321, 145 + 433); - EXPECT_NEAR(get_mag_strength_tesla(-15, 170) * 1e9, 42384, 145 + 424); + EXPECT_NEAR(get_mag_strength_tesla(-15, 40) * 1e9, 32728, 145 + 327); + EXPECT_NEAR(get_mag_strength_tesla(-15, 45) * 1e9, 34208, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(-15, 50) * 1e9, 35978, 145 + 360); + EXPECT_NEAR(get_mag_strength_tesla(-15, 55) * 1e9, 37922, 145 + 379); + EXPECT_NEAR(get_mag_strength_tesla(-15, 60) * 1e9, 39919, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(-15, 65) * 1e9, 41865, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(-15, 70) * 1e9, 43683, 145 + 437); + EXPECT_NEAR(get_mag_strength_tesla(-15, 75) * 1e9, 45317, 145 + 453); + EXPECT_NEAR(get_mag_strength_tesla(-15, 80) * 1e9, 46717, 145 + 467); + EXPECT_NEAR(get_mag_strength_tesla(-15, 85) * 1e9, 47835, 145 + 478); + EXPECT_NEAR(get_mag_strength_tesla(-15, 90) * 1e9, 48631, 145 + 486); + EXPECT_NEAR(get_mag_strength_tesla(-15, 95) * 1e9, 49092, 145 + 491); + EXPECT_NEAR(get_mag_strength_tesla(-15, 100) * 1e9, 49247, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(-15, 105) * 1e9, 49168, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(-15, 110) * 1e9, 48954, 145 + 490); + EXPECT_NEAR(get_mag_strength_tesla(-15, 115) * 1e9, 48693, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(-15, 120) * 1e9, 48434, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(-15, 125) * 1e9, 48179, 145 + 482); + EXPECT_NEAR(get_mag_strength_tesla(-15, 130) * 1e9, 47892, 145 + 479); + EXPECT_NEAR(get_mag_strength_tesla(-15, 135) * 1e9, 47528, 145 + 475); + EXPECT_NEAR(get_mag_strength_tesla(-15, 140) * 1e9, 47058, 145 + 471); + EXPECT_NEAR(get_mag_strength_tesla(-15, 145) * 1e9, 46479, 145 + 465); + EXPECT_NEAR(get_mag_strength_tesla(-15, 150) * 1e9, 45802, 145 + 458); + EXPECT_NEAR(get_mag_strength_tesla(-15, 155) * 1e9, 45042, 145 + 450); + EXPECT_NEAR(get_mag_strength_tesla(-15, 160) * 1e9, 44214, 145 + 442); + EXPECT_NEAR(get_mag_strength_tesla(-15, 165) * 1e9, 43324, 145 + 433); + EXPECT_NEAR(get_mag_strength_tesla(-15, 170) * 1e9, 42385, 145 + 424); EXPECT_NEAR(get_mag_strength_tesla(-15, 175) * 1e9, 41416, 145 + 414); - EXPECT_NEAR(get_mag_strength_tesla(-15, 180) * 1e9, 40441, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(-10, -180) * 1e9, 37894, 145 + 379); - EXPECT_NEAR(get_mag_strength_tesla(-10, -175) * 1e9, 37070, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(-10, -170) * 1e9, 36269, 145 + 363); - EXPECT_NEAR(get_mag_strength_tesla(-10, -165) * 1e9, 35488, 145 + 355); - EXPECT_NEAR(get_mag_strength_tesla(-10, -160) * 1e9, 34724, 145 + 347); - EXPECT_NEAR(get_mag_strength_tesla(-10, -155) * 1e9, 33977, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(-10, -150) * 1e9, 33252, 145 + 333); - EXPECT_NEAR(get_mag_strength_tesla(-10, -145) * 1e9, 32556, 145 + 326); - EXPECT_NEAR(get_mag_strength_tesla(-10, -140) * 1e9, 31895, 145 + 319); - EXPECT_NEAR(get_mag_strength_tesla(-10, -135) * 1e9, 31273, 145 + 313); - EXPECT_NEAR(get_mag_strength_tesla(-10, -130) * 1e9, 30692, 145 + 307); - EXPECT_NEAR(get_mag_strength_tesla(-10, -125) * 1e9, 30152, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(-10, -120) * 1e9, 29653, 145 + 297); - EXPECT_NEAR(get_mag_strength_tesla(-10, -115) * 1e9, 29182, 145 + 292); - EXPECT_NEAR(get_mag_strength_tesla(-10, -110) * 1e9, 28721, 145 + 287); - EXPECT_NEAR(get_mag_strength_tesla(-10, -105) * 1e9, 28245, 145 + 282); - EXPECT_NEAR(get_mag_strength_tesla(-10, -100) * 1e9, 27732, 145 + 277); - EXPECT_NEAR(get_mag_strength_tesla(-10, -95) * 1e9, 27172, 145 + 272); - EXPECT_NEAR(get_mag_strength_tesla(-10, -90) * 1e9, 26571, 145 + 266); - EXPECT_NEAR(get_mag_strength_tesla(-10, -85) * 1e9, 25951, 145 + 260); - EXPECT_NEAR(get_mag_strength_tesla(-10, -80) * 1e9, 25349, 145 + 253); - EXPECT_NEAR(get_mag_strength_tesla(-10, -75) * 1e9, 24809, 145 + 248); - EXPECT_NEAR(get_mag_strength_tesla(-10, -70) * 1e9, 24373, 145 + 244); - EXPECT_NEAR(get_mag_strength_tesla(-10, -65) * 1e9, 24080, 145 + 241); - EXPECT_NEAR(get_mag_strength_tesla(-10, -60) * 1e9, 23956, 145 + 240); - EXPECT_NEAR(get_mag_strength_tesla(-10, -55) * 1e9, 24012, 145 + 240); + EXPECT_NEAR(get_mag_strength_tesla(-15, 180) * 1e9, 40439, 145 + 404); + EXPECT_NEAR(get_mag_strength_tesla(-10, -180) * 1e9, 37892, 145 + 379); + EXPECT_NEAR(get_mag_strength_tesla(-10, -175) * 1e9, 37066, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(-10, -170) * 1e9, 36263, 145 + 363); + EXPECT_NEAR(get_mag_strength_tesla(-10, -165) * 1e9, 35480, 145 + 355); + EXPECT_NEAR(get_mag_strength_tesla(-10, -160) * 1e9, 34714, 145 + 347); + EXPECT_NEAR(get_mag_strength_tesla(-10, -155) * 1e9, 33967, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(-10, -150) * 1e9, 33241, 145 + 332); + EXPECT_NEAR(get_mag_strength_tesla(-10, -145) * 1e9, 32545, 145 + 325); + EXPECT_NEAR(get_mag_strength_tesla(-10, -140) * 1e9, 31883, 145 + 319); + EXPECT_NEAR(get_mag_strength_tesla(-10, -135) * 1e9, 31261, 145 + 313); + EXPECT_NEAR(get_mag_strength_tesla(-10, -130) * 1e9, 30679, 145 + 307); + EXPECT_NEAR(get_mag_strength_tesla(-10, -125) * 1e9, 30139, 145 + 301); + EXPECT_NEAR(get_mag_strength_tesla(-10, -120) * 1e9, 29639, 145 + 296); + EXPECT_NEAR(get_mag_strength_tesla(-10, -115) * 1e9, 29166, 145 + 292); + EXPECT_NEAR(get_mag_strength_tesla(-10, -110) * 1e9, 28704, 145 + 287); + EXPECT_NEAR(get_mag_strength_tesla(-10, -105) * 1e9, 28226, 145 + 282); + EXPECT_NEAR(get_mag_strength_tesla(-10, -100) * 1e9, 27711, 145 + 277); + EXPECT_NEAR(get_mag_strength_tesla(-10, -95) * 1e9, 27149, 145 + 271); + EXPECT_NEAR(get_mag_strength_tesla(-10, -90) * 1e9, 26546, 145 + 265); + EXPECT_NEAR(get_mag_strength_tesla(-10, -85) * 1e9, 25926, 145 + 259); + EXPECT_NEAR(get_mag_strength_tesla(-10, -80) * 1e9, 25324, 145 + 253); + EXPECT_NEAR(get_mag_strength_tesla(-10, -75) * 1e9, 24785, 145 + 248); + EXPECT_NEAR(get_mag_strength_tesla(-10, -70) * 1e9, 24352, 145 + 244); + EXPECT_NEAR(get_mag_strength_tesla(-10, -65) * 1e9, 24063, 145 + 241); + EXPECT_NEAR(get_mag_strength_tesla(-10, -60) * 1e9, 23944, 145 + 239); + EXPECT_NEAR(get_mag_strength_tesla(-10, -55) * 1e9, 24006, 145 + 240); EXPECT_NEAR(get_mag_strength_tesla(-10, -50) * 1e9, 24242, 145 + 242); - EXPECT_NEAR(get_mag_strength_tesla(-10, -45) * 1e9, 24626, 145 + 246); - EXPECT_NEAR(get_mag_strength_tesla(-10, -40) * 1e9, 25136, 145 + 251); - EXPECT_NEAR(get_mag_strength_tesla(-10, -35) * 1e9, 25746, 145 + 257); - EXPECT_NEAR(get_mag_strength_tesla(-10, -30) * 1e9, 26437, 145 + 264); - EXPECT_NEAR(get_mag_strength_tesla(-10, -25) * 1e9, 27192, 145 + 272); - EXPECT_NEAR(get_mag_strength_tesla(-10, -20) * 1e9, 27988, 145 + 280); - EXPECT_NEAR(get_mag_strength_tesla(-10, -15) * 1e9, 28791, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(-10, -10) * 1e9, 29552, 145 + 296); - EXPECT_NEAR(get_mag_strength_tesla(-10, -5) * 1e9, 30217, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(-10, 0) * 1e9, 30746, 145 + 307); - EXPECT_NEAR(get_mag_strength_tesla(-10, 5) * 1e9, 31118, 145 + 311); - EXPECT_NEAR(get_mag_strength_tesla(-10, 10) * 1e9, 31336, 145 + 313); - EXPECT_NEAR(get_mag_strength_tesla(-10, 15) * 1e9, 31432, 145 + 314); - EXPECT_NEAR(get_mag_strength_tesla(-10, 20) * 1e9, 31471, 145 + 315); - EXPECT_NEAR(get_mag_strength_tesla(-10, 25) * 1e9, 31546, 145 + 315); - EXPECT_NEAR(get_mag_strength_tesla(-10, 30) * 1e9, 31772, 145 + 318); - EXPECT_NEAR(get_mag_strength_tesla(-10, 35) * 1e9, 32256, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(-10, 40) * 1e9, 33071, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(-10, 45) * 1e9, 34222, 145 + 342); - EXPECT_NEAR(get_mag_strength_tesla(-10, 50) * 1e9, 35652, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(-10, 55) * 1e9, 37262, 145 + 373); - EXPECT_NEAR(get_mag_strength_tesla(-10, 60) * 1e9, 38943, 145 + 389); - EXPECT_NEAR(get_mag_strength_tesla(-10, 65) * 1e9, 40600, 145 + 406); - EXPECT_NEAR(get_mag_strength_tesla(-10, 70) * 1e9, 42161, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(-10, 75) * 1e9, 43572, 145 + 436); - EXPECT_NEAR(get_mag_strength_tesla(-10, 80) * 1e9, 44779, 145 + 448); - EXPECT_NEAR(get_mag_strength_tesla(-10, 85) * 1e9, 45726, 145 + 457); - EXPECT_NEAR(get_mag_strength_tesla(-10, 90) * 1e9, 46366, 145 + 464); - EXPECT_NEAR(get_mag_strength_tesla(-10, 95) * 1e9, 46678, 145 + 467); - EXPECT_NEAR(get_mag_strength_tesla(-10, 100) * 1e9, 46690, 145 + 467); - EXPECT_NEAR(get_mag_strength_tesla(-10, 105) * 1e9, 46482, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(-10, 110) * 1e9, 46156, 145 + 462); - EXPECT_NEAR(get_mag_strength_tesla(-10, 115) * 1e9, 45806, 145 + 458); - EXPECT_NEAR(get_mag_strength_tesla(-10, 120) * 1e9, 45480, 145 + 455); - EXPECT_NEAR(get_mag_strength_tesla(-10, 125) * 1e9, 45175, 145 + 452); - EXPECT_NEAR(get_mag_strength_tesla(-10, 130) * 1e9, 44852, 145 + 449); - EXPECT_NEAR(get_mag_strength_tesla(-10, 135) * 1e9, 44462, 145 + 445); - EXPECT_NEAR(get_mag_strength_tesla(-10, 140) * 1e9, 43976, 145 + 440); - EXPECT_NEAR(get_mag_strength_tesla(-10, 145) * 1e9, 43393, 145 + 434); - EXPECT_NEAR(get_mag_strength_tesla(-10, 150) * 1e9, 42729, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(-10, 155) * 1e9, 42004, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(-10, 160) * 1e9, 41232, 145 + 412); - EXPECT_NEAR(get_mag_strength_tesla(-10, 165) * 1e9, 40423, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(-10, 170) * 1e9, 39586, 145 + 396); + EXPECT_NEAR(get_mag_strength_tesla(-10, -45) * 1e9, 24630, 145 + 246); + EXPECT_NEAR(get_mag_strength_tesla(-10, -40) * 1e9, 25144, 145 + 251); + EXPECT_NEAR(get_mag_strength_tesla(-10, -35) * 1e9, 25756, 145 + 258); + EXPECT_NEAR(get_mag_strength_tesla(-10, -30) * 1e9, 26447, 145 + 264); + EXPECT_NEAR(get_mag_strength_tesla(-10, -25) * 1e9, 27201, 145 + 272); + EXPECT_NEAR(get_mag_strength_tesla(-10, -20) * 1e9, 27997, 145 + 280); + EXPECT_NEAR(get_mag_strength_tesla(-10, -15) * 1e9, 28798, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(-10, -10) * 1e9, 29555, 145 + 296); + EXPECT_NEAR(get_mag_strength_tesla(-10, -5) * 1e9, 30216, 145 + 302); + EXPECT_NEAR(get_mag_strength_tesla(-10, 0) * 1e9, 30740, 145 + 307); + EXPECT_NEAR(get_mag_strength_tesla(-10, 5) * 1e9, 31106, 145 + 311); + EXPECT_NEAR(get_mag_strength_tesla(-10, 10) * 1e9, 31320, 145 + 313); + EXPECT_NEAR(get_mag_strength_tesla(-10, 15) * 1e9, 31415, 145 + 314); + EXPECT_NEAR(get_mag_strength_tesla(-10, 20) * 1e9, 31454, 145 + 315); + EXPECT_NEAR(get_mag_strength_tesla(-10, 25) * 1e9, 31531, 145 + 315); + EXPECT_NEAR(get_mag_strength_tesla(-10, 30) * 1e9, 31762, 145 + 318); + EXPECT_NEAR(get_mag_strength_tesla(-10, 35) * 1e9, 32254, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(-10, 40) * 1e9, 33077, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(-10, 45) * 1e9, 34236, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(-10, 50) * 1e9, 35673, 145 + 357); + EXPECT_NEAR(get_mag_strength_tesla(-10, 55) * 1e9, 37288, 145 + 373); + EXPECT_NEAR(get_mag_strength_tesla(-10, 60) * 1e9, 38971, 145 + 390); + EXPECT_NEAR(get_mag_strength_tesla(-10, 65) * 1e9, 40628, 145 + 406); + EXPECT_NEAR(get_mag_strength_tesla(-10, 70) * 1e9, 42189, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(-10, 75) * 1e9, 43597, 145 + 436); + EXPECT_NEAR(get_mag_strength_tesla(-10, 80) * 1e9, 44800, 145 + 448); + EXPECT_NEAR(get_mag_strength_tesla(-10, 85) * 1e9, 45743, 145 + 457); + EXPECT_NEAR(get_mag_strength_tesla(-10, 90) * 1e9, 46377, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(-10, 95) * 1e9, 46685, 145 + 467); + EXPECT_NEAR(get_mag_strength_tesla(-10, 100) * 1e9, 46695, 145 + 467); + EXPECT_NEAR(get_mag_strength_tesla(-10, 105) * 1e9, 46485, 145 + 465); + EXPECT_NEAR(get_mag_strength_tesla(-10, 110) * 1e9, 46158, 145 + 462); + EXPECT_NEAR(get_mag_strength_tesla(-10, 115) * 1e9, 45807, 145 + 458); + EXPECT_NEAR(get_mag_strength_tesla(-10, 120) * 1e9, 45482, 145 + 455); + EXPECT_NEAR(get_mag_strength_tesla(-10, 125) * 1e9, 45178, 145 + 452); + EXPECT_NEAR(get_mag_strength_tesla(-10, 130) * 1e9, 44855, 145 + 449); + EXPECT_NEAR(get_mag_strength_tesla(-10, 135) * 1e9, 44466, 145 + 445); + EXPECT_NEAR(get_mag_strength_tesla(-10, 140) * 1e9, 43982, 145 + 440); + EXPECT_NEAR(get_mag_strength_tesla(-10, 145) * 1e9, 43399, 145 + 434); + EXPECT_NEAR(get_mag_strength_tesla(-10, 150) * 1e9, 42735, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(-10, 155) * 1e9, 42009, 145 + 420); + EXPECT_NEAR(get_mag_strength_tesla(-10, 160) * 1e9, 41237, 145 + 412); + EXPECT_NEAR(get_mag_strength_tesla(-10, 165) * 1e9, 40426, 145 + 404); + EXPECT_NEAR(get_mag_strength_tesla(-10, 170) * 1e9, 39588, 145 + 396); EXPECT_NEAR(get_mag_strength_tesla(-10, 175) * 1e9, 38737, 145 + 387); - EXPECT_NEAR(get_mag_strength_tesla(-10, 180) * 1e9, 37894, 145 + 379); - EXPECT_NEAR(get_mag_strength_tesla(-5, -180) * 1e9, 35733, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(-5, -175) * 1e9, 35073, 145 + 351); - EXPECT_NEAR(get_mag_strength_tesla(-5, -170) * 1e9, 34440, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(-5, -165) * 1e9, 33829, 145 + 338); - EXPECT_NEAR(get_mag_strength_tesla(-5, -160) * 1e9, 33238, 145 + 332); - EXPECT_NEAR(get_mag_strength_tesla(-5, -155) * 1e9, 32669, 145 + 327); - EXPECT_NEAR(get_mag_strength_tesla(-5, -150) * 1e9, 32129, 145 + 321); - EXPECT_NEAR(get_mag_strength_tesla(-5, -145) * 1e9, 31625, 145 + 316); - EXPECT_NEAR(get_mag_strength_tesla(-5, -140) * 1e9, 31161, 145 + 312); - EXPECT_NEAR(get_mag_strength_tesla(-5, -135) * 1e9, 30737, 145 + 307); - EXPECT_NEAR(get_mag_strength_tesla(-5, -130) * 1e9, 30352, 145 + 304); - EXPECT_NEAR(get_mag_strength_tesla(-5, -125) * 1e9, 30002, 145 + 300); - EXPECT_NEAR(get_mag_strength_tesla(-5, -120) * 1e9, 29686, 145 + 297); - EXPECT_NEAR(get_mag_strength_tesla(-5, -115) * 1e9, 29395, 145 + 294); - EXPECT_NEAR(get_mag_strength_tesla(-5, -110) * 1e9, 29115, 145 + 291); - EXPECT_NEAR(get_mag_strength_tesla(-5, -105) * 1e9, 28825, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(-5, -100) * 1e9, 28503, 145 + 285); - EXPECT_NEAR(get_mag_strength_tesla(-5, -95) * 1e9, 28133, 145 + 281); - EXPECT_NEAR(get_mag_strength_tesla(-5, -90) * 1e9, 27708, 145 + 277); - EXPECT_NEAR(get_mag_strength_tesla(-5, -85) * 1e9, 27238, 145 + 272); - EXPECT_NEAR(get_mag_strength_tesla(-5, -80) * 1e9, 26745, 145 + 267); - EXPECT_NEAR(get_mag_strength_tesla(-5, -75) * 1e9, 26262, 145 + 263); - EXPECT_NEAR(get_mag_strength_tesla(-5, -70) * 1e9, 25827, 145 + 258); - EXPECT_NEAR(get_mag_strength_tesla(-5, -65) * 1e9, 25480, 145 + 255); - EXPECT_NEAR(get_mag_strength_tesla(-5, -60) * 1e9, 25259, 145 + 253); - EXPECT_NEAR(get_mag_strength_tesla(-5, -55) * 1e9, 25194, 145 + 252); - EXPECT_NEAR(get_mag_strength_tesla(-5, -50) * 1e9, 25305, 145 + 253); - EXPECT_NEAR(get_mag_strength_tesla(-5, -45) * 1e9, 25593, 145 + 256); - EXPECT_NEAR(get_mag_strength_tesla(-5, -40) * 1e9, 26038, 145 + 260); - EXPECT_NEAR(get_mag_strength_tesla(-5, -35) * 1e9, 26610, 145 + 266); - EXPECT_NEAR(get_mag_strength_tesla(-5, -30) * 1e9, 27277, 145 + 273); - EXPECT_NEAR(get_mag_strength_tesla(-5, -25) * 1e9, 28006, 145 + 280); - EXPECT_NEAR(get_mag_strength_tesla(-5, -20) * 1e9, 28771, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(-5, -15) * 1e9, 29538, 145 + 295); - EXPECT_NEAR(get_mag_strength_tesla(-5, -10) * 1e9, 30268, 145 + 303); - EXPECT_NEAR(get_mag_strength_tesla(-5, -5) * 1e9, 30922, 145 + 309); - EXPECT_NEAR(get_mag_strength_tesla(-5, 0) * 1e9, 31464, 145 + 315); - EXPECT_NEAR(get_mag_strength_tesla(-5, 5) * 1e9, 31871, 145 + 319); - EXPECT_NEAR(get_mag_strength_tesla(-5, 10) * 1e9, 32135, 145 + 321); - EXPECT_NEAR(get_mag_strength_tesla(-5, 15) * 1e9, 32270, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(-5, 20) * 1e9, 32320, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(-5, 25) * 1e9, 32362, 145 + 324); - EXPECT_NEAR(get_mag_strength_tesla(-5, 30) * 1e9, 32500, 145 + 325); - EXPECT_NEAR(get_mag_strength_tesla(-5, 35) * 1e9, 32837, 145 + 328); - EXPECT_NEAR(get_mag_strength_tesla(-5, 40) * 1e9, 33445, 145 + 334); - EXPECT_NEAR(get_mag_strength_tesla(-5, 45) * 1e9, 34337, 145 + 343); - EXPECT_NEAR(get_mag_strength_tesla(-5, 50) * 1e9, 35472, 145 + 355); - EXPECT_NEAR(get_mag_strength_tesla(-5, 55) * 1e9, 36769, 145 + 368); - EXPECT_NEAR(get_mag_strength_tesla(-5, 60) * 1e9, 38138, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(-5, 65) * 1e9, 39501, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(-5, 70) * 1e9, 40797, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(-5, 75) * 1e9, 41977, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(-5, 80) * 1e9, 42987, 145 + 430); - EXPECT_NEAR(get_mag_strength_tesla(-5, 85) * 1e9, 43770, 145 + 438); - EXPECT_NEAR(get_mag_strength_tesla(-5, 90) * 1e9, 44275, 145 + 443); - EXPECT_NEAR(get_mag_strength_tesla(-5, 95) * 1e9, 44481, 145 + 445); - EXPECT_NEAR(get_mag_strength_tesla(-5, 100) * 1e9, 44410, 145 + 444); - EXPECT_NEAR(get_mag_strength_tesla(-5, 105) * 1e9, 44136, 145 + 441); - EXPECT_NEAR(get_mag_strength_tesla(-5, 110) * 1e9, 43753, 145 + 438); - EXPECT_NEAR(get_mag_strength_tesla(-5, 115) * 1e9, 43346, 145 + 433); - EXPECT_NEAR(get_mag_strength_tesla(-5, 120) * 1e9, 42962, 145 + 430); - EXPECT_NEAR(get_mag_strength_tesla(-5, 125) * 1e9, 42598, 145 + 426); - EXPECT_NEAR(get_mag_strength_tesla(-5, 130) * 1e9, 42216, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(-5, 135) * 1e9, 41777, 145 + 418); - EXPECT_NEAR(get_mag_strength_tesla(-5, 140) * 1e9, 41255, 145 + 413); - EXPECT_NEAR(get_mag_strength_tesla(-5, 145) * 1e9, 40654, 145 + 407); - EXPECT_NEAR(get_mag_strength_tesla(-5, 150) * 1e9, 39994, 145 + 400); - EXPECT_NEAR(get_mag_strength_tesla(-5, 155) * 1e9, 39297, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(-5, 160) * 1e9, 38581, 145 + 386); - EXPECT_NEAR(get_mag_strength_tesla(-5, 165) * 1e9, 37857, 145 + 379); - EXPECT_NEAR(get_mag_strength_tesla(-5, 170) * 1e9, 37133, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(-10, 180) * 1e9, 37892, 145 + 379); + EXPECT_NEAR(get_mag_strength_tesla(-5, -180) * 1e9, 35732, 145 + 357); + EXPECT_NEAR(get_mag_strength_tesla(-5, -175) * 1e9, 35070, 145 + 351); + EXPECT_NEAR(get_mag_strength_tesla(-5, -170) * 1e9, 34435, 145 + 344); + EXPECT_NEAR(get_mag_strength_tesla(-5, -165) * 1e9, 33822, 145 + 338); + EXPECT_NEAR(get_mag_strength_tesla(-5, -160) * 1e9, 33230, 145 + 332); + EXPECT_NEAR(get_mag_strength_tesla(-5, -155) * 1e9, 32660, 145 + 327); + EXPECT_NEAR(get_mag_strength_tesla(-5, -150) * 1e9, 32119, 145 + 321); + EXPECT_NEAR(get_mag_strength_tesla(-5, -145) * 1e9, 31615, 145 + 316); + EXPECT_NEAR(get_mag_strength_tesla(-5, -140) * 1e9, 31150, 145 + 312); + EXPECT_NEAR(get_mag_strength_tesla(-5, -135) * 1e9, 30726, 145 + 307); + EXPECT_NEAR(get_mag_strength_tesla(-5, -130) * 1e9, 30340, 145 + 303); + EXPECT_NEAR(get_mag_strength_tesla(-5, -125) * 1e9, 29990, 145 + 300); + EXPECT_NEAR(get_mag_strength_tesla(-5, -120) * 1e9, 29672, 145 + 297); + EXPECT_NEAR(get_mag_strength_tesla(-5, -115) * 1e9, 29380, 145 + 294); + EXPECT_NEAR(get_mag_strength_tesla(-5, -110) * 1e9, 29098, 145 + 291); + EXPECT_NEAR(get_mag_strength_tesla(-5, -105) * 1e9, 28806, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(-5, -100) * 1e9, 28482, 145 + 285); + EXPECT_NEAR(get_mag_strength_tesla(-5, -95) * 1e9, 28109, 145 + 281); + EXPECT_NEAR(get_mag_strength_tesla(-5, -90) * 1e9, 27682, 145 + 277); + EXPECT_NEAR(get_mag_strength_tesla(-5, -85) * 1e9, 27211, 145 + 272); + EXPECT_NEAR(get_mag_strength_tesla(-5, -80) * 1e9, 26718, 145 + 267); + EXPECT_NEAR(get_mag_strength_tesla(-5, -75) * 1e9, 26236, 145 + 262); + EXPECT_NEAR(get_mag_strength_tesla(-5, -70) * 1e9, 25804, 145 + 258); + EXPECT_NEAR(get_mag_strength_tesla(-5, -65) * 1e9, 25461, 145 + 255); + EXPECT_NEAR(get_mag_strength_tesla(-5, -60) * 1e9, 25244, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-5, -55) * 1e9, 25185, 145 + 252); + EXPECT_NEAR(get_mag_strength_tesla(-5, -50) * 1e9, 25302, 145 + 253); + EXPECT_NEAR(get_mag_strength_tesla(-5, -45) * 1e9, 25596, 145 + 256); + EXPECT_NEAR(get_mag_strength_tesla(-5, -40) * 1e9, 26045, 145 + 260); + EXPECT_NEAR(get_mag_strength_tesla(-5, -35) * 1e9, 26620, 145 + 266); + EXPECT_NEAR(get_mag_strength_tesla(-5, -30) * 1e9, 27287, 145 + 273); + EXPECT_NEAR(get_mag_strength_tesla(-5, -25) * 1e9, 28017, 145 + 280); + EXPECT_NEAR(get_mag_strength_tesla(-5, -20) * 1e9, 28781, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(-5, -15) * 1e9, 29546, 145 + 295); + EXPECT_NEAR(get_mag_strength_tesla(-5, -10) * 1e9, 30274, 145 + 303); + EXPECT_NEAR(get_mag_strength_tesla(-5, -5) * 1e9, 30924, 145 + 309); + EXPECT_NEAR(get_mag_strength_tesla(-5, 0) * 1e9, 31462, 145 + 315); + EXPECT_NEAR(get_mag_strength_tesla(-5, 5) * 1e9, 31865, 145 + 319); + EXPECT_NEAR(get_mag_strength_tesla(-5, 10) * 1e9, 32125, 145 + 321); + EXPECT_NEAR(get_mag_strength_tesla(-5, 15) * 1e9, 32257, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(-5, 20) * 1e9, 32306, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(-5, 25) * 1e9, 32350, 145 + 324); + EXPECT_NEAR(get_mag_strength_tesla(-5, 30) * 1e9, 32492, 145 + 325); + EXPECT_NEAR(get_mag_strength_tesla(-5, 35) * 1e9, 32834, 145 + 328); + EXPECT_NEAR(get_mag_strength_tesla(-5, 40) * 1e9, 33448, 145 + 334); + EXPECT_NEAR(get_mag_strength_tesla(-5, 45) * 1e9, 34348, 145 + 343); + EXPECT_NEAR(get_mag_strength_tesla(-5, 50) * 1e9, 35489, 145 + 355); + EXPECT_NEAR(get_mag_strength_tesla(-5, 55) * 1e9, 36790, 145 + 368); + EXPECT_NEAR(get_mag_strength_tesla(-5, 60) * 1e9, 38162, 145 + 382); + EXPECT_NEAR(get_mag_strength_tesla(-5, 65) * 1e9, 39526, 145 + 395); + EXPECT_NEAR(get_mag_strength_tesla(-5, 70) * 1e9, 40822, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(-5, 75) * 1e9, 42000, 145 + 420); + EXPECT_NEAR(get_mag_strength_tesla(-5, 80) * 1e9, 43007, 145 + 430); + EXPECT_NEAR(get_mag_strength_tesla(-5, 85) * 1e9, 43786, 145 + 438); + EXPECT_NEAR(get_mag_strength_tesla(-5, 90) * 1e9, 44287, 145 + 443); + EXPECT_NEAR(get_mag_strength_tesla(-5, 95) * 1e9, 44489, 145 + 445); + EXPECT_NEAR(get_mag_strength_tesla(-5, 100) * 1e9, 44416, 145 + 444); + EXPECT_NEAR(get_mag_strength_tesla(-5, 105) * 1e9, 44139, 145 + 441); + EXPECT_NEAR(get_mag_strength_tesla(-5, 110) * 1e9, 43755, 145 + 438); + EXPECT_NEAR(get_mag_strength_tesla(-5, 115) * 1e9, 43349, 145 + 433); + EXPECT_NEAR(get_mag_strength_tesla(-5, 120) * 1e9, 42965, 145 + 430); + EXPECT_NEAR(get_mag_strength_tesla(-5, 125) * 1e9, 42600, 145 + 426); + EXPECT_NEAR(get_mag_strength_tesla(-5, 130) * 1e9, 42220, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(-5, 135) * 1e9, 41782, 145 + 418); + EXPECT_NEAR(get_mag_strength_tesla(-5, 140) * 1e9, 41261, 145 + 413); + EXPECT_NEAR(get_mag_strength_tesla(-5, 145) * 1e9, 40661, 145 + 407); + EXPECT_NEAR(get_mag_strength_tesla(-5, 150) * 1e9, 40000, 145 + 400); + EXPECT_NEAR(get_mag_strength_tesla(-5, 155) * 1e9, 39303, 145 + 393); + EXPECT_NEAR(get_mag_strength_tesla(-5, 160) * 1e9, 38586, 145 + 386); + EXPECT_NEAR(get_mag_strength_tesla(-5, 165) * 1e9, 37860, 145 + 379); + EXPECT_NEAR(get_mag_strength_tesla(-5, 170) * 1e9, 37135, 145 + 371); EXPECT_NEAR(get_mag_strength_tesla(-5, 175) * 1e9, 36422, 145 + 364); - EXPECT_NEAR(get_mag_strength_tesla(-5, 180) * 1e9, 35733, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(0, -180) * 1e9, 34117, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(0, -175) * 1e9, 33632, 145 + 336); - EXPECT_NEAR(get_mag_strength_tesla(0, -170) * 1e9, 33175, 145 + 332); - EXPECT_NEAR(get_mag_strength_tesla(0, -165) * 1e9, 32739, 145 + 327); - EXPECT_NEAR(get_mag_strength_tesla(0, -160) * 1e9, 32324, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(0, -155) * 1e9, 31937, 145 + 319); - EXPECT_NEAR(get_mag_strength_tesla(0, -150) * 1e9, 31588, 145 + 316); - EXPECT_NEAR(get_mag_strength_tesla(0, -145) * 1e9, 31286, 145 + 313); - EXPECT_NEAR(get_mag_strength_tesla(0, -140) * 1e9, 31031, 145 + 310); - EXPECT_NEAR(get_mag_strength_tesla(0, -135) * 1e9, 30820, 145 + 308); - EXPECT_NEAR(get_mag_strength_tesla(0, -130) * 1e9, 30645, 145 + 306); - EXPECT_NEAR(get_mag_strength_tesla(0, -125) * 1e9, 30498, 145 + 305); - EXPECT_NEAR(get_mag_strength_tesla(0, -120) * 1e9, 30374, 145 + 304); - EXPECT_NEAR(get_mag_strength_tesla(0, -115) * 1e9, 30267, 145 + 303); - EXPECT_NEAR(get_mag_strength_tesla(0, -110) * 1e9, 30166, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(0, -105) * 1e9, 30053, 145 + 301); - EXPECT_NEAR(get_mag_strength_tesla(0, -100) * 1e9, 29903, 145 + 299); - EXPECT_NEAR(get_mag_strength_tesla(0, -95) * 1e9, 29693, 145 + 297); - EXPECT_NEAR(get_mag_strength_tesla(0, -90) * 1e9, 29407, 145 + 294); - EXPECT_NEAR(get_mag_strength_tesla(0, -85) * 1e9, 29042, 145 + 290); - EXPECT_NEAR(get_mag_strength_tesla(0, -80) * 1e9, 28614, 145 + 286); - EXPECT_NEAR(get_mag_strength_tesla(0, -75) * 1e9, 28147, 145 + 281); - EXPECT_NEAR(get_mag_strength_tesla(0, -70) * 1e9, 27679, 145 + 277); - EXPECT_NEAR(get_mag_strength_tesla(0, -65) * 1e9, 27249, 145 + 272); - EXPECT_NEAR(get_mag_strength_tesla(0, -60) * 1e9, 26903, 145 + 269); - EXPECT_NEAR(get_mag_strength_tesla(0, -55) * 1e9, 26686, 145 + 267); - EXPECT_NEAR(get_mag_strength_tesla(0, -50) * 1e9, 26638, 145 + 266); - EXPECT_NEAR(get_mag_strength_tesla(0, -45) * 1e9, 26778, 145 + 268); - EXPECT_NEAR(get_mag_strength_tesla(0, -40) * 1e9, 27099, 145 + 271); - EXPECT_NEAR(get_mag_strength_tesla(0, -35) * 1e9, 27570, 145 + 276); - EXPECT_NEAR(get_mag_strength_tesla(0, -30) * 1e9, 28149, 145 + 281); - EXPECT_NEAR(get_mag_strength_tesla(0, -25) * 1e9, 28795, 145 + 288); - EXPECT_NEAR(get_mag_strength_tesla(0, -20) * 1e9, 29475, 145 + 295); - EXPECT_NEAR(get_mag_strength_tesla(0, -15) * 1e9, 30158, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(0, -10) * 1e9, 30815, 145 + 308); - EXPECT_NEAR(get_mag_strength_tesla(0, -5) * 1e9, 31420, 145 + 314); + EXPECT_NEAR(get_mag_strength_tesla(-5, 180) * 1e9, 35732, 145 + 357); + EXPECT_NEAR(get_mag_strength_tesla(0, -180) * 1e9, 34116, 145 + 341); + EXPECT_NEAR(get_mag_strength_tesla(0, -175) * 1e9, 33629, 145 + 336); + EXPECT_NEAR(get_mag_strength_tesla(0, -170) * 1e9, 33171, 145 + 332); + EXPECT_NEAR(get_mag_strength_tesla(0, -165) * 1e9, 32734, 145 + 327); + EXPECT_NEAR(get_mag_strength_tesla(0, -160) * 1e9, 32317, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(0, -155) * 1e9, 31929, 145 + 319); + EXPECT_NEAR(get_mag_strength_tesla(0, -150) * 1e9, 31579, 145 + 316); + EXPECT_NEAR(get_mag_strength_tesla(0, -145) * 1e9, 31276, 145 + 313); + EXPECT_NEAR(get_mag_strength_tesla(0, -140) * 1e9, 31021, 145 + 310); + EXPECT_NEAR(get_mag_strength_tesla(0, -135) * 1e9, 30810, 145 + 308); + EXPECT_NEAR(get_mag_strength_tesla(0, -130) * 1e9, 30634, 145 + 306); + EXPECT_NEAR(get_mag_strength_tesla(0, -125) * 1e9, 30486, 145 + 305); + EXPECT_NEAR(get_mag_strength_tesla(0, -120) * 1e9, 30361, 145 + 304); + EXPECT_NEAR(get_mag_strength_tesla(0, -115) * 1e9, 30252, 145 + 303); + EXPECT_NEAR(get_mag_strength_tesla(0, -110) * 1e9, 30148, 145 + 301); + EXPECT_NEAR(get_mag_strength_tesla(0, -105) * 1e9, 30032, 145 + 300); + EXPECT_NEAR(get_mag_strength_tesla(0, -100) * 1e9, 29880, 145 + 299); + EXPECT_NEAR(get_mag_strength_tesla(0, -95) * 1e9, 29667, 145 + 297); + EXPECT_NEAR(get_mag_strength_tesla(0, -90) * 1e9, 29380, 145 + 294); + EXPECT_NEAR(get_mag_strength_tesla(0, -85) * 1e9, 29014, 145 + 290); + EXPECT_NEAR(get_mag_strength_tesla(0, -80) * 1e9, 28585, 145 + 286); + EXPECT_NEAR(get_mag_strength_tesla(0, -75) * 1e9, 28120, 145 + 281); + EXPECT_NEAR(get_mag_strength_tesla(0, -70) * 1e9, 27653, 145 + 277); + EXPECT_NEAR(get_mag_strength_tesla(0, -65) * 1e9, 27227, 145 + 272); + EXPECT_NEAR(get_mag_strength_tesla(0, -60) * 1e9, 26885, 145 + 269); + EXPECT_NEAR(get_mag_strength_tesla(0, -55) * 1e9, 26673, 145 + 267); + EXPECT_NEAR(get_mag_strength_tesla(0, -50) * 1e9, 26631, 145 + 266); + EXPECT_NEAR(get_mag_strength_tesla(0, -45) * 1e9, 26777, 145 + 268); + EXPECT_NEAR(get_mag_strength_tesla(0, -40) * 1e9, 27103, 145 + 271); + EXPECT_NEAR(get_mag_strength_tesla(0, -35) * 1e9, 27577, 145 + 276); + EXPECT_NEAR(get_mag_strength_tesla(0, -30) * 1e9, 28158, 145 + 282); + EXPECT_NEAR(get_mag_strength_tesla(0, -25) * 1e9, 28805, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(0, -20) * 1e9, 29484, 145 + 295); + EXPECT_NEAR(get_mag_strength_tesla(0, -15) * 1e9, 30166, 145 + 302); + EXPECT_NEAR(get_mag_strength_tesla(0, -10) * 1e9, 30821, 145 + 308); + EXPECT_NEAR(get_mag_strength_tesla(0, -5) * 1e9, 31424, 145 + 314); EXPECT_NEAR(get_mag_strength_tesla(0, 0) * 1e9, 31945, 145 + 319); - EXPECT_NEAR(get_mag_strength_tesla(0, 5) * 1e9, 32367, 145 + 324); - EXPECT_NEAR(get_mag_strength_tesla(0, 10) * 1e9, 32672, 145 + 327); - EXPECT_NEAR(get_mag_strength_tesla(0, 15) * 1e9, 32863, 145 + 329); - EXPECT_NEAR(get_mag_strength_tesla(0, 20) * 1e9, 32970, 145 + 330); - EXPECT_NEAR(get_mag_strength_tesla(0, 25) * 1e9, 33054, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(0, 30) * 1e9, 33199, 145 + 332); - EXPECT_NEAR(get_mag_strength_tesla(0, 35) * 1e9, 33490, 145 + 335); - EXPECT_NEAR(get_mag_strength_tesla(0, 40) * 1e9, 33986, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(0, 45) * 1e9, 34701, 145 + 347); - EXPECT_NEAR(get_mag_strength_tesla(0, 50) * 1e9, 35602, 145 + 356); - EXPECT_NEAR(get_mag_strength_tesla(0, 55) * 1e9, 36631, 145 + 366); - EXPECT_NEAR(get_mag_strength_tesla(0, 60) * 1e9, 37720, 145 + 377); - EXPECT_NEAR(get_mag_strength_tesla(0, 65) * 1e9, 38814, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(0, 70) * 1e9, 39863, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(0, 75) * 1e9, 40824, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(0, 80) * 1e9, 41649, 145 + 416); - EXPECT_NEAR(get_mag_strength_tesla(0, 85) * 1e9, 42283, 145 + 423); - EXPECT_NEAR(get_mag_strength_tesla(0, 90) * 1e9, 42681, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(0, 95) * 1e9, 42820, 145 + 428); - EXPECT_NEAR(get_mag_strength_tesla(0, 100) * 1e9, 42718, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(0, 105) * 1e9, 42429, 145 + 424); - EXPECT_NEAR(get_mag_strength_tesla(0, 110) * 1e9, 42031, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(0, 115) * 1e9, 41591, 145 + 416); - EXPECT_NEAR(get_mag_strength_tesla(0, 120) * 1e9, 41147, 145 + 411); - EXPECT_NEAR(get_mag_strength_tesla(0, 125) * 1e9, 40700, 145 + 407); - EXPECT_NEAR(get_mag_strength_tesla(0, 130) * 1e9, 40229, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(0, 135) * 1e9, 39706, 145 + 397); - EXPECT_NEAR(get_mag_strength_tesla(0, 140) * 1e9, 39119, 145 + 391); - EXPECT_NEAR(get_mag_strength_tesla(0, 145) * 1e9, 38478, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(0, 150) * 1e9, 37805, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(0, 155) * 1e9, 37125, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(0, 160) * 1e9, 36458, 145 + 365); - EXPECT_NEAR(get_mag_strength_tesla(0, 165) * 1e9, 35815, 145 + 358); - EXPECT_NEAR(get_mag_strength_tesla(0, 170) * 1e9, 35207, 145 + 352); - EXPECT_NEAR(get_mag_strength_tesla(0, 175) * 1e9, 34640, 145 + 346); - EXPECT_NEAR(get_mag_strength_tesla(0, 180) * 1e9, 34117, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(5, -180) * 1e9, 33141, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(5, -175) * 1e9, 32822, 145 + 328); - EXPECT_NEAR(get_mag_strength_tesla(5, -170) * 1e9, 32534, 145 + 325); - EXPECT_NEAR(get_mag_strength_tesla(5, -165) * 1e9, 32266, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(5, -160) * 1e9, 32019, 145 + 320); - EXPECT_NEAR(get_mag_strength_tesla(5, -155) * 1e9, 31806, 145 + 318); - EXPECT_NEAR(get_mag_strength_tesla(5, -150) * 1e9, 31642, 145 + 316); - EXPECT_NEAR(get_mag_strength_tesla(5, -145) * 1e9, 31537, 145 + 315); - EXPECT_NEAR(get_mag_strength_tesla(5, -140) * 1e9, 31492, 145 + 315); - EXPECT_NEAR(get_mag_strength_tesla(5, -135) * 1e9, 31497, 145 + 315); - EXPECT_NEAR(get_mag_strength_tesla(5, -130) * 1e9, 31537, 145 + 315); - EXPECT_NEAR(get_mag_strength_tesla(5, -125) * 1e9, 31599, 145 + 316); - EXPECT_NEAR(get_mag_strength_tesla(5, -120) * 1e9, 31673, 145 + 317); - EXPECT_NEAR(get_mag_strength_tesla(5, -115) * 1e9, 31753, 145 + 318); - EXPECT_NEAR(get_mag_strength_tesla(5, -110) * 1e9, 31828, 145 + 318); - EXPECT_NEAR(get_mag_strength_tesla(5, -105) * 1e9, 31879, 145 + 319); - EXPECT_NEAR(get_mag_strength_tesla(5, -100) * 1e9, 31877, 145 + 319); - EXPECT_NEAR(get_mag_strength_tesla(5, -95) * 1e9, 31794, 145 + 318); - EXPECT_NEAR(get_mag_strength_tesla(5, -90) * 1e9, 31605, 145 + 316); - EXPECT_NEAR(get_mag_strength_tesla(5, -85) * 1e9, 31302, 145 + 313); - EXPECT_NEAR(get_mag_strength_tesla(5, -80) * 1e9, 30895, 145 + 309); - EXPECT_NEAR(get_mag_strength_tesla(5, -75) * 1e9, 30409, 145 + 304); - EXPECT_NEAR(get_mag_strength_tesla(5, -70) * 1e9, 29880, 145 + 299); - EXPECT_NEAR(get_mag_strength_tesla(5, -65) * 1e9, 29350, 145 + 294); - EXPECT_NEAR(get_mag_strength_tesla(5, -60) * 1e9, 28870, 145 + 289); - EXPECT_NEAR(get_mag_strength_tesla(5, -55) * 1e9, 28492, 145 + 285); - EXPECT_NEAR(get_mag_strength_tesla(5, -50) * 1e9, 28270, 145 + 283); - EXPECT_NEAR(get_mag_strength_tesla(5, -45) * 1e9, 28235, 145 + 282); - EXPECT_NEAR(get_mag_strength_tesla(5, -40) * 1e9, 28391, 145 + 284); - EXPECT_NEAR(get_mag_strength_tesla(5, -35) * 1e9, 28711, 145 + 287); - EXPECT_NEAR(get_mag_strength_tesla(5, -30) * 1e9, 29154, 145 + 292); - EXPECT_NEAR(get_mag_strength_tesla(5, -25) * 1e9, 29676, 145 + 297); - EXPECT_NEAR(get_mag_strength_tesla(5, -20) * 1e9, 30240, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(5, -15) * 1e9, 30820, 145 + 308); - EXPECT_NEAR(get_mag_strength_tesla(5, -10) * 1e9, 31395, 145 + 314); - EXPECT_NEAR(get_mag_strength_tesla(5, -5) * 1e9, 31944, 145 + 319); - EXPECT_NEAR(get_mag_strength_tesla(5, 0) * 1e9, 32446, 145 + 324); - EXPECT_NEAR(get_mag_strength_tesla(5, 5) * 1e9, 32878, 145 + 329); - EXPECT_NEAR(get_mag_strength_tesla(5, 10) * 1e9, 33226, 145 + 332); - EXPECT_NEAR(get_mag_strength_tesla(5, 15) * 1e9, 33487, 145 + 335); - EXPECT_NEAR(get_mag_strength_tesla(5, 20) * 1e9, 33684, 145 + 337); - EXPECT_NEAR(get_mag_strength_tesla(5, 25) * 1e9, 33862, 145 + 339); - EXPECT_NEAR(get_mag_strength_tesla(5, 30) * 1e9, 34084, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(5, 35) * 1e9, 34412, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(5, 40) * 1e9, 34881, 145 + 349); - EXPECT_NEAR(get_mag_strength_tesla(5, 45) * 1e9, 35495, 145 + 355); - EXPECT_NEAR(get_mag_strength_tesla(5, 50) * 1e9, 36232, 145 + 362); - EXPECT_NEAR(get_mag_strength_tesla(5, 55) * 1e9, 37052, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(5, 60) * 1e9, 37916, 145 + 379); - EXPECT_NEAR(get_mag_strength_tesla(5, 65) * 1e9, 38787, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(5, 70) * 1e9, 39629, 145 + 396); - EXPECT_NEAR(get_mag_strength_tesla(5, 75) * 1e9, 40405, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(5, 80) * 1e9, 41072, 145 + 411); - EXPECT_NEAR(get_mag_strength_tesla(5, 85) * 1e9, 41583, 145 + 416); - EXPECT_NEAR(get_mag_strength_tesla(5, 90) * 1e9, 41899, 145 + 419); - EXPECT_NEAR(get_mag_strength_tesla(5, 95) * 1e9, 42002, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(5, 100) * 1e9, 41899, 145 + 419); - EXPECT_NEAR(get_mag_strength_tesla(5, 105) * 1e9, 41627, 145 + 416); - EXPECT_NEAR(get_mag_strength_tesla(5, 110) * 1e9, 41235, 145 + 412); - EXPECT_NEAR(get_mag_strength_tesla(5, 115) * 1e9, 40767, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(5, 120) * 1e9, 40251, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(5, 125) * 1e9, 39696, 145 + 397); - EXPECT_NEAR(get_mag_strength_tesla(5, 130) * 1e9, 39099, 145 + 391); - EXPECT_NEAR(get_mag_strength_tesla(5, 135) * 1e9, 38454, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(5, 140) * 1e9, 37768, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(5, 145) * 1e9, 37057, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(5, 150) * 1e9, 36346, 145 + 363); - EXPECT_NEAR(get_mag_strength_tesla(5, 155) * 1e9, 35661, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(5, 160) * 1e9, 35022, 145 + 350); - EXPECT_NEAR(get_mag_strength_tesla(5, 165) * 1e9, 34446, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(5, 170) * 1e9, 33940, 145 + 339); - EXPECT_NEAR(get_mag_strength_tesla(5, 175) * 1e9, 33508, 145 + 335); - EXPECT_NEAR(get_mag_strength_tesla(5, 180) * 1e9, 33141, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(10, -180) * 1e9, 32823, 145 + 328); - EXPECT_NEAR(get_mag_strength_tesla(10, -175) * 1e9, 32644, 145 + 326); - EXPECT_NEAR(get_mag_strength_tesla(10, -170) * 1e9, 32502, 145 + 325); - EXPECT_NEAR(get_mag_strength_tesla(10, -165) * 1e9, 32382, 145 + 324); - EXPECT_NEAR(get_mag_strength_tesla(10, -160) * 1e9, 32287, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(10, -155) * 1e9, 32233, 145 + 322); - EXPECT_NEAR(get_mag_strength_tesla(10, -150) * 1e9, 32240, 145 + 322); - EXPECT_NEAR(get_mag_strength_tesla(10, -145) * 1e9, 32322, 145 + 323); - EXPECT_NEAR(get_mag_strength_tesla(10, -140) * 1e9, 32476, 145 + 325); - EXPECT_NEAR(get_mag_strength_tesla(10, -135) * 1e9, 32690, 145 + 327); - EXPECT_NEAR(get_mag_strength_tesla(10, -130) * 1e9, 32941, 145 + 329); - EXPECT_NEAR(get_mag_strength_tesla(10, -125) * 1e9, 33210, 145 + 332); - EXPECT_NEAR(get_mag_strength_tesla(10, -120) * 1e9, 33482, 145 + 335); - EXPECT_NEAR(get_mag_strength_tesla(10, -115) * 1e9, 33748, 145 + 337); - EXPECT_NEAR(get_mag_strength_tesla(10, -110) * 1e9, 33993, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(10, -105) * 1e9, 34195, 145 + 342); - EXPECT_NEAR(get_mag_strength_tesla(10, -100) * 1e9, 34321, 145 + 343); - EXPECT_NEAR(get_mag_strength_tesla(10, -95) * 1e9, 34336, 145 + 343); - EXPECT_NEAR(get_mag_strength_tesla(10, -90) * 1e9, 34210, 145 + 342); - EXPECT_NEAR(get_mag_strength_tesla(10, -85) * 1e9, 33934, 145 + 339); - EXPECT_NEAR(get_mag_strength_tesla(10, -80) * 1e9, 33516, 145 + 335); - EXPECT_NEAR(get_mag_strength_tesla(10, -75) * 1e9, 32985, 145 + 330); - EXPECT_NEAR(get_mag_strength_tesla(10, -70) * 1e9, 32377, 145 + 324); - EXPECT_NEAR(get_mag_strength_tesla(10, -65) * 1e9, 31741, 145 + 317); - EXPECT_NEAR(get_mag_strength_tesla(10, -60) * 1e9, 31130, 145 + 311); - EXPECT_NEAR(get_mag_strength_tesla(10, -55) * 1e9, 30604, 145 + 306); - EXPECT_NEAR(get_mag_strength_tesla(10, -50) * 1e9, 30220, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(10, -45) * 1e9, 30016, 145 + 300); - EXPECT_NEAR(get_mag_strength_tesla(10, -40) * 1e9, 30001, 145 + 300); + EXPECT_NEAR(get_mag_strength_tesla(0, 5) * 1e9, 32364, 145 + 324); + EXPECT_NEAR(get_mag_strength_tesla(0, 10) * 1e9, 32667, 145 + 327); + EXPECT_NEAR(get_mag_strength_tesla(0, 15) * 1e9, 32856, 145 + 329); + EXPECT_NEAR(get_mag_strength_tesla(0, 20) * 1e9, 32962, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(0, 25) * 1e9, 33046, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(0, 30) * 1e9, 33193, 145 + 332); + EXPECT_NEAR(get_mag_strength_tesla(0, 35) * 1e9, 33488, 145 + 335); + EXPECT_NEAR(get_mag_strength_tesla(0, 40) * 1e9, 33990, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(0, 45) * 1e9, 34710, 145 + 347); + EXPECT_NEAR(get_mag_strength_tesla(0, 50) * 1e9, 35616, 145 + 356); + EXPECT_NEAR(get_mag_strength_tesla(0, 55) * 1e9, 36649, 145 + 366); + EXPECT_NEAR(get_mag_strength_tesla(0, 60) * 1e9, 37741, 145 + 377); + EXPECT_NEAR(get_mag_strength_tesla(0, 65) * 1e9, 38836, 145 + 388); + EXPECT_NEAR(get_mag_strength_tesla(0, 70) * 1e9, 39886, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(0, 75) * 1e9, 40846, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(0, 80) * 1e9, 41668, 145 + 417); + EXPECT_NEAR(get_mag_strength_tesla(0, 85) * 1e9, 42300, 145 + 423); + EXPECT_NEAR(get_mag_strength_tesla(0, 90) * 1e9, 42694, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(0, 95) * 1e9, 42830, 145 + 428); + EXPECT_NEAR(get_mag_strength_tesla(0, 100) * 1e9, 42725, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(0, 105) * 1e9, 42435, 145 + 424); + EXPECT_NEAR(get_mag_strength_tesla(0, 110) * 1e9, 42036, 145 + 420); + EXPECT_NEAR(get_mag_strength_tesla(0, 115) * 1e9, 41595, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(0, 120) * 1e9, 41151, 145 + 412); + EXPECT_NEAR(get_mag_strength_tesla(0, 125) * 1e9, 40705, 145 + 407); + EXPECT_NEAR(get_mag_strength_tesla(0, 130) * 1e9, 40234, 145 + 402); + EXPECT_NEAR(get_mag_strength_tesla(0, 135) * 1e9, 39712, 145 + 397); + EXPECT_NEAR(get_mag_strength_tesla(0, 140) * 1e9, 39126, 145 + 391); + EXPECT_NEAR(get_mag_strength_tesla(0, 145) * 1e9, 38485, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(0, 150) * 1e9, 37812, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(0, 155) * 1e9, 37131, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(0, 160) * 1e9, 36462, 145 + 365); + EXPECT_NEAR(get_mag_strength_tesla(0, 165) * 1e9, 35819, 145 + 358); + EXPECT_NEAR(get_mag_strength_tesla(0, 170) * 1e9, 35209, 145 + 352); + EXPECT_NEAR(get_mag_strength_tesla(0, 175) * 1e9, 34641, 145 + 346); + EXPECT_NEAR(get_mag_strength_tesla(0, 180) * 1e9, 34116, 145 + 341); + EXPECT_NEAR(get_mag_strength_tesla(5, -180) * 1e9, 33140, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(5, -175) * 1e9, 32820, 145 + 328); + EXPECT_NEAR(get_mag_strength_tesla(5, -170) * 1e9, 32531, 145 + 325); + EXPECT_NEAR(get_mag_strength_tesla(5, -165) * 1e9, 32261, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(5, -160) * 1e9, 32013, 145 + 320); + EXPECT_NEAR(get_mag_strength_tesla(5, -155) * 1e9, 31798, 145 + 318); + EXPECT_NEAR(get_mag_strength_tesla(5, -150) * 1e9, 31633, 145 + 316); + EXPECT_NEAR(get_mag_strength_tesla(5, -145) * 1e9, 31528, 145 + 315); + EXPECT_NEAR(get_mag_strength_tesla(5, -140) * 1e9, 31482, 145 + 315); + EXPECT_NEAR(get_mag_strength_tesla(5, -135) * 1e9, 31487, 145 + 315); + EXPECT_NEAR(get_mag_strength_tesla(5, -130) * 1e9, 31526, 145 + 315); + EXPECT_NEAR(get_mag_strength_tesla(5, -125) * 1e9, 31586, 145 + 316); + EXPECT_NEAR(get_mag_strength_tesla(5, -120) * 1e9, 31658, 145 + 317); + EXPECT_NEAR(get_mag_strength_tesla(5, -115) * 1e9, 31736, 145 + 317); + EXPECT_NEAR(get_mag_strength_tesla(5, -110) * 1e9, 31808, 145 + 318); + EXPECT_NEAR(get_mag_strength_tesla(5, -105) * 1e9, 31856, 145 + 319); + EXPECT_NEAR(get_mag_strength_tesla(5, -100) * 1e9, 31852, 145 + 319); + EXPECT_NEAR(get_mag_strength_tesla(5, -95) * 1e9, 31767, 145 + 318); + EXPECT_NEAR(get_mag_strength_tesla(5, -90) * 1e9, 31576, 145 + 316); + EXPECT_NEAR(get_mag_strength_tesla(5, -85) * 1e9, 31272, 145 + 313); + EXPECT_NEAR(get_mag_strength_tesla(5, -80) * 1e9, 30865, 145 + 309); + EXPECT_NEAR(get_mag_strength_tesla(5, -75) * 1e9, 30380, 145 + 304); + EXPECT_NEAR(get_mag_strength_tesla(5, -70) * 1e9, 29852, 145 + 299); + EXPECT_NEAR(get_mag_strength_tesla(5, -65) * 1e9, 29325, 145 + 293); + EXPECT_NEAR(get_mag_strength_tesla(5, -60) * 1e9, 28847, 145 + 288); + EXPECT_NEAR(get_mag_strength_tesla(5, -55) * 1e9, 28475, 145 + 285); + EXPECT_NEAR(get_mag_strength_tesla(5, -50) * 1e9, 28258, 145 + 283); + EXPECT_NEAR(get_mag_strength_tesla(5, -45) * 1e9, 28229, 145 + 282); + EXPECT_NEAR(get_mag_strength_tesla(5, -40) * 1e9, 28390, 145 + 284); + EXPECT_NEAR(get_mag_strength_tesla(5, -35) * 1e9, 28715, 145 + 287); + EXPECT_NEAR(get_mag_strength_tesla(5, -30) * 1e9, 29161, 145 + 292); + EXPECT_NEAR(get_mag_strength_tesla(5, -25) * 1e9, 29683, 145 + 297); + EXPECT_NEAR(get_mag_strength_tesla(5, -20) * 1e9, 30247, 145 + 302); + EXPECT_NEAR(get_mag_strength_tesla(5, -15) * 1e9, 30827, 145 + 308); + EXPECT_NEAR(get_mag_strength_tesla(5, -10) * 1e9, 31401, 145 + 314); + EXPECT_NEAR(get_mag_strength_tesla(5, -5) * 1e9, 31949, 145 + 319); + EXPECT_NEAR(get_mag_strength_tesla(5, 0) * 1e9, 32449, 145 + 324); + EXPECT_NEAR(get_mag_strength_tesla(5, 5) * 1e9, 32879, 145 + 329); + EXPECT_NEAR(get_mag_strength_tesla(5, 10) * 1e9, 33225, 145 + 332); + EXPECT_NEAR(get_mag_strength_tesla(5, 15) * 1e9, 33485, 145 + 335); + EXPECT_NEAR(get_mag_strength_tesla(5, 20) * 1e9, 33681, 145 + 337); + EXPECT_NEAR(get_mag_strength_tesla(5, 25) * 1e9, 33859, 145 + 339); + EXPECT_NEAR(get_mag_strength_tesla(5, 30) * 1e9, 34083, 145 + 341); + EXPECT_NEAR(get_mag_strength_tesla(5, 35) * 1e9, 34414, 145 + 344); + EXPECT_NEAR(get_mag_strength_tesla(5, 40) * 1e9, 34886, 145 + 349); + EXPECT_NEAR(get_mag_strength_tesla(5, 45) * 1e9, 35505, 145 + 355); + EXPECT_NEAR(get_mag_strength_tesla(5, 50) * 1e9, 36246, 145 + 362); + EXPECT_NEAR(get_mag_strength_tesla(5, 55) * 1e9, 37069, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(5, 60) * 1e9, 37936, 145 + 379); + EXPECT_NEAR(get_mag_strength_tesla(5, 65) * 1e9, 38808, 145 + 388); + EXPECT_NEAR(get_mag_strength_tesla(5, 70) * 1e9, 39652, 145 + 397); + EXPECT_NEAR(get_mag_strength_tesla(5, 75) * 1e9, 40428, 145 + 404); + EXPECT_NEAR(get_mag_strength_tesla(5, 80) * 1e9, 41093, 145 + 411); + EXPECT_NEAR(get_mag_strength_tesla(5, 85) * 1e9, 41602, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(5, 90) * 1e9, 41915, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(5, 95) * 1e9, 42015, 145 + 420); + EXPECT_NEAR(get_mag_strength_tesla(5, 100) * 1e9, 41910, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(5, 105) * 1e9, 41636, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(5, 110) * 1e9, 41243, 145 + 412); + EXPECT_NEAR(get_mag_strength_tesla(5, 115) * 1e9, 40774, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(5, 120) * 1e9, 40257, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(5, 125) * 1e9, 39702, 145 + 397); + EXPECT_NEAR(get_mag_strength_tesla(5, 130) * 1e9, 39105, 145 + 391); + EXPECT_NEAR(get_mag_strength_tesla(5, 135) * 1e9, 38460, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(5, 140) * 1e9, 37774, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(5, 145) * 1e9, 37063, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(5, 150) * 1e9, 36352, 145 + 364); + EXPECT_NEAR(get_mag_strength_tesla(5, 155) * 1e9, 35666, 145 + 357); + EXPECT_NEAR(get_mag_strength_tesla(5, 160) * 1e9, 35027, 145 + 350); + EXPECT_NEAR(get_mag_strength_tesla(5, 165) * 1e9, 34449, 145 + 344); + EXPECT_NEAR(get_mag_strength_tesla(5, 170) * 1e9, 33943, 145 + 339); + EXPECT_NEAR(get_mag_strength_tesla(5, 175) * 1e9, 33509, 145 + 335); + EXPECT_NEAR(get_mag_strength_tesla(5, 180) * 1e9, 33140, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(10, -180) * 1e9, 32822, 145 + 328); + EXPECT_NEAR(get_mag_strength_tesla(10, -175) * 1e9, 32642, 145 + 326); + EXPECT_NEAR(get_mag_strength_tesla(10, -170) * 1e9, 32498, 145 + 325); + EXPECT_NEAR(get_mag_strength_tesla(10, -165) * 1e9, 32377, 145 + 324); + EXPECT_NEAR(get_mag_strength_tesla(10, -160) * 1e9, 32280, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(10, -155) * 1e9, 32225, 145 + 322); + EXPECT_NEAR(get_mag_strength_tesla(10, -150) * 1e9, 32231, 145 + 322); + EXPECT_NEAR(get_mag_strength_tesla(10, -145) * 1e9, 32312, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(10, -140) * 1e9, 32466, 145 + 325); + EXPECT_NEAR(get_mag_strength_tesla(10, -135) * 1e9, 32678, 145 + 327); + EXPECT_NEAR(get_mag_strength_tesla(10, -130) * 1e9, 32928, 145 + 329); + EXPECT_NEAR(get_mag_strength_tesla(10, -125) * 1e9, 33195, 145 + 332); + EXPECT_NEAR(get_mag_strength_tesla(10, -120) * 1e9, 33466, 145 + 335); + EXPECT_NEAR(get_mag_strength_tesla(10, -115) * 1e9, 33729, 145 + 337); + EXPECT_NEAR(get_mag_strength_tesla(10, -110) * 1e9, 33971, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(10, -105) * 1e9, 34170, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(10, -100) * 1e9, 34294, 145 + 343); + EXPECT_NEAR(get_mag_strength_tesla(10, -95) * 1e9, 34306, 145 + 343); + EXPECT_NEAR(get_mag_strength_tesla(10, -90) * 1e9, 34179, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(10, -85) * 1e9, 33902, 145 + 339); + EXPECT_NEAR(get_mag_strength_tesla(10, -80) * 1e9, 33485, 145 + 335); + EXPECT_NEAR(get_mag_strength_tesla(10, -75) * 1e9, 32953, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(10, -70) * 1e9, 32346, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(10, -65) * 1e9, 31712, 145 + 317); + EXPECT_NEAR(get_mag_strength_tesla(10, -60) * 1e9, 31104, 145 + 311); + EXPECT_NEAR(get_mag_strength_tesla(10, -55) * 1e9, 30583, 145 + 306); + EXPECT_NEAR(get_mag_strength_tesla(10, -50) * 1e9, 30204, 145 + 302); + EXPECT_NEAR(get_mag_strength_tesla(10, -45) * 1e9, 30006, 145 + 300); + EXPECT_NEAR(get_mag_strength_tesla(10, -40) * 1e9, 29996, 145 + 300); EXPECT_NEAR(get_mag_strength_tesla(10, -35) * 1e9, 30155, 145 + 302); - EXPECT_NEAR(get_mag_strength_tesla(10, -30) * 1e9, 30442, 145 + 304); - EXPECT_NEAR(get_mag_strength_tesla(10, -25) * 1e9, 30822, 145 + 308); - EXPECT_NEAR(get_mag_strength_tesla(10, -20) * 1e9, 31264, 145 + 313); - EXPECT_NEAR(get_mag_strength_tesla(10, -15) * 1e9, 31746, 145 + 317); - EXPECT_NEAR(get_mag_strength_tesla(10, -10) * 1e9, 32250, 145 + 322); - EXPECT_NEAR(get_mag_strength_tesla(10, -5) * 1e9, 32759, 145 + 328); - EXPECT_NEAR(get_mag_strength_tesla(10, 0) * 1e9, 33249, 145 + 332); - EXPECT_NEAR(get_mag_strength_tesla(10, 5) * 1e9, 33699, 145 + 337); - EXPECT_NEAR(get_mag_strength_tesla(10, 10) * 1e9, 34092, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(10, 15) * 1e9, 34428, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(10, 20) * 1e9, 34726, 145 + 347); - EXPECT_NEAR(get_mag_strength_tesla(10, 25) * 1e9, 35021, 145 + 350); - EXPECT_NEAR(get_mag_strength_tesla(10, 30) * 1e9, 35356, 145 + 354); - EXPECT_NEAR(get_mag_strength_tesla(10, 35) * 1e9, 35764, 145 + 358); - EXPECT_NEAR(get_mag_strength_tesla(10, 40) * 1e9, 36258, 145 + 363); - EXPECT_NEAR(get_mag_strength_tesla(10, 45) * 1e9, 36830, 145 + 368); - EXPECT_NEAR(get_mag_strength_tesla(10, 50) * 1e9, 37463, 145 + 375); - EXPECT_NEAR(get_mag_strength_tesla(10, 55) * 1e9, 38138, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(10, 60) * 1e9, 38838, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(10, 65) * 1e9, 39546, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(10, 70) * 1e9, 40237, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(10, 75) * 1e9, 40878, 145 + 409); - EXPECT_NEAR(get_mag_strength_tesla(10, 80) * 1e9, 41431, 145 + 414); - EXPECT_NEAR(get_mag_strength_tesla(10, 85) * 1e9, 41855, 145 + 419); - EXPECT_NEAR(get_mag_strength_tesla(10, 90) * 1e9, 42120, 145 + 421); - EXPECT_NEAR(get_mag_strength_tesla(10, 95) * 1e9, 42208, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(10, 100) * 1e9, 42122, 145 + 421); - EXPECT_NEAR(get_mag_strength_tesla(10, 105) * 1e9, 41875, 145 + 419); - EXPECT_NEAR(get_mag_strength_tesla(10, 110) * 1e9, 41490, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(10, 115) * 1e9, 40987, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(10, 120) * 1e9, 40384, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(10, 125) * 1e9, 39698, 145 + 397); - EXPECT_NEAR(get_mag_strength_tesla(10, 130) * 1e9, 38946, 145 + 389); - EXPECT_NEAR(get_mag_strength_tesla(10, 135) * 1e9, 38147, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(10, 140) * 1e9, 37326, 145 + 373); - EXPECT_NEAR(get_mag_strength_tesla(10, 145) * 1e9, 36511, 145 + 365); - EXPECT_NEAR(get_mag_strength_tesla(10, 150) * 1e9, 35730, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(10, 155) * 1e9, 35008, 145 + 350); - EXPECT_NEAR(get_mag_strength_tesla(10, 160) * 1e9, 34369, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(10, 165) * 1e9, 33827, 145 + 338); - EXPECT_NEAR(get_mag_strength_tesla(10, 170) * 1e9, 33393, 145 + 334); + EXPECT_NEAR(get_mag_strength_tesla(10, -30) * 1e9, 30445, 145 + 304); + EXPECT_NEAR(get_mag_strength_tesla(10, -25) * 1e9, 30827, 145 + 308); + EXPECT_NEAR(get_mag_strength_tesla(10, -20) * 1e9, 31269, 145 + 313); + EXPECT_NEAR(get_mag_strength_tesla(10, -15) * 1e9, 31752, 145 + 318); + EXPECT_NEAR(get_mag_strength_tesla(10, -10) * 1e9, 32256, 145 + 323); + EXPECT_NEAR(get_mag_strength_tesla(10, -5) * 1e9, 32764, 145 + 328); + EXPECT_NEAR(get_mag_strength_tesla(10, 0) * 1e9, 33254, 145 + 333); + EXPECT_NEAR(get_mag_strength_tesla(10, 5) * 1e9, 33703, 145 + 337); + EXPECT_NEAR(get_mag_strength_tesla(10, 10) * 1e9, 34096, 145 + 341); + EXPECT_NEAR(get_mag_strength_tesla(10, 15) * 1e9, 34431, 145 + 344); + EXPECT_NEAR(get_mag_strength_tesla(10, 20) * 1e9, 34728, 145 + 347); + EXPECT_NEAR(get_mag_strength_tesla(10, 25) * 1e9, 35023, 145 + 350); + EXPECT_NEAR(get_mag_strength_tesla(10, 30) * 1e9, 35360, 145 + 354); + EXPECT_NEAR(get_mag_strength_tesla(10, 35) * 1e9, 35770, 145 + 358); + EXPECT_NEAR(get_mag_strength_tesla(10, 40) * 1e9, 36267, 145 + 363); + EXPECT_NEAR(get_mag_strength_tesla(10, 45) * 1e9, 36842, 145 + 368); + EXPECT_NEAR(get_mag_strength_tesla(10, 50) * 1e9, 37478, 145 + 375); + EXPECT_NEAR(get_mag_strength_tesla(10, 55) * 1e9, 38156, 145 + 382); + EXPECT_NEAR(get_mag_strength_tesla(10, 60) * 1e9, 38858, 145 + 389); + EXPECT_NEAR(get_mag_strength_tesla(10, 65) * 1e9, 39568, 145 + 396); + EXPECT_NEAR(get_mag_strength_tesla(10, 70) * 1e9, 40260, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(10, 75) * 1e9, 40903, 145 + 409); + EXPECT_NEAR(get_mag_strength_tesla(10, 80) * 1e9, 41455, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(10, 85) * 1e9, 41877, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(10, 90) * 1e9, 42139, 145 + 421); + EXPECT_NEAR(get_mag_strength_tesla(10, 95) * 1e9, 42225, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(10, 100) * 1e9, 42136, 145 + 421); + EXPECT_NEAR(get_mag_strength_tesla(10, 105) * 1e9, 41888, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(10, 110) * 1e9, 41501, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(10, 115) * 1e9, 40997, 145 + 410); + EXPECT_NEAR(get_mag_strength_tesla(10, 120) * 1e9, 40393, 145 + 404); + EXPECT_NEAR(get_mag_strength_tesla(10, 125) * 1e9, 39706, 145 + 397); + EXPECT_NEAR(get_mag_strength_tesla(10, 130) * 1e9, 38953, 145 + 390); + EXPECT_NEAR(get_mag_strength_tesla(10, 135) * 1e9, 38154, 145 + 382); + EXPECT_NEAR(get_mag_strength_tesla(10, 140) * 1e9, 37333, 145 + 373); + EXPECT_NEAR(get_mag_strength_tesla(10, 145) * 1e9, 36518, 145 + 365); + EXPECT_NEAR(get_mag_strength_tesla(10, 150) * 1e9, 35736, 145 + 357); + EXPECT_NEAR(get_mag_strength_tesla(10, 155) * 1e9, 35014, 145 + 350); + EXPECT_NEAR(get_mag_strength_tesla(10, 160) * 1e9, 34373, 145 + 344); + EXPECT_NEAR(get_mag_strength_tesla(10, 165) * 1e9, 33830, 145 + 338); + EXPECT_NEAR(get_mag_strength_tesla(10, 170) * 1e9, 33395, 145 + 334); EXPECT_NEAR(get_mag_strength_tesla(10, 175) * 1e9, 33064, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(10, 180) * 1e9, 32823, 145 + 328); - EXPECT_NEAR(get_mag_strength_tesla(15, -180) * 1e9, 33125, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(15, -175) * 1e9, 33044, 145 + 330); - EXPECT_NEAR(get_mag_strength_tesla(15, -170) * 1e9, 33014, 145 + 330); - EXPECT_NEAR(get_mag_strength_tesla(15, -165) * 1e9, 33016, 145 + 330); - EXPECT_NEAR(get_mag_strength_tesla(15, -160) * 1e9, 33053, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(15, -155) * 1e9, 33143, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(15, -150) * 1e9, 33307, 145 + 333); - EXPECT_NEAR(get_mag_strength_tesla(15, -145) * 1e9, 33558, 145 + 336); - EXPECT_NEAR(get_mag_strength_tesla(15, -140) * 1e9, 33896, 145 + 339); - EXPECT_NEAR(get_mag_strength_tesla(15, -135) * 1e9, 34302, 145 + 343); - EXPECT_NEAR(get_mag_strength_tesla(15, -130) * 1e9, 34750, 145 + 348); - EXPECT_NEAR(get_mag_strength_tesla(15, -125) * 1e9, 35216, 145 + 352); - EXPECT_NEAR(get_mag_strength_tesla(15, -120) * 1e9, 35678, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(15, -115) * 1e9, 36122, 145 + 361); - EXPECT_NEAR(get_mag_strength_tesla(15, -110) * 1e9, 36528, 145 + 365); - EXPECT_NEAR(get_mag_strength_tesla(15, -105) * 1e9, 36868, 145 + 369); - EXPECT_NEAR(get_mag_strength_tesla(15, -100) * 1e9, 37104, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(15, -95) * 1e9, 37196, 145 + 372); - EXPECT_NEAR(get_mag_strength_tesla(15, -90) * 1e9, 37114, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(15, -85) * 1e9, 36845, 145 + 368); - EXPECT_NEAR(get_mag_strength_tesla(15, -80) * 1e9, 36401, 145 + 364); - EXPECT_NEAR(get_mag_strength_tesla(15, -75) * 1e9, 35810, 145 + 358); - EXPECT_NEAR(get_mag_strength_tesla(15, -70) * 1e9, 35118, 145 + 351); - EXPECT_NEAR(get_mag_strength_tesla(15, -65) * 1e9, 34379, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(15, -60) * 1e9, 33653, 145 + 337); - EXPECT_NEAR(get_mag_strength_tesla(15, -55) * 1e9, 33003, 145 + 330); - EXPECT_NEAR(get_mag_strength_tesla(15, -50) * 1e9, 32487, 145 + 325); - EXPECT_NEAR(get_mag_strength_tesla(15, -45) * 1e9, 32144, 145 + 321); - EXPECT_NEAR(get_mag_strength_tesla(15, -40) * 1e9, 31982, 145 + 320); - EXPECT_NEAR(get_mag_strength_tesla(15, -35) * 1e9, 31987, 145 + 320); - EXPECT_NEAR(get_mag_strength_tesla(15, -30) * 1e9, 32129, 145 + 321); - EXPECT_NEAR(get_mag_strength_tesla(15, -25) * 1e9, 32375, 145 + 324); - EXPECT_NEAR(get_mag_strength_tesla(15, -20) * 1e9, 32706, 145 + 327); - EXPECT_NEAR(get_mag_strength_tesla(15, -15) * 1e9, 33104, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(15, -10) * 1e9, 33557, 145 + 336); - EXPECT_NEAR(get_mag_strength_tesla(15, -5) * 1e9, 34043, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(15, 0) * 1e9, 34537, 145 + 345); - EXPECT_NEAR(get_mag_strength_tesla(15, 5) * 1e9, 35012, 145 + 350); - EXPECT_NEAR(get_mag_strength_tesla(15, 10) * 1e9, 35452, 145 + 355); - EXPECT_NEAR(get_mag_strength_tesla(15, 15) * 1e9, 35856, 145 + 359); - EXPECT_NEAR(get_mag_strength_tesla(15, 20) * 1e9, 36245, 145 + 362); - EXPECT_NEAR(get_mag_strength_tesla(15, 25) * 1e9, 36647, 145 + 366); - EXPECT_NEAR(get_mag_strength_tesla(15, 30) * 1e9, 37090, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(15, 35) * 1e9, 37582, 145 + 376); - EXPECT_NEAR(get_mag_strength_tesla(15, 40) * 1e9, 38118, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(15, 45) * 1e9, 38682, 145 + 387); - EXPECT_NEAR(get_mag_strength_tesla(15, 50) * 1e9, 39259, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(15, 55) * 1e9, 39846, 145 + 398); - EXPECT_NEAR(get_mag_strength_tesla(15, 60) * 1e9, 40444, 145 + 404); - EXPECT_NEAR(get_mag_strength_tesla(15, 65) * 1e9, 41051, 145 + 411); - EXPECT_NEAR(get_mag_strength_tesla(15, 70) * 1e9, 41652, 145 + 417); - EXPECT_NEAR(get_mag_strength_tesla(15, 75) * 1e9, 42216, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(15, 80) * 1e9, 42708, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(15, 85) * 1e9, 43092, 145 + 431); - EXPECT_NEAR(get_mag_strength_tesla(15, 90) * 1e9, 43339, 145 + 433); - EXPECT_NEAR(get_mag_strength_tesla(15, 95) * 1e9, 43434, 145 + 434); - EXPECT_NEAR(get_mag_strength_tesla(15, 100) * 1e9, 43371, 145 + 434); - EXPECT_NEAR(get_mag_strength_tesla(15, 105) * 1e9, 43146, 145 + 431); - EXPECT_NEAR(get_mag_strength_tesla(15, 110) * 1e9, 42759, 145 + 428); - EXPECT_NEAR(get_mag_strength_tesla(15, 115) * 1e9, 42211, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(15, 120) * 1e9, 41513, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(15, 125) * 1e9, 40687, 145 + 407); - EXPECT_NEAR(get_mag_strength_tesla(15, 130) * 1e9, 39767, 145 + 398); - EXPECT_NEAR(get_mag_strength_tesla(15, 135) * 1e9, 38796, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(15, 140) * 1e9, 37816, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(15, 145) * 1e9, 36868, 145 + 369); - EXPECT_NEAR(get_mag_strength_tesla(15, 150) * 1e9, 35984, 145 + 360); - EXPECT_NEAR(get_mag_strength_tesla(15, 155) * 1e9, 35192, 145 + 352); - EXPECT_NEAR(get_mag_strength_tesla(15, 160) * 1e9, 34514, 145 + 345); - EXPECT_NEAR(get_mag_strength_tesla(15, 165) * 1e9, 33967, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(15, 170) * 1e9, 33560, 145 + 336); + EXPECT_NEAR(get_mag_strength_tesla(10, 180) * 1e9, 32822, 145 + 328); + EXPECT_NEAR(get_mag_strength_tesla(15, -180) * 1e9, 33124, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(15, -175) * 1e9, 33042, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(15, -170) * 1e9, 33010, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(15, -165) * 1e9, 33010, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(15, -160) * 1e9, 33046, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(15, -155) * 1e9, 33134, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(15, -150) * 1e9, 33296, 145 + 333); + EXPECT_NEAR(get_mag_strength_tesla(15, -145) * 1e9, 33547, 145 + 335); + EXPECT_NEAR(get_mag_strength_tesla(15, -140) * 1e9, 33883, 145 + 339); + EXPECT_NEAR(get_mag_strength_tesla(15, -135) * 1e9, 34288, 145 + 343); + EXPECT_NEAR(get_mag_strength_tesla(15, -130) * 1e9, 34735, 145 + 347); + EXPECT_NEAR(get_mag_strength_tesla(15, -125) * 1e9, 35198, 145 + 352); + EXPECT_NEAR(get_mag_strength_tesla(15, -120) * 1e9, 35659, 145 + 357); + EXPECT_NEAR(get_mag_strength_tesla(15, -115) * 1e9, 36100, 145 + 361); + EXPECT_NEAR(get_mag_strength_tesla(15, -110) * 1e9, 36503, 145 + 365); + EXPECT_NEAR(get_mag_strength_tesla(15, -105) * 1e9, 36840, 145 + 368); + EXPECT_NEAR(get_mag_strength_tesla(15, -100) * 1e9, 37074, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(15, -95) * 1e9, 37164, 145 + 372); + EXPECT_NEAR(get_mag_strength_tesla(15, -90) * 1e9, 37081, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(15, -85) * 1e9, 36812, 145 + 368); + EXPECT_NEAR(get_mag_strength_tesla(15, -80) * 1e9, 36367, 145 + 364); + EXPECT_NEAR(get_mag_strength_tesla(15, -75) * 1e9, 35776, 145 + 358); + EXPECT_NEAR(get_mag_strength_tesla(15, -70) * 1e9, 35086, 145 + 351); + EXPECT_NEAR(get_mag_strength_tesla(15, -65) * 1e9, 34348, 145 + 343); + EXPECT_NEAR(get_mag_strength_tesla(15, -60) * 1e9, 33624, 145 + 336); + EXPECT_NEAR(get_mag_strength_tesla(15, -55) * 1e9, 32979, 145 + 330); + EXPECT_NEAR(get_mag_strength_tesla(15, -50) * 1e9, 32468, 145 + 325); + EXPECT_NEAR(get_mag_strength_tesla(15, -45) * 1e9, 32130, 145 + 321); + EXPECT_NEAR(get_mag_strength_tesla(15, -40) * 1e9, 31974, 145 + 320); + EXPECT_NEAR(get_mag_strength_tesla(15, -35) * 1e9, 31983, 145 + 320); + EXPECT_NEAR(get_mag_strength_tesla(15, -30) * 1e9, 32128, 145 + 321); + EXPECT_NEAR(get_mag_strength_tesla(15, -25) * 1e9, 32377, 145 + 324); + EXPECT_NEAR(get_mag_strength_tesla(15, -20) * 1e9, 32709, 145 + 327); + EXPECT_NEAR(get_mag_strength_tesla(15, -15) * 1e9, 33109, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(15, -10) * 1e9, 33562, 145 + 336); + EXPECT_NEAR(get_mag_strength_tesla(15, -5) * 1e9, 34050, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(15, 0) * 1e9, 34544, 145 + 345); + EXPECT_NEAR(get_mag_strength_tesla(15, 5) * 1e9, 35019, 145 + 350); + EXPECT_NEAR(get_mag_strength_tesla(15, 10) * 1e9, 35458, 145 + 355); + EXPECT_NEAR(get_mag_strength_tesla(15, 15) * 1e9, 35862, 145 + 359); + EXPECT_NEAR(get_mag_strength_tesla(15, 20) * 1e9, 36252, 145 + 363); + EXPECT_NEAR(get_mag_strength_tesla(15, 25) * 1e9, 36655, 145 + 367); + EXPECT_NEAR(get_mag_strength_tesla(15, 30) * 1e9, 37098, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(15, 35) * 1e9, 37593, 145 + 376); + EXPECT_NEAR(get_mag_strength_tesla(15, 40) * 1e9, 38131, 145 + 381); + EXPECT_NEAR(get_mag_strength_tesla(15, 45) * 1e9, 38696, 145 + 387); + EXPECT_NEAR(get_mag_strength_tesla(15, 50) * 1e9, 39276, 145 + 393); + EXPECT_NEAR(get_mag_strength_tesla(15, 55) * 1e9, 39864, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(15, 60) * 1e9, 40465, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(15, 65) * 1e9, 41074, 145 + 411); + EXPECT_NEAR(get_mag_strength_tesla(15, 70) * 1e9, 41677, 145 + 417); + EXPECT_NEAR(get_mag_strength_tesla(15, 75) * 1e9, 42243, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(15, 80) * 1e9, 42735, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(15, 85) * 1e9, 43117, 145 + 431); + EXPECT_NEAR(get_mag_strength_tesla(15, 90) * 1e9, 43362, 145 + 434); + EXPECT_NEAR(get_mag_strength_tesla(15, 95) * 1e9, 43456, 145 + 435); + EXPECT_NEAR(get_mag_strength_tesla(15, 100) * 1e9, 43390, 145 + 434); + EXPECT_NEAR(get_mag_strength_tesla(15, 105) * 1e9, 43163, 145 + 432); + EXPECT_NEAR(get_mag_strength_tesla(15, 110) * 1e9, 42773, 145 + 428); + EXPECT_NEAR(get_mag_strength_tesla(15, 115) * 1e9, 42224, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(15, 120) * 1e9, 41524, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(15, 125) * 1e9, 40697, 145 + 407); + EXPECT_NEAR(get_mag_strength_tesla(15, 130) * 1e9, 39776, 145 + 398); + EXPECT_NEAR(get_mag_strength_tesla(15, 135) * 1e9, 38804, 145 + 388); + EXPECT_NEAR(get_mag_strength_tesla(15, 140) * 1e9, 37824, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(15, 145) * 1e9, 36874, 145 + 369); + EXPECT_NEAR(get_mag_strength_tesla(15, 150) * 1e9, 35990, 145 + 360); + EXPECT_NEAR(get_mag_strength_tesla(15, 155) * 1e9, 35197, 145 + 352); + EXPECT_NEAR(get_mag_strength_tesla(15, 160) * 1e9, 34518, 145 + 345); + EXPECT_NEAR(get_mag_strength_tesla(15, 165) * 1e9, 33970, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(15, 170) * 1e9, 33561, 145 + 336); EXPECT_NEAR(get_mag_strength_tesla(15, 175) * 1e9, 33286, 145 + 333); - EXPECT_NEAR(get_mag_strength_tesla(15, 180) * 1e9, 33125, 145 + 331); - EXPECT_NEAR(get_mag_strength_tesla(20, -180) * 1e9, 33989, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(20, -175) * 1e9, 33959, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(20, -170) * 1e9, 34002, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(20, -165) * 1e9, 34098, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(20, -160) * 1e9, 34248, 145 + 342); - EXPECT_NEAR(get_mag_strength_tesla(20, -155) * 1e9, 34466, 145 + 345); - EXPECT_NEAR(get_mag_strength_tesla(20, -150) * 1e9, 34772, 145 + 348); - EXPECT_NEAR(get_mag_strength_tesla(20, -145) * 1e9, 35178, 145 + 352); - EXPECT_NEAR(get_mag_strength_tesla(20, -140) * 1e9, 35678, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(20, -135) * 1e9, 36254, 145 + 363); - EXPECT_NEAR(get_mag_strength_tesla(20, -130) * 1e9, 36876, 145 + 369); - EXPECT_NEAR(get_mag_strength_tesla(20, -125) * 1e9, 37516, 145 + 375); - EXPECT_NEAR(get_mag_strength_tesla(20, -120) * 1e9, 38148, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(20, -115) * 1e9, 38751, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(20, -110) * 1e9, 39299, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(20, -105) * 1e9, 39760, 145 + 398); - EXPECT_NEAR(get_mag_strength_tesla(20, -100) * 1e9, 40090, 145 + 401); - EXPECT_NEAR(get_mag_strength_tesla(20, -95) * 1e9, 40248, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(20, -90) * 1e9, 40201, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(20, -85) * 1e9, 39936, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(20, -80) * 1e9, 39465, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(20, -75) * 1e9, 38820, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(20, -70) * 1e9, 38052, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(20, -65) * 1e9, 37223, 145 + 372); - EXPECT_NEAR(get_mag_strength_tesla(20, -60) * 1e9, 36402, 145 + 364); - EXPECT_NEAR(get_mag_strength_tesla(20, -55) * 1e9, 35656, 145 + 357); - EXPECT_NEAR(get_mag_strength_tesla(20, -50) * 1e9, 35042, 145 + 350); - EXPECT_NEAR(get_mag_strength_tesla(20, -45) * 1e9, 34595, 145 + 346); - EXPECT_NEAR(get_mag_strength_tesla(20, -40) * 1e9, 34322, 145 + 343); - EXPECT_NEAR(get_mag_strength_tesla(20, -35) * 1e9, 34210, 145 + 342); - EXPECT_NEAR(get_mag_strength_tesla(20, -30) * 1e9, 34232, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(15, 180) * 1e9, 33124, 145 + 331); + EXPECT_NEAR(get_mag_strength_tesla(20, -180) * 1e9, 33988, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(20, -175) * 1e9, 33956, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(20, -170) * 1e9, 33997, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(20, -165) * 1e9, 34091, 145 + 341); + EXPECT_NEAR(get_mag_strength_tesla(20, -160) * 1e9, 34239, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(20, -155) * 1e9, 34455, 145 + 345); + EXPECT_NEAR(get_mag_strength_tesla(20, -150) * 1e9, 34759, 145 + 348); + EXPECT_NEAR(get_mag_strength_tesla(20, -145) * 1e9, 35163, 145 + 352); + EXPECT_NEAR(get_mag_strength_tesla(20, -140) * 1e9, 35662, 145 + 357); + EXPECT_NEAR(get_mag_strength_tesla(20, -135) * 1e9, 36237, 145 + 362); + EXPECT_NEAR(get_mag_strength_tesla(20, -130) * 1e9, 36857, 145 + 369); + EXPECT_NEAR(get_mag_strength_tesla(20, -125) * 1e9, 37495, 145 + 375); + EXPECT_NEAR(get_mag_strength_tesla(20, -120) * 1e9, 38125, 145 + 381); + EXPECT_NEAR(get_mag_strength_tesla(20, -115) * 1e9, 38725, 145 + 387); + EXPECT_NEAR(get_mag_strength_tesla(20, -110) * 1e9, 39271, 145 + 393); + EXPECT_NEAR(get_mag_strength_tesla(20, -105) * 1e9, 39729, 145 + 397); + EXPECT_NEAR(get_mag_strength_tesla(20, -100) * 1e9, 40058, 145 + 401); + EXPECT_NEAR(get_mag_strength_tesla(20, -95) * 1e9, 40214, 145 + 402); + EXPECT_NEAR(get_mag_strength_tesla(20, -90) * 1e9, 40166, 145 + 402); + EXPECT_NEAR(get_mag_strength_tesla(20, -85) * 1e9, 39900, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(20, -80) * 1e9, 39429, 145 + 394); + EXPECT_NEAR(get_mag_strength_tesla(20, -75) * 1e9, 38784, 145 + 388); + EXPECT_NEAR(get_mag_strength_tesla(20, -70) * 1e9, 38017, 145 + 380); + EXPECT_NEAR(get_mag_strength_tesla(20, -65) * 1e9, 37190, 145 + 372); + EXPECT_NEAR(get_mag_strength_tesla(20, -60) * 1e9, 36372, 145 + 364); + EXPECT_NEAR(get_mag_strength_tesla(20, -55) * 1e9, 35630, 145 + 356); + EXPECT_NEAR(get_mag_strength_tesla(20, -50) * 1e9, 35021, 145 + 350); + EXPECT_NEAR(get_mag_strength_tesla(20, -45) * 1e9, 34579, 145 + 346); + EXPECT_NEAR(get_mag_strength_tesla(20, -40) * 1e9, 34311, 145 + 343); + EXPECT_NEAR(get_mag_strength_tesla(20, -35) * 1e9, 34203, 145 + 342); + EXPECT_NEAR(get_mag_strength_tesla(20, -30) * 1e9, 34229, 145 + 342); EXPECT_NEAR(get_mag_strength_tesla(20, -25) * 1e9, 34368, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(20, -20) * 1e9, 34605, 145 + 346); - EXPECT_NEAR(get_mag_strength_tesla(20, -15) * 1e9, 34935, 145 + 349); - EXPECT_NEAR(get_mag_strength_tesla(20, -10) * 1e9, 35348, 145 + 353); - EXPECT_NEAR(get_mag_strength_tesla(20, -5) * 1e9, 35820, 145 + 358); - EXPECT_NEAR(get_mag_strength_tesla(20, 0) * 1e9, 36322, 145 + 363); - EXPECT_NEAR(get_mag_strength_tesla(20, 5) * 1e9, 36821, 145 + 368); - EXPECT_NEAR(get_mag_strength_tesla(20, 10) * 1e9, 37298, 145 + 373); - EXPECT_NEAR(get_mag_strength_tesla(20, 15) * 1e9, 37755, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(20, 20) * 1e9, 38211, 145 + 382); - EXPECT_NEAR(get_mag_strength_tesla(20, 25) * 1e9, 38689, 145 + 387); - EXPECT_NEAR(get_mag_strength_tesla(20, 30) * 1e9, 39206, 145 + 392); - EXPECT_NEAR(get_mag_strength_tesla(20, 35) * 1e9, 39758, 145 + 398); - EXPECT_NEAR(get_mag_strength_tesla(20, 40) * 1e9, 40329, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(20, 45) * 1e9, 40897, 145 + 409); - EXPECT_NEAR(get_mag_strength_tesla(20, 50) * 1e9, 41453, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(20, 55) * 1e9, 42002, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(20, 60) * 1e9, 42556, 145 + 426); - EXPECT_NEAR(get_mag_strength_tesla(20, 65) * 1e9, 43122, 145 + 431); - EXPECT_NEAR(get_mag_strength_tesla(20, 70) * 1e9, 43691, 145 + 437); - EXPECT_NEAR(get_mag_strength_tesla(20, 75) * 1e9, 44236, 145 + 442); - EXPECT_NEAR(get_mag_strength_tesla(20, 80) * 1e9, 44720, 145 + 447); - EXPECT_NEAR(get_mag_strength_tesla(20, 85) * 1e9, 45108, 145 + 451); - EXPECT_NEAR(get_mag_strength_tesla(20, 90) * 1e9, 45373, 145 + 454); - EXPECT_NEAR(get_mag_strength_tesla(20, 95) * 1e9, 45495, 145 + 455); - EXPECT_NEAR(get_mag_strength_tesla(20, 100) * 1e9, 45460, 145 + 455); - EXPECT_NEAR(get_mag_strength_tesla(20, 105) * 1e9, 45251, 145 + 453); - EXPECT_NEAR(get_mag_strength_tesla(20, 110) * 1e9, 44854, 145 + 449); - EXPECT_NEAR(get_mag_strength_tesla(20, 115) * 1e9, 44257, 145 + 443); - EXPECT_NEAR(get_mag_strength_tesla(20, 120) * 1e9, 43467, 145 + 435); - EXPECT_NEAR(get_mag_strength_tesla(20, 125) * 1e9, 42510, 145 + 425); - EXPECT_NEAR(get_mag_strength_tesla(20, 130) * 1e9, 41433, 145 + 414); - EXPECT_NEAR(get_mag_strength_tesla(20, 135) * 1e9, 40293, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(20, 140) * 1e9, 39151, 145 + 392); - EXPECT_NEAR(get_mag_strength_tesla(20, 145) * 1e9, 38056, 145 + 381); - EXPECT_NEAR(get_mag_strength_tesla(20, 150) * 1e9, 37049, 145 + 370); - EXPECT_NEAR(get_mag_strength_tesla(20, 155) * 1e9, 36160, 145 + 362); - EXPECT_NEAR(get_mag_strength_tesla(20, 160) * 1e9, 35412, 145 + 354); - EXPECT_NEAR(get_mag_strength_tesla(20, 165) * 1e9, 34820, 145 + 348); - EXPECT_NEAR(get_mag_strength_tesla(20, 170) * 1e9, 34392, 145 + 344); - EXPECT_NEAR(get_mag_strength_tesla(20, 175) * 1e9, 34122, 145 + 341); - EXPECT_NEAR(get_mag_strength_tesla(20, 180) * 1e9, 33989, 145 + 340); - EXPECT_NEAR(get_mag_strength_tesla(25, -180) * 1e9, 35366, 145 + 354); - EXPECT_NEAR(get_mag_strength_tesla(25, -175) * 1e9, 35343, 145 + 353); - EXPECT_NEAR(get_mag_strength_tesla(25, -170) * 1e9, 35423, 145 + 354); - EXPECT_NEAR(get_mag_strength_tesla(25, -165) * 1e9, 35586, 145 + 356); - EXPECT_NEAR(get_mag_strength_tesla(25, -160) * 1e9, 35829, 145 + 358); - EXPECT_NEAR(get_mag_strength_tesla(25, -155) * 1e9, 36161, 145 + 362); - EXPECT_NEAR(get_mag_strength_tesla(25, -150) * 1e9, 36595, 145 + 366); - EXPECT_NEAR(get_mag_strength_tesla(25, -145) * 1e9, 37137, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(25, -140) * 1e9, 37778, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(25, -135) * 1e9, 38496, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(25, -130) * 1e9, 39260, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(25, -125) * 1e9, 40041, 145 + 400); - EXPECT_NEAR(get_mag_strength_tesla(25, -120) * 1e9, 40810, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(25, -115) * 1e9, 41540, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(25, -110) * 1e9, 42201, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(25, -105) * 1e9, 42757, 145 + 428); - EXPECT_NEAR(get_mag_strength_tesla(25, -100) * 1e9, 43163, 145 + 432); - EXPECT_NEAR(get_mag_strength_tesla(25, -95) * 1e9, 43375, 145 + 434); - EXPECT_NEAR(get_mag_strength_tesla(25, -90) * 1e9, 43360, 145 + 434); - EXPECT_NEAR(get_mag_strength_tesla(25, -85) * 1e9, 43104, 145 + 431); - EXPECT_NEAR(get_mag_strength_tesla(25, -80) * 1e9, 42617, 145 + 426); - EXPECT_NEAR(get_mag_strength_tesla(25, -75) * 1e9, 41934, 145 + 419); - EXPECT_NEAR(get_mag_strength_tesla(25, -70) * 1e9, 41112, 145 + 411); - EXPECT_NEAR(get_mag_strength_tesla(25, -65) * 1e9, 40217, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(25, -60) * 1e9, 39326, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(25, -55) * 1e9, 38509, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(25, -50) * 1e9, 37822, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(25, -45) * 1e9, 37298, 145 + 373); - EXPECT_NEAR(get_mag_strength_tesla(25, -40) * 1e9, 36941, 145 + 369); - EXPECT_NEAR(get_mag_strength_tesla(25, -35) * 1e9, 36738, 145 + 367); - EXPECT_NEAR(get_mag_strength_tesla(25, -30) * 1e9, 36667, 145 + 367); - EXPECT_NEAR(get_mag_strength_tesla(25, -25) * 1e9, 36714, 145 + 367); - EXPECT_NEAR(get_mag_strength_tesla(25, -20) * 1e9, 36873, 145 + 369); - EXPECT_NEAR(get_mag_strength_tesla(25, -15) * 1e9, 37143, 145 + 371); - EXPECT_NEAR(get_mag_strength_tesla(25, -10) * 1e9, 37516, 145 + 375); - EXPECT_NEAR(get_mag_strength_tesla(25, -5) * 1e9, 37968, 145 + 380); - EXPECT_NEAR(get_mag_strength_tesla(25, 0) * 1e9, 38466, 145 + 385); - EXPECT_NEAR(get_mag_strength_tesla(25, 5) * 1e9, 38975, 145 + 390); - EXPECT_NEAR(get_mag_strength_tesla(25, 10) * 1e9, 39474, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(25, 15) * 1e9, 39961, 145 + 400); - EXPECT_NEAR(get_mag_strength_tesla(25, 20) * 1e9, 40452, 145 + 405); - EXPECT_NEAR(get_mag_strength_tesla(25, 25) * 1e9, 40967, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(25, 30) * 1e9, 41517, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(25, 35) * 1e9, 42096, 145 + 421); - EXPECT_NEAR(get_mag_strength_tesla(25, 40) * 1e9, 42684, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(25, 45) * 1e9, 43262, 145 + 433); - EXPECT_NEAR(get_mag_strength_tesla(25, 50) * 1e9, 43823, 145 + 438); - EXPECT_NEAR(get_mag_strength_tesla(25, 55) * 1e9, 44377, 145 + 444); - EXPECT_NEAR(get_mag_strength_tesla(25, 60) * 1e9, 44938, 145 + 449); - EXPECT_NEAR(get_mag_strength_tesla(25, 65) * 1e9, 45518, 145 + 455); - EXPECT_NEAR(get_mag_strength_tesla(25, 70) * 1e9, 46107, 145 + 461); - EXPECT_NEAR(get_mag_strength_tesla(25, 75) * 1e9, 46679, 145 + 467); - EXPECT_NEAR(get_mag_strength_tesla(25, 80) * 1e9, 47199, 145 + 472); - EXPECT_NEAR(get_mag_strength_tesla(25, 85) * 1e9, 47629, 145 + 476); - EXPECT_NEAR(get_mag_strength_tesla(25, 90) * 1e9, 47938, 145 + 479); - EXPECT_NEAR(get_mag_strength_tesla(25, 95) * 1e9, 48102, 145 + 481); - EXPECT_NEAR(get_mag_strength_tesla(25, 100) * 1e9, 48098, 145 + 481); - EXPECT_NEAR(get_mag_strength_tesla(25, 105) * 1e9, 47904, 145 + 479); - EXPECT_NEAR(get_mag_strength_tesla(25, 110) * 1e9, 47494, 145 + 475); - EXPECT_NEAR(get_mag_strength_tesla(25, 115) * 1e9, 46855, 145 + 469); - EXPECT_NEAR(get_mag_strength_tesla(25, 120) * 1e9, 45990, 145 + 460); - EXPECT_NEAR(get_mag_strength_tesla(25, 125) * 1e9, 44928, 145 + 449); - EXPECT_NEAR(get_mag_strength_tesla(25, 130) * 1e9, 43724, 145 + 437); - EXPECT_NEAR(get_mag_strength_tesla(25, 135) * 1e9, 42445, 145 + 424); - EXPECT_NEAR(get_mag_strength_tesla(25, 140) * 1e9, 41160, 145 + 412); - EXPECT_NEAR(get_mag_strength_tesla(25, 145) * 1e9, 39931, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(25, 150) * 1e9, 38803, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(25, 155) * 1e9, 37810, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(25, 160) * 1e9, 36973, 145 + 370); - EXPECT_NEAR(get_mag_strength_tesla(25, 165) * 1e9, 36310, 145 + 363); - EXPECT_NEAR(get_mag_strength_tesla(25, 170) * 1e9, 35826, 145 + 358); - EXPECT_NEAR(get_mag_strength_tesla(25, 175) * 1e9, 35517, 145 + 355); - EXPECT_NEAR(get_mag_strength_tesla(25, 180) * 1e9, 35366, 145 + 354); - EXPECT_NEAR(get_mag_strength_tesla(30, -180) * 1e9, 37220, 145 + 372); - EXPECT_NEAR(get_mag_strength_tesla(30, -175) * 1e9, 37174, 145 + 372); - EXPECT_NEAR(get_mag_strength_tesla(30, -170) * 1e9, 37262, 145 + 373); - EXPECT_NEAR(get_mag_strength_tesla(30, -165) * 1e9, 37466, 145 + 375); - EXPECT_NEAR(get_mag_strength_tesla(30, -160) * 1e9, 37783, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(30, -155) * 1e9, 38212, 145 + 382); - EXPECT_NEAR(get_mag_strength_tesla(30, -150) * 1e9, 38758, 145 + 388); - EXPECT_NEAR(get_mag_strength_tesla(30, -145) * 1e9, 39414, 145 + 394); - EXPECT_NEAR(get_mag_strength_tesla(30, -140) * 1e9, 40169, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(30, -135) * 1e9, 40996, 145 + 410); - EXPECT_NEAR(get_mag_strength_tesla(30, -130) * 1e9, 41865, 145 + 419); - EXPECT_NEAR(get_mag_strength_tesla(30, -125) * 1e9, 42744, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(30, -120) * 1e9, 43605, 145 + 436); - EXPECT_NEAR(get_mag_strength_tesla(30, -115) * 1e9, 44419, 145 + 444); - EXPECT_NEAR(get_mag_strength_tesla(30, -110) * 1e9, 45153, 145 + 452); - EXPECT_NEAR(get_mag_strength_tesla(30, -105) * 1e9, 45769, 145 + 458); - EXPECT_NEAR(get_mag_strength_tesla(30, -100) * 1e9, 46222, 145 + 462); - EXPECT_NEAR(get_mag_strength_tesla(30, -95) * 1e9, 46471, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(30, -90) * 1e9, 46481, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(30, -85) * 1e9, 46238, 145 + 462); - EXPECT_NEAR(get_mag_strength_tesla(30, -80) * 1e9, 45752, 145 + 458); - EXPECT_NEAR(get_mag_strength_tesla(30, -75) * 1e9, 45057, 145 + 451); - EXPECT_NEAR(get_mag_strength_tesla(30, -70) * 1e9, 44208, 145 + 442); - EXPECT_NEAR(get_mag_strength_tesla(30, -65) * 1e9, 43278, 145 + 433); - EXPECT_NEAR(get_mag_strength_tesla(30, -60) * 1e9, 42344, 145 + 423); - EXPECT_NEAR(get_mag_strength_tesla(30, -55) * 1e9, 41479, 145 + 415); - EXPECT_NEAR(get_mag_strength_tesla(30, -50) * 1e9, 40736, 145 + 407); - EXPECT_NEAR(get_mag_strength_tesla(30, -45) * 1e9, 40148, 145 + 401); - EXPECT_NEAR(get_mag_strength_tesla(30, -40) * 1e9, 39720, 145 + 397); - EXPECT_NEAR(get_mag_strength_tesla(30, -35) * 1e9, 39439, 145 + 394); - EXPECT_NEAR(get_mag_strength_tesla(30, -30) * 1e9, 39289, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(30, -25) * 1e9, 39260, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(30, -20) * 1e9, 39349, 145 + 393); - EXPECT_NEAR(get_mag_strength_tesla(30, -15) * 1e9, 39558, 145 + 396); - EXPECT_NEAR(get_mag_strength_tesla(30, -10) * 1e9, 39881, 145 + 399); - EXPECT_NEAR(get_mag_strength_tesla(30, -5) * 1e9, 40295, 145 + 403); - EXPECT_NEAR(get_mag_strength_tesla(30, 0) * 1e9, 40768, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(30, 5) * 1e9, 41265, 145 + 413); - EXPECT_NEAR(get_mag_strength_tesla(30, 10) * 1e9, 41761, 145 + 418); - EXPECT_NEAR(get_mag_strength_tesla(30, 15) * 1e9, 42251, 145 + 423); - EXPECT_NEAR(get_mag_strength_tesla(30, 20) * 1e9, 42748, 145 + 427); - EXPECT_NEAR(get_mag_strength_tesla(30, 25) * 1e9, 43267, 145 + 433); - EXPECT_NEAR(get_mag_strength_tesla(30, 30) * 1e9, 43817, 145 + 438); - EXPECT_NEAR(get_mag_strength_tesla(30, 35) * 1e9, 44396, 145 + 444); - EXPECT_NEAR(get_mag_strength_tesla(30, 40) * 1e9, 44988, 145 + 450); - EXPECT_NEAR(get_mag_strength_tesla(30, 45) * 1e9, 45579, 145 + 456); - EXPECT_NEAR(get_mag_strength_tesla(30, 50) * 1e9, 46168, 145 + 462); - EXPECT_NEAR(get_mag_strength_tesla(30, 55) * 1e9, 46761, 145 + 468); - EXPECT_NEAR(get_mag_strength_tesla(30, 60) * 1e9, 47373, 145 + 474); - EXPECT_NEAR(get_mag_strength_tesla(30, 65) * 1e9, 48008, 145 + 480); - EXPECT_NEAR(get_mag_strength_tesla(30, 70) * 1e9, 48658, 145 + 487); - EXPECT_NEAR(get_mag_strength_tesla(30, 75) * 1e9, 49293, 145 + 493); - EXPECT_NEAR(get_mag_strength_tesla(30, 80) * 1e9, 49877, 145 + 499); - EXPECT_NEAR(get_mag_strength_tesla(30, 85) * 1e9, 50370, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(30, 90) * 1e9, 50737, 145 + 507); - EXPECT_NEAR(get_mag_strength_tesla(30, 95) * 1e9, 50950, 145 + 509); - EXPECT_NEAR(get_mag_strength_tesla(30, 100) * 1e9, 50979, 145 + 510); - EXPECT_NEAR(get_mag_strength_tesla(30, 105) * 1e9, 50797, 145 + 508); - EXPECT_NEAR(get_mag_strength_tesla(30, 110) * 1e9, 50379, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(30, 115) * 1e9, 49710, 145 + 497); - EXPECT_NEAR(get_mag_strength_tesla(30, 120) * 1e9, 48797, 145 + 488); - EXPECT_NEAR(get_mag_strength_tesla(30, 125) * 1e9, 47670, 145 + 477); - EXPECT_NEAR(get_mag_strength_tesla(30, 130) * 1e9, 46386, 145 + 464); - EXPECT_NEAR(get_mag_strength_tesla(30, 135) * 1e9, 45016, 145 + 450); - EXPECT_NEAR(get_mag_strength_tesla(30, 140) * 1e9, 43636, 145 + 436); - EXPECT_NEAR(get_mag_strength_tesla(30, 145) * 1e9, 42309, 145 + 423); - EXPECT_NEAR(get_mag_strength_tesla(30, 150) * 1e9, 41087, 145 + 411); - EXPECT_NEAR(get_mag_strength_tesla(30, 155) * 1e9, 40005, 145 + 400); - EXPECT_NEAR(get_mag_strength_tesla(30, 160) * 1e9, 39086, 145 + 391); - EXPECT_NEAR(get_mag_strength_tesla(30, 165) * 1e9, 38345, 145 + 383); - EXPECT_NEAR(get_mag_strength_tesla(30, 170) * 1e9, 37790, 145 + 378); - EXPECT_NEAR(get_mag_strength_tesla(30, 175) * 1e9, 37419, 145 + 374); - EXPECT_NEAR(get_mag_strength_tesla(30, 180) * 1e9, 37220, 145 + 372); - EXPECT_NEAR(get_mag_strength_tesla(35, -180) * 1e9, 39521, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(35, -175) * 1e9, 39439, 145 + 394); - EXPECT_NEAR(get_mag_strength_tesla(35, -170) * 1e9, 39517, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(35, -165) * 1e9, 39743, 145 + 397); - EXPECT_NEAR(get_mag_strength_tesla(35, -160) * 1e9, 40110, 145 + 401); - EXPECT_NEAR(get_mag_strength_tesla(35, -155) * 1e9, 40612, 145 + 406); - EXPECT_NEAR(get_mag_strength_tesla(35, -150) * 1e9, 41240, 145 + 412); - EXPECT_NEAR(get_mag_strength_tesla(35, -145) * 1e9, 41982, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(35, -140) * 1e9, 42816, 145 + 428); - EXPECT_NEAR(get_mag_strength_tesla(35, -135) * 1e9, 43712, 145 + 437); - EXPECT_NEAR(get_mag_strength_tesla(35, -130) * 1e9, 44641, 145 + 446); - EXPECT_NEAR(get_mag_strength_tesla(35, -125) * 1e9, 45572, 145 + 456); - EXPECT_NEAR(get_mag_strength_tesla(35, -120) * 1e9, 46474, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(35, -115) * 1e9, 47320, 145 + 473); - EXPECT_NEAR(get_mag_strength_tesla(35, -110) * 1e9, 48078, 145 + 481); - EXPECT_NEAR(get_mag_strength_tesla(35, -105) * 1e9, 48711, 145 + 487); - EXPECT_NEAR(get_mag_strength_tesla(35, -100) * 1e9, 49177, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(35, -95) * 1e9, 49437, 145 + 494); - EXPECT_NEAR(get_mag_strength_tesla(35, -90) * 1e9, 49459, 145 + 495); - EXPECT_NEAR(get_mag_strength_tesla(35, -85) * 1e9, 49230, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(35, -80) * 1e9, 48756, 145 + 488); - EXPECT_NEAR(get_mag_strength_tesla(35, -75) * 1e9, 48071, 145 + 481); - EXPECT_NEAR(get_mag_strength_tesla(35, -70) * 1e9, 47227, 145 + 472); - EXPECT_NEAR(get_mag_strength_tesla(35, -65) * 1e9, 46294, 145 + 463); - EXPECT_NEAR(get_mag_strength_tesla(35, -60) * 1e9, 45346, 145 + 453); - EXPECT_NEAR(get_mag_strength_tesla(35, -55) * 1e9, 44453, 145 + 445); - EXPECT_NEAR(get_mag_strength_tesla(35, -50) * 1e9, 43668, 145 + 437); - EXPECT_NEAR(get_mag_strength_tesla(35, -45) * 1e9, 43023, 145 + 430); - EXPECT_NEAR(get_mag_strength_tesla(35, -40) * 1e9, 42527, 145 + 425); - EXPECT_NEAR(get_mag_strength_tesla(35, -35) * 1e9, 42171, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(35, -30) * 1e9, 41946, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(20, -20) * 1e9, 34607, 145 + 346); + EXPECT_NEAR(get_mag_strength_tesla(20, -15) * 1e9, 34939, 145 + 349); + EXPECT_NEAR(get_mag_strength_tesla(20, -10) * 1e9, 35353, 145 + 354); + EXPECT_NEAR(get_mag_strength_tesla(20, -5) * 1e9, 35828, 145 + 358); + EXPECT_NEAR(get_mag_strength_tesla(20, 0) * 1e9, 36330, 145 + 363); + EXPECT_NEAR(get_mag_strength_tesla(20, 5) * 1e9, 36830, 145 + 368); + EXPECT_NEAR(get_mag_strength_tesla(20, 10) * 1e9, 37308, 145 + 373); + EXPECT_NEAR(get_mag_strength_tesla(20, 15) * 1e9, 37765, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(20, 20) * 1e9, 38221, 145 + 382); + EXPECT_NEAR(get_mag_strength_tesla(20, 25) * 1e9, 38701, 145 + 387); + EXPECT_NEAR(get_mag_strength_tesla(20, 30) * 1e9, 39219, 145 + 392); + EXPECT_NEAR(get_mag_strength_tesla(20, 35) * 1e9, 39773, 145 + 398); + EXPECT_NEAR(get_mag_strength_tesla(20, 40) * 1e9, 40345, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(20, 45) * 1e9, 40914, 145 + 409); + EXPECT_NEAR(get_mag_strength_tesla(20, 50) * 1e9, 41472, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(20, 55) * 1e9, 42022, 145 + 420); + EXPECT_NEAR(get_mag_strength_tesla(20, 60) * 1e9, 42578, 145 + 426); + EXPECT_NEAR(get_mag_strength_tesla(20, 65) * 1e9, 43147, 145 + 431); + EXPECT_NEAR(get_mag_strength_tesla(20, 70) * 1e9, 43718, 145 + 437); + EXPECT_NEAR(get_mag_strength_tesla(20, 75) * 1e9, 44265, 145 + 443); + EXPECT_NEAR(get_mag_strength_tesla(20, 80) * 1e9, 44750, 145 + 447); + EXPECT_NEAR(get_mag_strength_tesla(20, 85) * 1e9, 45137, 145 + 451); + EXPECT_NEAR(get_mag_strength_tesla(20, 90) * 1e9, 45400, 145 + 454); + EXPECT_NEAR(get_mag_strength_tesla(20, 95) * 1e9, 45520, 145 + 455); + EXPECT_NEAR(get_mag_strength_tesla(20, 100) * 1e9, 45482, 145 + 455); + EXPECT_NEAR(get_mag_strength_tesla(20, 105) * 1e9, 45271, 145 + 453); + EXPECT_NEAR(get_mag_strength_tesla(20, 110) * 1e9, 44871, 145 + 449); + EXPECT_NEAR(get_mag_strength_tesla(20, 115) * 1e9, 44273, 145 + 443); + EXPECT_NEAR(get_mag_strength_tesla(20, 120) * 1e9, 43481, 145 + 435); + EXPECT_NEAR(get_mag_strength_tesla(20, 125) * 1e9, 42522, 145 + 425); + EXPECT_NEAR(get_mag_strength_tesla(20, 130) * 1e9, 41444, 145 + 414); + EXPECT_NEAR(get_mag_strength_tesla(20, 135) * 1e9, 40303, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(20, 140) * 1e9, 39159, 145 + 392); + EXPECT_NEAR(get_mag_strength_tesla(20, 145) * 1e9, 38063, 145 + 381); + EXPECT_NEAR(get_mag_strength_tesla(20, 150) * 1e9, 37056, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(20, 155) * 1e9, 36166, 145 + 362); + EXPECT_NEAR(get_mag_strength_tesla(20, 160) * 1e9, 35416, 145 + 354); + EXPECT_NEAR(get_mag_strength_tesla(20, 165) * 1e9, 34823, 145 + 348); + EXPECT_NEAR(get_mag_strength_tesla(20, 170) * 1e9, 34394, 145 + 344); + EXPECT_NEAR(get_mag_strength_tesla(20, 175) * 1e9, 34123, 145 + 341); + EXPECT_NEAR(get_mag_strength_tesla(20, 180) * 1e9, 33988, 145 + 340); + EXPECT_NEAR(get_mag_strength_tesla(25, -180) * 1e9, 35364, 145 + 354); + EXPECT_NEAR(get_mag_strength_tesla(25, -175) * 1e9, 35340, 145 + 353); + EXPECT_NEAR(get_mag_strength_tesla(25, -170) * 1e9, 35416, 145 + 354); + EXPECT_NEAR(get_mag_strength_tesla(25, -165) * 1e9, 35577, 145 + 356); + EXPECT_NEAR(get_mag_strength_tesla(25, -160) * 1e9, 35817, 145 + 358); + EXPECT_NEAR(get_mag_strength_tesla(25, -155) * 1e9, 36148, 145 + 361); + EXPECT_NEAR(get_mag_strength_tesla(25, -150) * 1e9, 36580, 145 + 366); + EXPECT_NEAR(get_mag_strength_tesla(25, -145) * 1e9, 37120, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(25, -140) * 1e9, 37759, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(25, -135) * 1e9, 38475, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(25, -130) * 1e9, 39238, 145 + 392); + EXPECT_NEAR(get_mag_strength_tesla(25, -125) * 1e9, 40016, 145 + 400); + EXPECT_NEAR(get_mag_strength_tesla(25, -120) * 1e9, 40783, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(25, -115) * 1e9, 41510, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(25, -110) * 1e9, 42170, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(25, -105) * 1e9, 42724, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(25, -100) * 1e9, 43128, 145 + 431); + EXPECT_NEAR(get_mag_strength_tesla(25, -95) * 1e9, 43339, 145 + 433); + EXPECT_NEAR(get_mag_strength_tesla(25, -90) * 1e9, 43323, 145 + 433); + EXPECT_NEAR(get_mag_strength_tesla(25, -85) * 1e9, 43066, 145 + 431); + EXPECT_NEAR(get_mag_strength_tesla(25, -80) * 1e9, 42579, 145 + 426); + EXPECT_NEAR(get_mag_strength_tesla(25, -75) * 1e9, 41897, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(25, -70) * 1e9, 41076, 145 + 411); + EXPECT_NEAR(get_mag_strength_tesla(25, -65) * 1e9, 40183, 145 + 402); + EXPECT_NEAR(get_mag_strength_tesla(25, -60) * 1e9, 39295, 145 + 393); + EXPECT_NEAR(get_mag_strength_tesla(25, -55) * 1e9, 38482, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(25, -50) * 1e9, 37800, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(25, -45) * 1e9, 37281, 145 + 373); + EXPECT_NEAR(get_mag_strength_tesla(25, -40) * 1e9, 36929, 145 + 369); + EXPECT_NEAR(get_mag_strength_tesla(25, -35) * 1e9, 36730, 145 + 367); + EXPECT_NEAR(get_mag_strength_tesla(25, -30) * 1e9, 36663, 145 + 367); + EXPECT_NEAR(get_mag_strength_tesla(25, -25) * 1e9, 36713, 145 + 367); + EXPECT_NEAR(get_mag_strength_tesla(25, -20) * 1e9, 36875, 145 + 369); + EXPECT_NEAR(get_mag_strength_tesla(25, -15) * 1e9, 37148, 145 + 371); + EXPECT_NEAR(get_mag_strength_tesla(25, -10) * 1e9, 37522, 145 + 375); + EXPECT_NEAR(get_mag_strength_tesla(25, -5) * 1e9, 37976, 145 + 380); + EXPECT_NEAR(get_mag_strength_tesla(25, 0) * 1e9, 38476, 145 + 385); + EXPECT_NEAR(get_mag_strength_tesla(25, 5) * 1e9, 38986, 145 + 390); + EXPECT_NEAR(get_mag_strength_tesla(25, 10) * 1e9, 39486, 145 + 395); + EXPECT_NEAR(get_mag_strength_tesla(25, 15) * 1e9, 39974, 145 + 400); + EXPECT_NEAR(get_mag_strength_tesla(25, 20) * 1e9, 40466, 145 + 405); + EXPECT_NEAR(get_mag_strength_tesla(25, 25) * 1e9, 40983, 145 + 410); + EXPECT_NEAR(get_mag_strength_tesla(25, 30) * 1e9, 41535, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(25, 35) * 1e9, 42115, 145 + 421); + EXPECT_NEAR(get_mag_strength_tesla(25, 40) * 1e9, 42704, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(25, 45) * 1e9, 43282, 145 + 433); + EXPECT_NEAR(get_mag_strength_tesla(25, 50) * 1e9, 43844, 145 + 438); + EXPECT_NEAR(get_mag_strength_tesla(25, 55) * 1e9, 44399, 145 + 444); + EXPECT_NEAR(get_mag_strength_tesla(25, 60) * 1e9, 44962, 145 + 450); + EXPECT_NEAR(get_mag_strength_tesla(25, 65) * 1e9, 45544, 145 + 455); + EXPECT_NEAR(get_mag_strength_tesla(25, 70) * 1e9, 46135, 145 + 461); + EXPECT_NEAR(get_mag_strength_tesla(25, 75) * 1e9, 46710, 145 + 467); + EXPECT_NEAR(get_mag_strength_tesla(25, 80) * 1e9, 47231, 145 + 472); + EXPECT_NEAR(get_mag_strength_tesla(25, 85) * 1e9, 47660, 145 + 477); + EXPECT_NEAR(get_mag_strength_tesla(25, 90) * 1e9, 47968, 145 + 480); + EXPECT_NEAR(get_mag_strength_tesla(25, 95) * 1e9, 48130, 145 + 481); + EXPECT_NEAR(get_mag_strength_tesla(25, 100) * 1e9, 48124, 145 + 481); + EXPECT_NEAR(get_mag_strength_tesla(25, 105) * 1e9, 47926, 145 + 479); + EXPECT_NEAR(get_mag_strength_tesla(25, 110) * 1e9, 47514, 145 + 475); + EXPECT_NEAR(get_mag_strength_tesla(25, 115) * 1e9, 46873, 145 + 469); + EXPECT_NEAR(get_mag_strength_tesla(25, 120) * 1e9, 46005, 145 + 460); + EXPECT_NEAR(get_mag_strength_tesla(25, 125) * 1e9, 44942, 145 + 449); + EXPECT_NEAR(get_mag_strength_tesla(25, 130) * 1e9, 43736, 145 + 437); + EXPECT_NEAR(get_mag_strength_tesla(25, 135) * 1e9, 42455, 145 + 425); + EXPECT_NEAR(get_mag_strength_tesla(25, 140) * 1e9, 41170, 145 + 412); + EXPECT_NEAR(get_mag_strength_tesla(25, 145) * 1e9, 39940, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(25, 150) * 1e9, 38811, 145 + 388); + EXPECT_NEAR(get_mag_strength_tesla(25, 155) * 1e9, 37817, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(25, 160) * 1e9, 36979, 145 + 370); + EXPECT_NEAR(get_mag_strength_tesla(25, 165) * 1e9, 36314, 145 + 363); + EXPECT_NEAR(get_mag_strength_tesla(25, 170) * 1e9, 35829, 145 + 358); + EXPECT_NEAR(get_mag_strength_tesla(25, 175) * 1e9, 35518, 145 + 355); + EXPECT_NEAR(get_mag_strength_tesla(25, 180) * 1e9, 35364, 145 + 354); + EXPECT_NEAR(get_mag_strength_tesla(30, -180) * 1e9, 37218, 145 + 372); + EXPECT_NEAR(get_mag_strength_tesla(30, -175) * 1e9, 37170, 145 + 372); + EXPECT_NEAR(get_mag_strength_tesla(30, -170) * 1e9, 37254, 145 + 373); + EXPECT_NEAR(get_mag_strength_tesla(30, -165) * 1e9, 37456, 145 + 375); + EXPECT_NEAR(get_mag_strength_tesla(30, -160) * 1e9, 37770, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(30, -155) * 1e9, 38196, 145 + 382); + EXPECT_NEAR(get_mag_strength_tesla(30, -150) * 1e9, 38739, 145 + 387); + EXPECT_NEAR(get_mag_strength_tesla(30, -145) * 1e9, 39394, 145 + 394); + EXPECT_NEAR(get_mag_strength_tesla(30, -140) * 1e9, 40146, 145 + 401); + EXPECT_NEAR(get_mag_strength_tesla(30, -135) * 1e9, 40971, 145 + 410); + EXPECT_NEAR(get_mag_strength_tesla(30, -130) * 1e9, 41838, 145 + 418); + EXPECT_NEAR(get_mag_strength_tesla(30, -125) * 1e9, 42716, 145 + 427); + EXPECT_NEAR(get_mag_strength_tesla(30, -120) * 1e9, 43575, 145 + 436); + EXPECT_NEAR(get_mag_strength_tesla(30, -115) * 1e9, 44386, 145 + 444); + EXPECT_NEAR(get_mag_strength_tesla(30, -110) * 1e9, 45119, 145 + 451); + EXPECT_NEAR(get_mag_strength_tesla(30, -105) * 1e9, 45733, 145 + 457); + EXPECT_NEAR(get_mag_strength_tesla(30, -100) * 1e9, 46186, 145 + 462); + EXPECT_NEAR(get_mag_strength_tesla(30, -95) * 1e9, 46433, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(30, -90) * 1e9, 46443, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(30, -85) * 1e9, 46200, 145 + 462); + EXPECT_NEAR(get_mag_strength_tesla(30, -80) * 1e9, 45713, 145 + 457); + EXPECT_NEAR(get_mag_strength_tesla(30, -75) * 1e9, 45019, 145 + 450); + EXPECT_NEAR(get_mag_strength_tesla(30, -70) * 1e9, 44172, 145 + 442); + EXPECT_NEAR(get_mag_strength_tesla(30, -65) * 1e9, 43245, 145 + 432); + EXPECT_NEAR(get_mag_strength_tesla(30, -60) * 1e9, 42314, 145 + 423); + EXPECT_NEAR(get_mag_strength_tesla(30, -55) * 1e9, 41453, 145 + 415); + EXPECT_NEAR(get_mag_strength_tesla(30, -50) * 1e9, 40715, 145 + 407); + EXPECT_NEAR(get_mag_strength_tesla(30, -45) * 1e9, 40132, 145 + 401); + EXPECT_NEAR(get_mag_strength_tesla(30, -40) * 1e9, 39708, 145 + 397); + EXPECT_NEAR(get_mag_strength_tesla(30, -35) * 1e9, 39431, 145 + 394); + EXPECT_NEAR(get_mag_strength_tesla(30, -30) * 1e9, 39284, 145 + 393); + EXPECT_NEAR(get_mag_strength_tesla(30, -25) * 1e9, 39258, 145 + 393); + EXPECT_NEAR(get_mag_strength_tesla(30, -20) * 1e9, 39351, 145 + 394); + EXPECT_NEAR(get_mag_strength_tesla(30, -15) * 1e9, 39563, 145 + 396); + EXPECT_NEAR(get_mag_strength_tesla(30, -10) * 1e9, 39888, 145 + 399); + EXPECT_NEAR(get_mag_strength_tesla(30, -5) * 1e9, 40305, 145 + 403); + EXPECT_NEAR(get_mag_strength_tesla(30, 0) * 1e9, 40780, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(30, 5) * 1e9, 41278, 145 + 413); + EXPECT_NEAR(get_mag_strength_tesla(30, 10) * 1e9, 41775, 145 + 418); + EXPECT_NEAR(get_mag_strength_tesla(30, 15) * 1e9, 42267, 145 + 423); + EXPECT_NEAR(get_mag_strength_tesla(30, 20) * 1e9, 42765, 145 + 428); + EXPECT_NEAR(get_mag_strength_tesla(30, 25) * 1e9, 43286, 145 + 433); + EXPECT_NEAR(get_mag_strength_tesla(30, 30) * 1e9, 43838, 145 + 438); + EXPECT_NEAR(get_mag_strength_tesla(30, 35) * 1e9, 44418, 145 + 444); + EXPECT_NEAR(get_mag_strength_tesla(30, 40) * 1e9, 45010, 145 + 450); + EXPECT_NEAR(get_mag_strength_tesla(30, 45) * 1e9, 45602, 145 + 456); + EXPECT_NEAR(get_mag_strength_tesla(30, 50) * 1e9, 46190, 145 + 462); + EXPECT_NEAR(get_mag_strength_tesla(30, 55) * 1e9, 46785, 145 + 468); + EXPECT_NEAR(get_mag_strength_tesla(30, 60) * 1e9, 47398, 145 + 474); + EXPECT_NEAR(get_mag_strength_tesla(30, 65) * 1e9, 48036, 145 + 480); + EXPECT_NEAR(get_mag_strength_tesla(30, 70) * 1e9, 48687, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(30, 75) * 1e9, 49325, 145 + 493); + EXPECT_NEAR(get_mag_strength_tesla(30, 80) * 1e9, 49910, 145 + 499); + EXPECT_NEAR(get_mag_strength_tesla(30, 85) * 1e9, 50403, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(30, 90) * 1e9, 50769, 145 + 508); + EXPECT_NEAR(get_mag_strength_tesla(30, 95) * 1e9, 50979, 145 + 510); + EXPECT_NEAR(get_mag_strength_tesla(30, 100) * 1e9, 51005, 145 + 510); + EXPECT_NEAR(get_mag_strength_tesla(30, 105) * 1e9, 50821, 145 + 508); + EXPECT_NEAR(get_mag_strength_tesla(30, 110) * 1e9, 50400, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(30, 115) * 1e9, 49729, 145 + 497); + EXPECT_NEAR(get_mag_strength_tesla(30, 120) * 1e9, 48813, 145 + 488); + EXPECT_NEAR(get_mag_strength_tesla(30, 125) * 1e9, 47684, 145 + 477); + EXPECT_NEAR(get_mag_strength_tesla(30, 130) * 1e9, 46398, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(30, 135) * 1e9, 45028, 145 + 450); + EXPECT_NEAR(get_mag_strength_tesla(30, 140) * 1e9, 43646, 145 + 436); + EXPECT_NEAR(get_mag_strength_tesla(30, 145) * 1e9, 42319, 145 + 423); + EXPECT_NEAR(get_mag_strength_tesla(30, 150) * 1e9, 41096, 145 + 411); + EXPECT_NEAR(get_mag_strength_tesla(30, 155) * 1e9, 40013, 145 + 400); + EXPECT_NEAR(get_mag_strength_tesla(30, 160) * 1e9, 39093, 145 + 391); + EXPECT_NEAR(get_mag_strength_tesla(30, 165) * 1e9, 38351, 145 + 384); + EXPECT_NEAR(get_mag_strength_tesla(30, 170) * 1e9, 37794, 145 + 378); + EXPECT_NEAR(get_mag_strength_tesla(30, 175) * 1e9, 37420, 145 + 374); + EXPECT_NEAR(get_mag_strength_tesla(30, 180) * 1e9, 37218, 145 + 372); + EXPECT_NEAR(get_mag_strength_tesla(35, -180) * 1e9, 39520, 145 + 395); + EXPECT_NEAR(get_mag_strength_tesla(35, -175) * 1e9, 39434, 145 + 394); + EXPECT_NEAR(get_mag_strength_tesla(35, -170) * 1e9, 39508, 145 + 395); + EXPECT_NEAR(get_mag_strength_tesla(35, -165) * 1e9, 39731, 145 + 397); + EXPECT_NEAR(get_mag_strength_tesla(35, -160) * 1e9, 40095, 145 + 401); + EXPECT_NEAR(get_mag_strength_tesla(35, -155) * 1e9, 40594, 145 + 406); + EXPECT_NEAR(get_mag_strength_tesla(35, -150) * 1e9, 41220, 145 + 412); + EXPECT_NEAR(get_mag_strength_tesla(35, -145) * 1e9, 41959, 145 + 420); + EXPECT_NEAR(get_mag_strength_tesla(35, -140) * 1e9, 42790, 145 + 428); + EXPECT_NEAR(get_mag_strength_tesla(35, -135) * 1e9, 43684, 145 + 437); + EXPECT_NEAR(get_mag_strength_tesla(35, -130) * 1e9, 44612, 145 + 446); + EXPECT_NEAR(get_mag_strength_tesla(35, -125) * 1e9, 45540, 145 + 455); + EXPECT_NEAR(get_mag_strength_tesla(35, -120) * 1e9, 46441, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(35, -115) * 1e9, 47286, 145 + 473); + EXPECT_NEAR(get_mag_strength_tesla(35, -110) * 1e9, 48042, 145 + 480); + EXPECT_NEAR(get_mag_strength_tesla(35, -105) * 1e9, 48674, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(35, -100) * 1e9, 49139, 145 + 491); + EXPECT_NEAR(get_mag_strength_tesla(35, -95) * 1e9, 49398, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(35, -90) * 1e9, 49420, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(35, -85) * 1e9, 49191, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(35, -80) * 1e9, 48718, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(35, -75) * 1e9, 48034, 145 + 480); + EXPECT_NEAR(get_mag_strength_tesla(35, -70) * 1e9, 47193, 145 + 472); + EXPECT_NEAR(get_mag_strength_tesla(35, -65) * 1e9, 46262, 145 + 463); + EXPECT_NEAR(get_mag_strength_tesla(35, -60) * 1e9, 45318, 145 + 453); + EXPECT_NEAR(get_mag_strength_tesla(35, -55) * 1e9, 44429, 145 + 444); + EXPECT_NEAR(get_mag_strength_tesla(35, -50) * 1e9, 43649, 145 + 436); + EXPECT_NEAR(get_mag_strength_tesla(35, -45) * 1e9, 43008, 145 + 430); + EXPECT_NEAR(get_mag_strength_tesla(35, -40) * 1e9, 42516, 145 + 425); + EXPECT_NEAR(get_mag_strength_tesla(35, -35) * 1e9, 42164, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(35, -30) * 1e9, 41942, 145 + 419); EXPECT_NEAR(get_mag_strength_tesla(35, -25) * 1e9, 41842, 145 + 418); - EXPECT_NEAR(get_mag_strength_tesla(35, -20) * 1e9, 41862, 145 + 419); - EXPECT_NEAR(get_mag_strength_tesla(35, -15) * 1e9, 42004, 145 + 420); - EXPECT_NEAR(get_mag_strength_tesla(35, -10) * 1e9, 42262, 145 + 423); - EXPECT_NEAR(get_mag_strength_tesla(35, -5) * 1e9, 42618, 145 + 426); - EXPECT_NEAR(get_mag_strength_tesla(35, 0) * 1e9, 43040, 145 + 430); - EXPECT_NEAR(get_mag_strength_tesla(35, 5) * 1e9, 43496, 145 + 435); - EXPECT_NEAR(get_mag_strength_tesla(35, 10) * 1e9, 43963, 145 + 440); - EXPECT_NEAR(get_mag_strength_tesla(35, 15) * 1e9, 44433, 145 + 444); - EXPECT_NEAR(get_mag_strength_tesla(35, 20) * 1e9, 44912, 145 + 449); - EXPECT_NEAR(get_mag_strength_tesla(35, 25) * 1e9, 45412, 145 + 454); - EXPECT_NEAR(get_mag_strength_tesla(35, 30) * 1e9, 45945, 145 + 459); - EXPECT_NEAR(get_mag_strength_tesla(35, 35) * 1e9, 46510, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(35, 40) * 1e9, 47103, 145 + 471); - EXPECT_NEAR(get_mag_strength_tesla(35, 45) * 1e9, 47716, 145 + 477); - EXPECT_NEAR(get_mag_strength_tesla(35, 50) * 1e9, 48350, 145 + 483); - EXPECT_NEAR(get_mag_strength_tesla(35, 55) * 1e9, 49009, 145 + 490); - EXPECT_NEAR(get_mag_strength_tesla(35, 60) * 1e9, 49699, 145 + 497); - EXPECT_NEAR(get_mag_strength_tesla(35, 65) * 1e9, 50419, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(35, 70) * 1e9, 51152, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(35, 75) * 1e9, 51868, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(35, 80) * 1e9, 52527, 145 + 525); - EXPECT_NEAR(get_mag_strength_tesla(35, 85) * 1e9, 53088, 145 + 531); - EXPECT_NEAR(get_mag_strength_tesla(35, 90) * 1e9, 53514, 145 + 535); - EXPECT_NEAR(get_mag_strength_tesla(35, 95) * 1e9, 53771, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(35, 100) * 1e9, 53828, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(35, 105) * 1e9, 53658, 145 + 537); - EXPECT_NEAR(get_mag_strength_tesla(35, 110) * 1e9, 53238, 145 + 532); - EXPECT_NEAR(get_mag_strength_tesla(35, 115) * 1e9, 52560, 145 + 526); - EXPECT_NEAR(get_mag_strength_tesla(35, 120) * 1e9, 51630, 145 + 516); - EXPECT_NEAR(get_mag_strength_tesla(35, 125) * 1e9, 50484, 145 + 505); - EXPECT_NEAR(get_mag_strength_tesla(35, 130) * 1e9, 49177, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(35, 135) * 1e9, 47780, 145 + 478); - EXPECT_NEAR(get_mag_strength_tesla(35, 140) * 1e9, 46365, 145 + 464); - EXPECT_NEAR(get_mag_strength_tesla(35, 145) * 1e9, 44998, 145 + 450); - EXPECT_NEAR(get_mag_strength_tesla(35, 150) * 1e9, 43731, 145 + 437); - EXPECT_NEAR(get_mag_strength_tesla(35, 155) * 1e9, 42599, 145 + 426); - EXPECT_NEAR(get_mag_strength_tesla(35, 160) * 1e9, 41625, 145 + 416); - EXPECT_NEAR(get_mag_strength_tesla(35, 165) * 1e9, 40826, 145 + 408); - EXPECT_NEAR(get_mag_strength_tesla(35, 170) * 1e9, 40208, 145 + 402); - EXPECT_NEAR(get_mag_strength_tesla(35, 175) * 1e9, 39774, 145 + 398); - EXPECT_NEAR(get_mag_strength_tesla(35, 180) * 1e9, 39521, 145 + 395); - EXPECT_NEAR(get_mag_strength_tesla(40, -180) * 1e9, 42218, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(40, -175) * 1e9, 42104, 145 + 421); - EXPECT_NEAR(get_mag_strength_tesla(40, -170) * 1e9, 42164, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(40, -165) * 1e9, 42394, 145 + 424); - EXPECT_NEAR(get_mag_strength_tesla(40, -160) * 1e9, 42783, 145 + 428); - EXPECT_NEAR(get_mag_strength_tesla(40, -155) * 1e9, 43322, 145 + 433); - EXPECT_NEAR(get_mag_strength_tesla(40, -150) * 1e9, 43993, 145 + 440); - EXPECT_NEAR(get_mag_strength_tesla(40, -145) * 1e9, 44775, 145 + 448); - EXPECT_NEAR(get_mag_strength_tesla(40, -140) * 1e9, 45641, 145 + 456); - EXPECT_NEAR(get_mag_strength_tesla(40, -135) * 1e9, 46559, 145 + 466); - EXPECT_NEAR(get_mag_strength_tesla(40, -130) * 1e9, 47498, 145 + 475); - EXPECT_NEAR(get_mag_strength_tesla(40, -125) * 1e9, 48428, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(40, -120) * 1e9, 49320, 145 + 493); - EXPECT_NEAR(get_mag_strength_tesla(40, -115) * 1e9, 50147, 145 + 501); - EXPECT_NEAR(get_mag_strength_tesla(40, -110) * 1e9, 50879, 145 + 509); - EXPECT_NEAR(get_mag_strength_tesla(40, -105) * 1e9, 51483, 145 + 515); - EXPECT_NEAR(get_mag_strength_tesla(40, -100) * 1e9, 51923, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(40, -95) * 1e9, 52165, 145 + 522); - EXPECT_NEAR(get_mag_strength_tesla(40, -90) * 1e9, 52182, 145 + 522); - EXPECT_NEAR(get_mag_strength_tesla(40, -85) * 1e9, 51960, 145 + 520); - EXPECT_NEAR(get_mag_strength_tesla(40, -80) * 1e9, 51507, 145 + 515); - EXPECT_NEAR(get_mag_strength_tesla(40, -75) * 1e9, 50851, 145 + 509); - EXPECT_NEAR(get_mag_strength_tesla(40, -70) * 1e9, 50038, 145 + 500); - EXPECT_NEAR(get_mag_strength_tesla(40, -65) * 1e9, 49130, 145 + 491); - EXPECT_NEAR(get_mag_strength_tesla(40, -60) * 1e9, 48196, 145 + 482); - EXPECT_NEAR(get_mag_strength_tesla(40, -55) * 1e9, 47298, 145 + 473); - EXPECT_NEAR(get_mag_strength_tesla(40, -50) * 1e9, 46488, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(40, -45) * 1e9, 45796, 145 + 458); - EXPECT_NEAR(get_mag_strength_tesla(40, -40) * 1e9, 45236, 145 + 452); - EXPECT_NEAR(get_mag_strength_tesla(40, -35) * 1e9, 44808, 145 + 448); - EXPECT_NEAR(get_mag_strength_tesla(40, -30) * 1e9, 44508, 145 + 445); + EXPECT_NEAR(get_mag_strength_tesla(35, -20) * 1e9, 41864, 145 + 419); + EXPECT_NEAR(get_mag_strength_tesla(35, -15) * 1e9, 42009, 145 + 420); + EXPECT_NEAR(get_mag_strength_tesla(35, -10) * 1e9, 42271, 145 + 423); + EXPECT_NEAR(get_mag_strength_tesla(35, -5) * 1e9, 42629, 145 + 426); + EXPECT_NEAR(get_mag_strength_tesla(35, 0) * 1e9, 43053, 145 + 431); + EXPECT_NEAR(get_mag_strength_tesla(35, 5) * 1e9, 43512, 145 + 435); + EXPECT_NEAR(get_mag_strength_tesla(35, 10) * 1e9, 43980, 145 + 440); + EXPECT_NEAR(get_mag_strength_tesla(35, 15) * 1e9, 44451, 145 + 445); + EXPECT_NEAR(get_mag_strength_tesla(35, 20) * 1e9, 44932, 145 + 449); + EXPECT_NEAR(get_mag_strength_tesla(35, 25) * 1e9, 45434, 145 + 454); + EXPECT_NEAR(get_mag_strength_tesla(35, 30) * 1e9, 45968, 145 + 460); + EXPECT_NEAR(get_mag_strength_tesla(35, 35) * 1e9, 46534, 145 + 465); + EXPECT_NEAR(get_mag_strength_tesla(35, 40) * 1e9, 47127, 145 + 471); + EXPECT_NEAR(get_mag_strength_tesla(35, 45) * 1e9, 47741, 145 + 477); + EXPECT_NEAR(get_mag_strength_tesla(35, 50) * 1e9, 48374, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(35, 55) * 1e9, 49034, 145 + 490); + EXPECT_NEAR(get_mag_strength_tesla(35, 60) * 1e9, 49725, 145 + 497); + EXPECT_NEAR(get_mag_strength_tesla(35, 65) * 1e9, 50447, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(35, 70) * 1e9, 51182, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(35, 75) * 1e9, 51900, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(35, 80) * 1e9, 52560, 145 + 526); + EXPECT_NEAR(get_mag_strength_tesla(35, 85) * 1e9, 53122, 145 + 531); + EXPECT_NEAR(get_mag_strength_tesla(35, 90) * 1e9, 53546, 145 + 535); + EXPECT_NEAR(get_mag_strength_tesla(35, 95) * 1e9, 53800, 145 + 538); + EXPECT_NEAR(get_mag_strength_tesla(35, 100) * 1e9, 53855, 145 + 539); + EXPECT_NEAR(get_mag_strength_tesla(35, 105) * 1e9, 53681, 145 + 537); + EXPECT_NEAR(get_mag_strength_tesla(35, 110) * 1e9, 53259, 145 + 533); + EXPECT_NEAR(get_mag_strength_tesla(35, 115) * 1e9, 52577, 145 + 526); + EXPECT_NEAR(get_mag_strength_tesla(35, 120) * 1e9, 51646, 145 + 516); + EXPECT_NEAR(get_mag_strength_tesla(35, 125) * 1e9, 50498, 145 + 505); + EXPECT_NEAR(get_mag_strength_tesla(35, 130) * 1e9, 49190, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(35, 135) * 1e9, 47791, 145 + 478); + EXPECT_NEAR(get_mag_strength_tesla(35, 140) * 1e9, 46376, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(35, 145) * 1e9, 45008, 145 + 450); + EXPECT_NEAR(get_mag_strength_tesla(35, 150) * 1e9, 43741, 145 + 437); + EXPECT_NEAR(get_mag_strength_tesla(35, 155) * 1e9, 42608, 145 + 426); + EXPECT_NEAR(get_mag_strength_tesla(35, 160) * 1e9, 41634, 145 + 416); + EXPECT_NEAR(get_mag_strength_tesla(35, 165) * 1e9, 40832, 145 + 408); + EXPECT_NEAR(get_mag_strength_tesla(35, 170) * 1e9, 40212, 145 + 402); + EXPECT_NEAR(get_mag_strength_tesla(35, 175) * 1e9, 39776, 145 + 398); + EXPECT_NEAR(get_mag_strength_tesla(35, 180) * 1e9, 39520, 145 + 395); + EXPECT_NEAR(get_mag_strength_tesla(40, -180) * 1e9, 42217, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(40, -175) * 1e9, 42099, 145 + 421); + EXPECT_NEAR(get_mag_strength_tesla(40, -170) * 1e9, 42155, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(40, -165) * 1e9, 42380, 145 + 424); + EXPECT_NEAR(get_mag_strength_tesla(40, -160) * 1e9, 42766, 145 + 428); + EXPECT_NEAR(get_mag_strength_tesla(40, -155) * 1e9, 43302, 145 + 433); + EXPECT_NEAR(get_mag_strength_tesla(40, -150) * 1e9, 43970, 145 + 440); + EXPECT_NEAR(get_mag_strength_tesla(40, -145) * 1e9, 44749, 145 + 447); + EXPECT_NEAR(get_mag_strength_tesla(40, -140) * 1e9, 45613, 145 + 456); + EXPECT_NEAR(get_mag_strength_tesla(40, -135) * 1e9, 46529, 145 + 465); + EXPECT_NEAR(get_mag_strength_tesla(40, -130) * 1e9, 47466, 145 + 475); + EXPECT_NEAR(get_mag_strength_tesla(40, -125) * 1e9, 48394, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(40, -120) * 1e9, 49285, 145 + 493); + EXPECT_NEAR(get_mag_strength_tesla(40, -115) * 1e9, 50111, 145 + 501); + EXPECT_NEAR(get_mag_strength_tesla(40, -110) * 1e9, 50842, 145 + 508); + EXPECT_NEAR(get_mag_strength_tesla(40, -105) * 1e9, 51446, 145 + 514); + EXPECT_NEAR(get_mag_strength_tesla(40, -100) * 1e9, 51886, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(40, -95) * 1e9, 52128, 145 + 521); + EXPECT_NEAR(get_mag_strength_tesla(40, -90) * 1e9, 52144, 145 + 521); + EXPECT_NEAR(get_mag_strength_tesla(40, -85) * 1e9, 51923, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(40, -80) * 1e9, 51471, 145 + 515); + EXPECT_NEAR(get_mag_strength_tesla(40, -75) * 1e9, 50816, 145 + 508); + EXPECT_NEAR(get_mag_strength_tesla(40, -70) * 1e9, 50006, 145 + 500); + EXPECT_NEAR(get_mag_strength_tesla(40, -65) * 1e9, 49102, 145 + 491); + EXPECT_NEAR(get_mag_strength_tesla(40, -60) * 1e9, 48171, 145 + 482); + EXPECT_NEAR(get_mag_strength_tesla(40, -55) * 1e9, 47277, 145 + 473); + EXPECT_NEAR(get_mag_strength_tesla(40, -50) * 1e9, 46471, 145 + 465); + EXPECT_NEAR(get_mag_strength_tesla(40, -45) * 1e9, 45783, 145 + 458); + EXPECT_NEAR(get_mag_strength_tesla(40, -40) * 1e9, 45227, 145 + 452); + EXPECT_NEAR(get_mag_strength_tesla(40, -35) * 1e9, 44802, 145 + 448); + EXPECT_NEAR(get_mag_strength_tesla(40, -30) * 1e9, 44504, 145 + 445); EXPECT_NEAR(get_mag_strength_tesla(40, -25) * 1e9, 44330, 145 + 443); - EXPECT_NEAR(get_mag_strength_tesla(40, -20) * 1e9, 44274, 145 + 443); - EXPECT_NEAR(get_mag_strength_tesla(40, -15) * 1e9, 44340, 145 + 443); - EXPECT_NEAR(get_mag_strength_tesla(40, -10) * 1e9, 44520, 145 + 445); - EXPECT_NEAR(get_mag_strength_tesla(40, -5) * 1e9, 44797, 145 + 448); - EXPECT_NEAR(get_mag_strength_tesla(40, 0) * 1e9, 45145, 145 + 451); - EXPECT_NEAR(get_mag_strength_tesla(40, 5) * 1e9, 45538, 145 + 455); - EXPECT_NEAR(get_mag_strength_tesla(40, 10) * 1e9, 45954, 145 + 460); - EXPECT_NEAR(get_mag_strength_tesla(40, 15) * 1e9, 46383, 145 + 464); - EXPECT_NEAR(get_mag_strength_tesla(40, 20) * 1e9, 46830, 145 + 468); - EXPECT_NEAR(get_mag_strength_tesla(40, 25) * 1e9, 47303, 145 + 473); - EXPECT_NEAR(get_mag_strength_tesla(40, 30) * 1e9, 47814, 145 + 478); - EXPECT_NEAR(get_mag_strength_tesla(40, 35) * 1e9, 48368, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(40, 40) * 1e9, 48968, 145 + 490); - EXPECT_NEAR(get_mag_strength_tesla(40, 45) * 1e9, 49613, 145 + 496); - EXPECT_NEAR(get_mag_strength_tesla(40, 50) * 1e9, 50303, 145 + 503); - EXPECT_NEAR(get_mag_strength_tesla(40, 55) * 1e9, 51039, 145 + 510); - EXPECT_NEAR(get_mag_strength_tesla(40, 60) * 1e9, 51819, 145 + 518); - EXPECT_NEAR(get_mag_strength_tesla(40, 65) * 1e9, 52630, 145 + 526); - EXPECT_NEAR(get_mag_strength_tesla(40, 70) * 1e9, 53450, 145 + 534); - EXPECT_NEAR(get_mag_strength_tesla(40, 75) * 1e9, 54244, 145 + 542); - EXPECT_NEAR(get_mag_strength_tesla(40, 80) * 1e9, 54972, 145 + 550); - EXPECT_NEAR(get_mag_strength_tesla(40, 85) * 1e9, 55592, 145 + 556); - EXPECT_NEAR(get_mag_strength_tesla(40, 90) * 1e9, 56064, 145 + 561); - EXPECT_NEAR(get_mag_strength_tesla(40, 95) * 1e9, 56353, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(40, 100) * 1e9, 56431, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(40, 105) * 1e9, 56272, 145 + 563); - EXPECT_NEAR(get_mag_strength_tesla(40, 110) * 1e9, 55861, 145 + 559); - EXPECT_NEAR(get_mag_strength_tesla(40, 115) * 1e9, 55194, 145 + 552); - EXPECT_NEAR(get_mag_strength_tesla(40, 120) * 1e9, 54285, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(40, 125) * 1e9, 53169, 145 + 532); - EXPECT_NEAR(get_mag_strength_tesla(40, 130) * 1e9, 51898, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(40, 135) * 1e9, 50539, 145 + 505); - EXPECT_NEAR(get_mag_strength_tesla(40, 140) * 1e9, 49158, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(40, 145) * 1e9, 47818, 145 + 478); - EXPECT_NEAR(get_mag_strength_tesla(40, 150) * 1e9, 46566, 145 + 466); - EXPECT_NEAR(get_mag_strength_tesla(40, 155) * 1e9, 45438, 145 + 454); - EXPECT_NEAR(get_mag_strength_tesla(40, 160) * 1e9, 44456, 145 + 445); - EXPECT_NEAR(get_mag_strength_tesla(40, 165) * 1e9, 43635, 145 + 436); - EXPECT_NEAR(get_mag_strength_tesla(40, 170) * 1e9, 42985, 145 + 430); - EXPECT_NEAR(get_mag_strength_tesla(40, 175) * 1e9, 42512, 145 + 425); - EXPECT_NEAR(get_mag_strength_tesla(40, 180) * 1e9, 42218, 145 + 422); - EXPECT_NEAR(get_mag_strength_tesla(45, -180) * 1e9, 45210, 145 + 452); - EXPECT_NEAR(get_mag_strength_tesla(45, -175) * 1e9, 45076, 145 + 451); - EXPECT_NEAR(get_mag_strength_tesla(45, -170) * 1e9, 45117, 145 + 451); - EXPECT_NEAR(get_mag_strength_tesla(45, -165) * 1e9, 45332, 145 + 453); - EXPECT_NEAR(get_mag_strength_tesla(45, -160) * 1e9, 45712, 145 + 457); - EXPECT_NEAR(get_mag_strength_tesla(45, -155) * 1e9, 46242, 145 + 462); - EXPECT_NEAR(get_mag_strength_tesla(45, -150) * 1e9, 46903, 145 + 469); - EXPECT_NEAR(get_mag_strength_tesla(45, -145) * 1e9, 47669, 145 + 477); - EXPECT_NEAR(get_mag_strength_tesla(45, -140) * 1e9, 48509, 145 + 485); - EXPECT_NEAR(get_mag_strength_tesla(45, -135) * 1e9, 49392, 145 + 494); - EXPECT_NEAR(get_mag_strength_tesla(45, -130) * 1e9, 50285, 145 + 503); - EXPECT_NEAR(get_mag_strength_tesla(45, -125) * 1e9, 51161, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(45, -120) * 1e9, 51992, 145 + 520); - EXPECT_NEAR(get_mag_strength_tesla(45, -115) * 1e9, 52752, 145 + 528); - EXPECT_NEAR(get_mag_strength_tesla(45, -110) * 1e9, 53415, 145 + 534); - EXPECT_NEAR(get_mag_strength_tesla(45, -105) * 1e9, 53952, 145 + 540); - EXPECT_NEAR(get_mag_strength_tesla(45, -100) * 1e9, 54334, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(45, -95) * 1e9, 54533, 145 + 545); - EXPECT_NEAR(get_mag_strength_tesla(45, -90) * 1e9, 54527, 145 + 545); - EXPECT_NEAR(get_mag_strength_tesla(45, -85) * 1e9, 54307, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(45, -80) * 1e9, 53878, 145 + 539); - EXPECT_NEAR(get_mag_strength_tesla(45, -75) * 1e9, 53264, 145 + 533); - EXPECT_NEAR(get_mag_strength_tesla(45, -70) * 1e9, 52504, 145 + 525); - EXPECT_NEAR(get_mag_strength_tesla(45, -65) * 1e9, 51649, 145 + 516); - EXPECT_NEAR(get_mag_strength_tesla(45, -60) * 1e9, 50756, 145 + 508); - EXPECT_NEAR(get_mag_strength_tesla(45, -55) * 1e9, 49880, 145 + 499); - EXPECT_NEAR(get_mag_strength_tesla(45, -50) * 1e9, 49066, 145 + 491); - EXPECT_NEAR(get_mag_strength_tesla(45, -45) * 1e9, 48345, 145 + 483); - EXPECT_NEAR(get_mag_strength_tesla(45, -40) * 1e9, 47737, 145 + 477); - EXPECT_NEAR(get_mag_strength_tesla(45, -35) * 1e9, 47246, 145 + 472); - EXPECT_NEAR(get_mag_strength_tesla(45, -30) * 1e9, 46876, 145 + 469); - EXPECT_NEAR(get_mag_strength_tesla(45, -25) * 1e9, 46624, 145 + 466); - EXPECT_NEAR(get_mag_strength_tesla(45, -20) * 1e9, 46490, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(45, -15) * 1e9, 46473, 145 + 465); - EXPECT_NEAR(get_mag_strength_tesla(45, -10) * 1e9, 46565, 145 + 466); - EXPECT_NEAR(get_mag_strength_tesla(45, -5) * 1e9, 46751, 145 + 468); - EXPECT_NEAR(get_mag_strength_tesla(45, 0) * 1e9, 47011, 145 + 470); - EXPECT_NEAR(get_mag_strength_tesla(45, 5) * 1e9, 47325, 145 + 473); - EXPECT_NEAR(get_mag_strength_tesla(45, 10) * 1e9, 47676, 145 + 477); - EXPECT_NEAR(get_mag_strength_tesla(45, 15) * 1e9, 48055, 145 + 481); - EXPECT_NEAR(get_mag_strength_tesla(45, 20) * 1e9, 48465, 145 + 485); - EXPECT_NEAR(get_mag_strength_tesla(45, 25) * 1e9, 48913, 145 + 489); - EXPECT_NEAR(get_mag_strength_tesla(45, 30) * 1e9, 49409, 145 + 494); - EXPECT_NEAR(get_mag_strength_tesla(45, 35) * 1e9, 49962, 145 + 500); - EXPECT_NEAR(get_mag_strength_tesla(45, 40) * 1e9, 50579, 145 + 506); - EXPECT_NEAR(get_mag_strength_tesla(45, 45) * 1e9, 51261, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(45, 50) * 1e9, 52008, 145 + 520); - EXPECT_NEAR(get_mag_strength_tesla(45, 55) * 1e9, 52816, 145 + 528); - EXPECT_NEAR(get_mag_strength_tesla(45, 60) * 1e9, 53674, 145 + 537); - EXPECT_NEAR(get_mag_strength_tesla(45, 65) * 1e9, 54561, 145 + 546); - EXPECT_NEAR(get_mag_strength_tesla(45, 70) * 1e9, 55449, 145 + 554); - EXPECT_NEAR(get_mag_strength_tesla(45, 75) * 1e9, 56301, 145 + 563); - EXPECT_NEAR(get_mag_strength_tesla(45, 80) * 1e9, 57075, 145 + 571); - EXPECT_NEAR(get_mag_strength_tesla(45, 85) * 1e9, 57730, 145 + 577); - EXPECT_NEAR(get_mag_strength_tesla(45, 90) * 1e9, 58228, 145 + 582); - EXPECT_NEAR(get_mag_strength_tesla(45, 95) * 1e9, 58536, 145 + 585); - EXPECT_NEAR(get_mag_strength_tesla(45, 100) * 1e9, 58628, 145 + 586); - EXPECT_NEAR(get_mag_strength_tesla(45, 105) * 1e9, 58484, 145 + 585); - EXPECT_NEAR(get_mag_strength_tesla(45, 110) * 1e9, 58095, 145 + 581); - EXPECT_NEAR(get_mag_strength_tesla(45, 115) * 1e9, 57466, 145 + 575); - EXPECT_NEAR(get_mag_strength_tesla(45, 120) * 1e9, 56614, 145 + 566); - EXPECT_NEAR(get_mag_strength_tesla(45, 125) * 1e9, 55574, 145 + 556); - EXPECT_NEAR(get_mag_strength_tesla(45, 130) * 1e9, 54396, 145 + 544); - EXPECT_NEAR(get_mag_strength_tesla(45, 135) * 1e9, 53137, 145 + 531); - EXPECT_NEAR(get_mag_strength_tesla(45, 140) * 1e9, 51857, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(45, 145) * 1e9, 50608, 145 + 506); - EXPECT_NEAR(get_mag_strength_tesla(45, 150) * 1e9, 49434, 145 + 494); - EXPECT_NEAR(get_mag_strength_tesla(45, 155) * 1e9, 48368, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(45, 160) * 1e9, 47430, 145 + 474); - EXPECT_NEAR(get_mag_strength_tesla(45, 165) * 1e9, 46636, 145 + 466); - EXPECT_NEAR(get_mag_strength_tesla(45, 170) * 1e9, 45996, 145 + 460); - EXPECT_NEAR(get_mag_strength_tesla(45, 175) * 1e9, 45518, 145 + 455); - EXPECT_NEAR(get_mag_strength_tesla(45, 180) * 1e9, 45210, 145 + 452); - EXPECT_NEAR(get_mag_strength_tesla(50, -180) * 1e9, 48320, 145 + 483); - EXPECT_NEAR(get_mag_strength_tesla(50, -175) * 1e9, 48181, 145 + 482); - EXPECT_NEAR(get_mag_strength_tesla(50, -170) * 1e9, 48203, 145 + 482); - EXPECT_NEAR(get_mag_strength_tesla(50, -165) * 1e9, 48385, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(50, -160) * 1e9, 48720, 145 + 487); - EXPECT_NEAR(get_mag_strength_tesla(50, -155) * 1e9, 49195, 145 + 492); - EXPECT_NEAR(get_mag_strength_tesla(50, -150) * 1e9, 49789, 145 + 498); - EXPECT_NEAR(get_mag_strength_tesla(50, -145) * 1e9, 50477, 145 + 505); - EXPECT_NEAR(get_mag_strength_tesla(50, -140) * 1e9, 51230, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(50, -135) * 1e9, 52018, 145 + 520); - EXPECT_NEAR(get_mag_strength_tesla(50, -130) * 1e9, 52811, 145 + 528); - EXPECT_NEAR(get_mag_strength_tesla(50, -125) * 1e9, 53583, 145 + 536); - EXPECT_NEAR(get_mag_strength_tesla(50, -120) * 1e9, 54307, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(50, -115) * 1e9, 54961, 145 + 550); - EXPECT_NEAR(get_mag_strength_tesla(50, -110) * 1e9, 55522, 145 + 555); - EXPECT_NEAR(get_mag_strength_tesla(50, -105) * 1e9, 55964, 145 + 560); - EXPECT_NEAR(get_mag_strength_tesla(50, -100) * 1e9, 56267, 145 + 563); - EXPECT_NEAR(get_mag_strength_tesla(50, -95) * 1e9, 56407, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(50, -90) * 1e9, 56371, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(50, -85) * 1e9, 56150, 145 + 562); - EXPECT_NEAR(get_mag_strength_tesla(50, -80) * 1e9, 55750, 145 + 558); - EXPECT_NEAR(get_mag_strength_tesla(50, -75) * 1e9, 55190, 145 + 552); - EXPECT_NEAR(get_mag_strength_tesla(50, -70) * 1e9, 54500, 145 + 545); - EXPECT_NEAR(get_mag_strength_tesla(50, -65) * 1e9, 53720, 145 + 537); - EXPECT_NEAR(get_mag_strength_tesla(50, -60) * 1e9, 52896, 145 + 529); - EXPECT_NEAR(get_mag_strength_tesla(50, -55) * 1e9, 52070, 145 + 521); - EXPECT_NEAR(get_mag_strength_tesla(50, -50) * 1e9, 51283, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(50, -45) * 1e9, 50563, 145 + 506); - EXPECT_NEAR(get_mag_strength_tesla(50, -40) * 1e9, 49932, 145 + 499); - EXPECT_NEAR(get_mag_strength_tesla(50, -35) * 1e9, 49400, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(40, -20) * 1e9, 44277, 145 + 443); + EXPECT_NEAR(get_mag_strength_tesla(40, -15) * 1e9, 44346, 145 + 443); + EXPECT_NEAR(get_mag_strength_tesla(40, -10) * 1e9, 44529, 145 + 445); + EXPECT_NEAR(get_mag_strength_tesla(40, -5) * 1e9, 44809, 145 + 448); + EXPECT_NEAR(get_mag_strength_tesla(40, 0) * 1e9, 45160, 145 + 452); + EXPECT_NEAR(get_mag_strength_tesla(40, 5) * 1e9, 45554, 145 + 456); + EXPECT_NEAR(get_mag_strength_tesla(40, 10) * 1e9, 45972, 145 + 460); + EXPECT_NEAR(get_mag_strength_tesla(40, 15) * 1e9, 46403, 145 + 464); + EXPECT_NEAR(get_mag_strength_tesla(40, 20) * 1e9, 46851, 145 + 469); + EXPECT_NEAR(get_mag_strength_tesla(40, 25) * 1e9, 47326, 145 + 473); + EXPECT_NEAR(get_mag_strength_tesla(40, 30) * 1e9, 47838, 145 + 478); + EXPECT_NEAR(get_mag_strength_tesla(40, 35) * 1e9, 48394, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(40, 40) * 1e9, 48994, 145 + 490); + EXPECT_NEAR(get_mag_strength_tesla(40, 45) * 1e9, 49638, 145 + 496); + EXPECT_NEAR(get_mag_strength_tesla(40, 50) * 1e9, 50329, 145 + 503); + EXPECT_NEAR(get_mag_strength_tesla(40, 55) * 1e9, 51065, 145 + 511); + EXPECT_NEAR(get_mag_strength_tesla(40, 60) * 1e9, 51846, 145 + 518); + EXPECT_NEAR(get_mag_strength_tesla(40, 65) * 1e9, 52658, 145 + 527); + EXPECT_NEAR(get_mag_strength_tesla(40, 70) * 1e9, 53480, 145 + 535); + EXPECT_NEAR(get_mag_strength_tesla(40, 75) * 1e9, 54276, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(40, 80) * 1e9, 55004, 145 + 550); + EXPECT_NEAR(get_mag_strength_tesla(40, 85) * 1e9, 55624, 145 + 556); + EXPECT_NEAR(get_mag_strength_tesla(40, 90) * 1e9, 56094, 145 + 561); + EXPECT_NEAR(get_mag_strength_tesla(40, 95) * 1e9, 56381, 145 + 564); + EXPECT_NEAR(get_mag_strength_tesla(40, 100) * 1e9, 56456, 145 + 565); + EXPECT_NEAR(get_mag_strength_tesla(40, 105) * 1e9, 56294, 145 + 563); + EXPECT_NEAR(get_mag_strength_tesla(40, 110) * 1e9, 55880, 145 + 559); + EXPECT_NEAR(get_mag_strength_tesla(40, 115) * 1e9, 55210, 145 + 552); + EXPECT_NEAR(get_mag_strength_tesla(40, 120) * 1e9, 54298, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(40, 125) * 1e9, 53180, 145 + 532); + EXPECT_NEAR(get_mag_strength_tesla(40, 130) * 1e9, 51909, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(40, 135) * 1e9, 50549, 145 + 505); + EXPECT_NEAR(get_mag_strength_tesla(40, 140) * 1e9, 49169, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(40, 145) * 1e9, 47829, 145 + 478); + EXPECT_NEAR(get_mag_strength_tesla(40, 150) * 1e9, 46578, 145 + 466); + EXPECT_NEAR(get_mag_strength_tesla(40, 155) * 1e9, 45449, 145 + 454); + EXPECT_NEAR(get_mag_strength_tesla(40, 160) * 1e9, 44466, 145 + 445); + EXPECT_NEAR(get_mag_strength_tesla(40, 165) * 1e9, 43644, 145 + 436); + EXPECT_NEAR(get_mag_strength_tesla(40, 170) * 1e9, 42991, 145 + 430); + EXPECT_NEAR(get_mag_strength_tesla(40, 175) * 1e9, 42515, 145 + 425); + EXPECT_NEAR(get_mag_strength_tesla(40, 180) * 1e9, 42217, 145 + 422); + EXPECT_NEAR(get_mag_strength_tesla(45, -180) * 1e9, 45209, 145 + 452); + EXPECT_NEAR(get_mag_strength_tesla(45, -175) * 1e9, 45071, 145 + 451); + EXPECT_NEAR(get_mag_strength_tesla(45, -170) * 1e9, 45108, 145 + 451); + EXPECT_NEAR(get_mag_strength_tesla(45, -165) * 1e9, 45318, 145 + 453); + EXPECT_NEAR(get_mag_strength_tesla(45, -160) * 1e9, 45694, 145 + 457); + EXPECT_NEAR(get_mag_strength_tesla(45, -155) * 1e9, 46220, 145 + 462); + EXPECT_NEAR(get_mag_strength_tesla(45, -150) * 1e9, 46878, 145 + 469); + EXPECT_NEAR(get_mag_strength_tesla(45, -145) * 1e9, 47641, 145 + 476); + EXPECT_NEAR(get_mag_strength_tesla(45, -140) * 1e9, 48478, 145 + 485); + EXPECT_NEAR(get_mag_strength_tesla(45, -135) * 1e9, 49359, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(45, -130) * 1e9, 50252, 145 + 503); + EXPECT_NEAR(get_mag_strength_tesla(45, -125) * 1e9, 51126, 145 + 511); + EXPECT_NEAR(get_mag_strength_tesla(45, -120) * 1e9, 51956, 145 + 520); + EXPECT_NEAR(get_mag_strength_tesla(45, -115) * 1e9, 52716, 145 + 527); + EXPECT_NEAR(get_mag_strength_tesla(45, -110) * 1e9, 53379, 145 + 534); + EXPECT_NEAR(get_mag_strength_tesla(45, -105) * 1e9, 53916, 145 + 539); + EXPECT_NEAR(get_mag_strength_tesla(45, -100) * 1e9, 54299, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(45, -95) * 1e9, 54498, 145 + 545); + EXPECT_NEAR(get_mag_strength_tesla(45, -90) * 1e9, 54493, 145 + 545); + EXPECT_NEAR(get_mag_strength_tesla(45, -85) * 1e9, 54274, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(45, -80) * 1e9, 53847, 145 + 538); + EXPECT_NEAR(get_mag_strength_tesla(45, -75) * 1e9, 53234, 145 + 532); + EXPECT_NEAR(get_mag_strength_tesla(45, -70) * 1e9, 52476, 145 + 525); + EXPECT_NEAR(get_mag_strength_tesla(45, -65) * 1e9, 51624, 145 + 516); + EXPECT_NEAR(get_mag_strength_tesla(45, -60) * 1e9, 50734, 145 + 507); + EXPECT_NEAR(get_mag_strength_tesla(45, -55) * 1e9, 49862, 145 + 499); + EXPECT_NEAR(get_mag_strength_tesla(45, -50) * 1e9, 49051, 145 + 491); + EXPECT_NEAR(get_mag_strength_tesla(45, -45) * 1e9, 48334, 145 + 483); + EXPECT_NEAR(get_mag_strength_tesla(45, -40) * 1e9, 47729, 145 + 477); + EXPECT_NEAR(get_mag_strength_tesla(45, -35) * 1e9, 47242, 145 + 472); + EXPECT_NEAR(get_mag_strength_tesla(45, -30) * 1e9, 46874, 145 + 469); + EXPECT_NEAR(get_mag_strength_tesla(45, -25) * 1e9, 46625, 145 + 466); + EXPECT_NEAR(get_mag_strength_tesla(45, -20) * 1e9, 46495, 145 + 465); + EXPECT_NEAR(get_mag_strength_tesla(45, -15) * 1e9, 46480, 145 + 465); + EXPECT_NEAR(get_mag_strength_tesla(45, -10) * 1e9, 46575, 145 + 466); + EXPECT_NEAR(get_mag_strength_tesla(45, -5) * 1e9, 46763, 145 + 468); + EXPECT_NEAR(get_mag_strength_tesla(45, 0) * 1e9, 47026, 145 + 470); + EXPECT_NEAR(get_mag_strength_tesla(45, 5) * 1e9, 47342, 145 + 473); + EXPECT_NEAR(get_mag_strength_tesla(45, 10) * 1e9, 47694, 145 + 477); + EXPECT_NEAR(get_mag_strength_tesla(45, 15) * 1e9, 48076, 145 + 481); + EXPECT_NEAR(get_mag_strength_tesla(45, 20) * 1e9, 48487, 145 + 485); + EXPECT_NEAR(get_mag_strength_tesla(45, 25) * 1e9, 48936, 145 + 489); + EXPECT_NEAR(get_mag_strength_tesla(45, 30) * 1e9, 49434, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(45, 35) * 1e9, 49988, 145 + 500); + EXPECT_NEAR(get_mag_strength_tesla(45, 40) * 1e9, 50605, 145 + 506); + EXPECT_NEAR(get_mag_strength_tesla(45, 45) * 1e9, 51287, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(45, 50) * 1e9, 52035, 145 + 520); + EXPECT_NEAR(get_mag_strength_tesla(45, 55) * 1e9, 52843, 145 + 528); + EXPECT_NEAR(get_mag_strength_tesla(45, 60) * 1e9, 53701, 145 + 537); + EXPECT_NEAR(get_mag_strength_tesla(45, 65) * 1e9, 54590, 145 + 546); + EXPECT_NEAR(get_mag_strength_tesla(45, 70) * 1e9, 55479, 145 + 555); + EXPECT_NEAR(get_mag_strength_tesla(45, 75) * 1e9, 56332, 145 + 563); + EXPECT_NEAR(get_mag_strength_tesla(45, 80) * 1e9, 57106, 145 + 571); + EXPECT_NEAR(get_mag_strength_tesla(45, 85) * 1e9, 57760, 145 + 578); + EXPECT_NEAR(get_mag_strength_tesla(45, 90) * 1e9, 58256, 145 + 583); + EXPECT_NEAR(get_mag_strength_tesla(45, 95) * 1e9, 58561, 145 + 586); + EXPECT_NEAR(get_mag_strength_tesla(45, 100) * 1e9, 58649, 145 + 586); + EXPECT_NEAR(get_mag_strength_tesla(45, 105) * 1e9, 58502, 145 + 585); + EXPECT_NEAR(get_mag_strength_tesla(45, 110) * 1e9, 58110, 145 + 581); + EXPECT_NEAR(get_mag_strength_tesla(45, 115) * 1e9, 57478, 145 + 575); + EXPECT_NEAR(get_mag_strength_tesla(45, 120) * 1e9, 56624, 145 + 566); + EXPECT_NEAR(get_mag_strength_tesla(45, 125) * 1e9, 55584, 145 + 556); + EXPECT_NEAR(get_mag_strength_tesla(45, 130) * 1e9, 54405, 145 + 544); + EXPECT_NEAR(get_mag_strength_tesla(45, 135) * 1e9, 53147, 145 + 531); + EXPECT_NEAR(get_mag_strength_tesla(45, 140) * 1e9, 51867, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(45, 145) * 1e9, 50619, 145 + 506); + EXPECT_NEAR(get_mag_strength_tesla(45, 150) * 1e9, 49447, 145 + 494); + EXPECT_NEAR(get_mag_strength_tesla(45, 155) * 1e9, 48380, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(45, 160) * 1e9, 47442, 145 + 474); + EXPECT_NEAR(get_mag_strength_tesla(45, 165) * 1e9, 46646, 145 + 466); + EXPECT_NEAR(get_mag_strength_tesla(45, 170) * 1e9, 46003, 145 + 460); + EXPECT_NEAR(get_mag_strength_tesla(45, 175) * 1e9, 45522, 145 + 455); + EXPECT_NEAR(get_mag_strength_tesla(45, 180) * 1e9, 45209, 145 + 452); + EXPECT_NEAR(get_mag_strength_tesla(50, -180) * 1e9, 48321, 145 + 483); + EXPECT_NEAR(get_mag_strength_tesla(50, -175) * 1e9, 48177, 145 + 482); + EXPECT_NEAR(get_mag_strength_tesla(50, -170) * 1e9, 48194, 145 + 482); + EXPECT_NEAR(get_mag_strength_tesla(50, -165) * 1e9, 48370, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(50, -160) * 1e9, 48701, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(50, -155) * 1e9, 49171, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(50, -150) * 1e9, 49762, 145 + 498); + EXPECT_NEAR(get_mag_strength_tesla(50, -145) * 1e9, 50447, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(50, -140) * 1e9, 51198, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(50, -135) * 1e9, 51984, 145 + 520); + EXPECT_NEAR(get_mag_strength_tesla(50, -130) * 1e9, 52776, 145 + 528); + EXPECT_NEAR(get_mag_strength_tesla(50, -125) * 1e9, 53547, 145 + 535); + EXPECT_NEAR(get_mag_strength_tesla(50, -120) * 1e9, 54272, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(50, -115) * 1e9, 54926, 145 + 549); + EXPECT_NEAR(get_mag_strength_tesla(50, -110) * 1e9, 55487, 145 + 555); + EXPECT_NEAR(get_mag_strength_tesla(50, -105) * 1e9, 55931, 145 + 559); + EXPECT_NEAR(get_mag_strength_tesla(50, -100) * 1e9, 56234, 145 + 562); + EXPECT_NEAR(get_mag_strength_tesla(50, -95) * 1e9, 56376, 145 + 564); + EXPECT_NEAR(get_mag_strength_tesla(50, -90) * 1e9, 56341, 145 + 563); + EXPECT_NEAR(get_mag_strength_tesla(50, -85) * 1e9, 56122, 145 + 561); + EXPECT_NEAR(get_mag_strength_tesla(50, -80) * 1e9, 55724, 145 + 557); + EXPECT_NEAR(get_mag_strength_tesla(50, -75) * 1e9, 55166, 145 + 552); + EXPECT_NEAR(get_mag_strength_tesla(50, -70) * 1e9, 54478, 145 + 545); + EXPECT_NEAR(get_mag_strength_tesla(50, -65) * 1e9, 53701, 145 + 537); + EXPECT_NEAR(get_mag_strength_tesla(50, -60) * 1e9, 52879, 145 + 529); + EXPECT_NEAR(get_mag_strength_tesla(50, -55) * 1e9, 52056, 145 + 521); + EXPECT_NEAR(get_mag_strength_tesla(50, -50) * 1e9, 51272, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(50, -45) * 1e9, 50555, 145 + 506); + EXPECT_NEAR(get_mag_strength_tesla(50, -40) * 1e9, 49926, 145 + 499); + EXPECT_NEAR(get_mag_strength_tesla(50, -35) * 1e9, 49398, 145 + 494); EXPECT_NEAR(get_mag_strength_tesla(50, -30) * 1e9, 48975, 145 + 490); - EXPECT_NEAR(get_mag_strength_tesla(50, -25) * 1e9, 48659, 145 + 487); - EXPECT_NEAR(get_mag_strength_tesla(50, -20) * 1e9, 48453, 145 + 485); - EXPECT_NEAR(get_mag_strength_tesla(50, -15) * 1e9, 48354, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(50, -10) * 1e9, 48357, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(50, -5) * 1e9, 48450, 145 + 484); - EXPECT_NEAR(get_mag_strength_tesla(50, 0) * 1e9, 48620, 145 + 486); - EXPECT_NEAR(get_mag_strength_tesla(50, 5) * 1e9, 48852, 145 + 489); - EXPECT_NEAR(get_mag_strength_tesla(50, 10) * 1e9, 49136, 145 + 491); - EXPECT_NEAR(get_mag_strength_tesla(50, 15) * 1e9, 49465, 145 + 495); - EXPECT_NEAR(get_mag_strength_tesla(50, 20) * 1e9, 49840, 145 + 498); - EXPECT_NEAR(get_mag_strength_tesla(50, 25) * 1e9, 50269, 145 + 503); - EXPECT_NEAR(get_mag_strength_tesla(50, 30) * 1e9, 50760, 145 + 508); - EXPECT_NEAR(get_mag_strength_tesla(50, 35) * 1e9, 51320, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(50, 40) * 1e9, 51958, 145 + 520); - EXPECT_NEAR(get_mag_strength_tesla(50, 45) * 1e9, 52673, 145 + 527); - EXPECT_NEAR(get_mag_strength_tesla(50, 50) * 1e9, 53463, 145 + 535); - EXPECT_NEAR(get_mag_strength_tesla(50, 55) * 1e9, 54319, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(50, 60) * 1e9, 55223, 145 + 552); - EXPECT_NEAR(get_mag_strength_tesla(50, 65) * 1e9, 56150, 145 + 562); - EXPECT_NEAR(get_mag_strength_tesla(50, 70) * 1e9, 57069, 145 + 571); - EXPECT_NEAR(get_mag_strength_tesla(50, 75) * 1e9, 57941, 145 + 579); - EXPECT_NEAR(get_mag_strength_tesla(50, 80) * 1e9, 58727, 145 + 587); - EXPECT_NEAR(get_mag_strength_tesla(50, 85) * 1e9, 59388, 145 + 594); - EXPECT_NEAR(get_mag_strength_tesla(50, 90) * 1e9, 59889, 145 + 599); - EXPECT_NEAR(get_mag_strength_tesla(50, 95) * 1e9, 60201, 145 + 602); - EXPECT_NEAR(get_mag_strength_tesla(50, 100) * 1e9, 60303, 145 + 603); - EXPECT_NEAR(get_mag_strength_tesla(50, 105) * 1e9, 60182, 145 + 602); - EXPECT_NEAR(get_mag_strength_tesla(50, 110) * 1e9, 59835, 145 + 598); - EXPECT_NEAR(get_mag_strength_tesla(50, 115) * 1e9, 59272, 145 + 593); - EXPECT_NEAR(get_mag_strength_tesla(50, 120) * 1e9, 58514, 145 + 585); - EXPECT_NEAR(get_mag_strength_tesla(50, 125) * 1e9, 57595, 145 + 576); - EXPECT_NEAR(get_mag_strength_tesla(50, 130) * 1e9, 56557, 145 + 566); - EXPECT_NEAR(get_mag_strength_tesla(50, 135) * 1e9, 55450, 145 + 555); - EXPECT_NEAR(get_mag_strength_tesla(50, 140) * 1e9, 54323, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(50, 145) * 1e9, 53220, 145 + 532); - EXPECT_NEAR(get_mag_strength_tesla(50, 150) * 1e9, 52178, 145 + 522); - EXPECT_NEAR(get_mag_strength_tesla(50, 155) * 1e9, 51224, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(50, 160) * 1e9, 50378, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(50, 165) * 1e9, 49655, 145 + 497); - EXPECT_NEAR(get_mag_strength_tesla(50, 170) * 1e9, 49065, 145 + 491); - EXPECT_NEAR(get_mag_strength_tesla(50, 175) * 1e9, 48617, 145 + 486); - EXPECT_NEAR(get_mag_strength_tesla(50, 180) * 1e9, 48320, 145 + 483); - EXPECT_NEAR(get_mag_strength_tesla(55, -180) * 1e9, 51313, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(55, -175) * 1e9, 51175, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(55, -170) * 1e9, 51173, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(55, -165) * 1e9, 51305, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(55, -160) * 1e9, 51566, 145 + 516); - EXPECT_NEAR(get_mag_strength_tesla(55, -155) * 1e9, 51944, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(55, -150) * 1e9, 52423, 145 + 524); - EXPECT_NEAR(get_mag_strength_tesla(55, -145) * 1e9, 52982, 145 + 530); - EXPECT_NEAR(get_mag_strength_tesla(55, -140) * 1e9, 53595, 145 + 536); - EXPECT_NEAR(get_mag_strength_tesla(55, -135) * 1e9, 54237, 145 + 542); - EXPECT_NEAR(get_mag_strength_tesla(55, -130) * 1e9, 54883, 145 + 549); - EXPECT_NEAR(get_mag_strength_tesla(55, -125) * 1e9, 55509, 145 + 555); - EXPECT_NEAR(get_mag_strength_tesla(55, -120) * 1e9, 56092, 145 + 561); - EXPECT_NEAR(get_mag_strength_tesla(55, -115) * 1e9, 56612, 145 + 566); - EXPECT_NEAR(get_mag_strength_tesla(55, -110) * 1e9, 57048, 145 + 570); - EXPECT_NEAR(get_mag_strength_tesla(55, -105) * 1e9, 57382, 145 + 574); - EXPECT_NEAR(get_mag_strength_tesla(55, -100) * 1e9, 57596, 145 + 576); - EXPECT_NEAR(get_mag_strength_tesla(55, -95) * 1e9, 57675, 145 + 577); - EXPECT_NEAR(get_mag_strength_tesla(55, -90) * 1e9, 57608, 145 + 576); - EXPECT_NEAR(get_mag_strength_tesla(55, -85) * 1e9, 57391, 145 + 574); - EXPECT_NEAR(get_mag_strength_tesla(55, -80) * 1e9, 57029, 145 + 570); - EXPECT_NEAR(get_mag_strength_tesla(55, -75) * 1e9, 56534, 145 + 565); - EXPECT_NEAR(get_mag_strength_tesla(55, -70) * 1e9, 55930, 145 + 559); - EXPECT_NEAR(get_mag_strength_tesla(55, -65) * 1e9, 55246, 145 + 552); - EXPECT_NEAR(get_mag_strength_tesla(55, -60) * 1e9, 54515, 145 + 545); - EXPECT_NEAR(get_mag_strength_tesla(55, -55) * 1e9, 53771, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(55, -50) * 1e9, 53044, 145 + 530); - EXPECT_NEAR(get_mag_strength_tesla(55, -45) * 1e9, 52362, 145 + 524); - EXPECT_NEAR(get_mag_strength_tesla(55, -40) * 1e9, 51744, 145 + 517); + EXPECT_NEAR(get_mag_strength_tesla(50, -25) * 1e9, 48662, 145 + 487); + EXPECT_NEAR(get_mag_strength_tesla(50, -20) * 1e9, 48458, 145 + 485); + EXPECT_NEAR(get_mag_strength_tesla(50, -15) * 1e9, 48362, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(50, -10) * 1e9, 48367, 145 + 484); + EXPECT_NEAR(get_mag_strength_tesla(50, -5) * 1e9, 48463, 145 + 485); + EXPECT_NEAR(get_mag_strength_tesla(50, 0) * 1e9, 48634, 145 + 486); + EXPECT_NEAR(get_mag_strength_tesla(50, 5) * 1e9, 48868, 145 + 489); + EXPECT_NEAR(get_mag_strength_tesla(50, 10) * 1e9, 49154, 145 + 492); + EXPECT_NEAR(get_mag_strength_tesla(50, 15) * 1e9, 49484, 145 + 495); + EXPECT_NEAR(get_mag_strength_tesla(50, 20) * 1e9, 49862, 145 + 499); + EXPECT_NEAR(get_mag_strength_tesla(50, 25) * 1e9, 50292, 145 + 503); + EXPECT_NEAR(get_mag_strength_tesla(50, 30) * 1e9, 50783, 145 + 508); + EXPECT_NEAR(get_mag_strength_tesla(50, 35) * 1e9, 51345, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(50, 40) * 1e9, 51983, 145 + 520); + EXPECT_NEAR(get_mag_strength_tesla(50, 45) * 1e9, 52699, 145 + 527); + EXPECT_NEAR(get_mag_strength_tesla(50, 50) * 1e9, 53490, 145 + 535); + EXPECT_NEAR(get_mag_strength_tesla(50, 55) * 1e9, 54346, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(50, 60) * 1e9, 55251, 145 + 553); + EXPECT_NEAR(get_mag_strength_tesla(50, 65) * 1e9, 56179, 145 + 562); + EXPECT_NEAR(get_mag_strength_tesla(50, 70) * 1e9, 57098, 145 + 571); + EXPECT_NEAR(get_mag_strength_tesla(50, 75) * 1e9, 57970, 145 + 580); + EXPECT_NEAR(get_mag_strength_tesla(50, 80) * 1e9, 58755, 145 + 588); + EXPECT_NEAR(get_mag_strength_tesla(50, 85) * 1e9, 59414, 145 + 594); + EXPECT_NEAR(get_mag_strength_tesla(50, 90) * 1e9, 59913, 145 + 599); + EXPECT_NEAR(get_mag_strength_tesla(50, 95) * 1e9, 60222, 145 + 602); + EXPECT_NEAR(get_mag_strength_tesla(50, 100) * 1e9, 60320, 145 + 603); + EXPECT_NEAR(get_mag_strength_tesla(50, 105) * 1e9, 60196, 145 + 602); + EXPECT_NEAR(get_mag_strength_tesla(50, 110) * 1e9, 59846, 145 + 598); + EXPECT_NEAR(get_mag_strength_tesla(50, 115) * 1e9, 59281, 145 + 593); + EXPECT_NEAR(get_mag_strength_tesla(50, 120) * 1e9, 58522, 145 + 585); + EXPECT_NEAR(get_mag_strength_tesla(50, 125) * 1e9, 57602, 145 + 576); + EXPECT_NEAR(get_mag_strength_tesla(50, 130) * 1e9, 56565, 145 + 566); + EXPECT_NEAR(get_mag_strength_tesla(50, 135) * 1e9, 55459, 145 + 555); + EXPECT_NEAR(get_mag_strength_tesla(50, 140) * 1e9, 54334, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(50, 145) * 1e9, 53232, 145 + 532); + EXPECT_NEAR(get_mag_strength_tesla(50, 150) * 1e9, 52191, 145 + 522); + EXPECT_NEAR(get_mag_strength_tesla(50, 155) * 1e9, 51238, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(50, 160) * 1e9, 50392, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(50, 165) * 1e9, 49667, 145 + 497); + EXPECT_NEAR(get_mag_strength_tesla(50, 170) * 1e9, 49074, 145 + 491); + EXPECT_NEAR(get_mag_strength_tesla(50, 175) * 1e9, 48622, 145 + 486); + EXPECT_NEAR(get_mag_strength_tesla(50, 180) * 1e9, 48321, 145 + 483); + EXPECT_NEAR(get_mag_strength_tesla(55, -180) * 1e9, 51314, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(55, -175) * 1e9, 51171, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(55, -170) * 1e9, 51163, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(55, -165) * 1e9, 51290, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(55, -160) * 1e9, 51546, 145 + 515); + EXPECT_NEAR(get_mag_strength_tesla(55, -155) * 1e9, 51920, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(55, -150) * 1e9, 52396, 145 + 524); + EXPECT_NEAR(get_mag_strength_tesla(55, -145) * 1e9, 52951, 145 + 530); + EXPECT_NEAR(get_mag_strength_tesla(55, -140) * 1e9, 53562, 145 + 536); + EXPECT_NEAR(get_mag_strength_tesla(55, -135) * 1e9, 54203, 145 + 542); + EXPECT_NEAR(get_mag_strength_tesla(55, -130) * 1e9, 54848, 145 + 548); + EXPECT_NEAR(get_mag_strength_tesla(55, -125) * 1e9, 55474, 145 + 555); + EXPECT_NEAR(get_mag_strength_tesla(55, -120) * 1e9, 56058, 145 + 561); + EXPECT_NEAR(get_mag_strength_tesla(55, -115) * 1e9, 56578, 145 + 566); + EXPECT_NEAR(get_mag_strength_tesla(55, -110) * 1e9, 57016, 145 + 570); + EXPECT_NEAR(get_mag_strength_tesla(55, -105) * 1e9, 57352, 145 + 574); + EXPECT_NEAR(get_mag_strength_tesla(55, -100) * 1e9, 57568, 145 + 576); + EXPECT_NEAR(get_mag_strength_tesla(55, -95) * 1e9, 57648, 145 + 576); + EXPECT_NEAR(get_mag_strength_tesla(55, -90) * 1e9, 57583, 145 + 576); + EXPECT_NEAR(get_mag_strength_tesla(55, -85) * 1e9, 57368, 145 + 574); + EXPECT_NEAR(get_mag_strength_tesla(55, -80) * 1e9, 57008, 145 + 570); + EXPECT_NEAR(get_mag_strength_tesla(55, -75) * 1e9, 56515, 145 + 565); + EXPECT_NEAR(get_mag_strength_tesla(55, -70) * 1e9, 55914, 145 + 559); + EXPECT_NEAR(get_mag_strength_tesla(55, -65) * 1e9, 55232, 145 + 552); + EXPECT_NEAR(get_mag_strength_tesla(55, -60) * 1e9, 54503, 145 + 545); + EXPECT_NEAR(get_mag_strength_tesla(55, -55) * 1e9, 53761, 145 + 538); + EXPECT_NEAR(get_mag_strength_tesla(55, -50) * 1e9, 53037, 145 + 530); + EXPECT_NEAR(get_mag_strength_tesla(55, -45) * 1e9, 52357, 145 + 524); + EXPECT_NEAR(get_mag_strength_tesla(55, -40) * 1e9, 51741, 145 + 517); EXPECT_NEAR(get_mag_strength_tesla(55, -35) * 1e9, 51204, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(55, -30) * 1e9, 50752, 145 + 508); - EXPECT_NEAR(get_mag_strength_tesla(55, -25) * 1e9, 50394, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(55, -20) * 1e9, 50133, 145 + 501); - EXPECT_NEAR(get_mag_strength_tesla(55, -15) * 1e9, 49967, 145 + 500); - EXPECT_NEAR(get_mag_strength_tesla(55, -10) * 1e9, 49893, 145 + 499); - EXPECT_NEAR(get_mag_strength_tesla(55, -5) * 1e9, 49906, 145 + 499); - EXPECT_NEAR(get_mag_strength_tesla(55, 0) * 1e9, 49996, 145 + 500); - EXPECT_NEAR(get_mag_strength_tesla(55, 5) * 1e9, 50157, 145 + 502); - EXPECT_NEAR(get_mag_strength_tesla(55, 10) * 1e9, 50381, 145 + 504); - EXPECT_NEAR(get_mag_strength_tesla(55, 15) * 1e9, 50666, 145 + 507); - EXPECT_NEAR(get_mag_strength_tesla(55, 20) * 1e9, 51014, 145 + 510); - EXPECT_NEAR(get_mag_strength_tesla(55, 25) * 1e9, 51428, 145 + 514); - EXPECT_NEAR(get_mag_strength_tesla(55, 30) * 1e9, 51916, 145 + 519); - EXPECT_NEAR(get_mag_strength_tesla(55, 35) * 1e9, 52482, 145 + 525); - EXPECT_NEAR(get_mag_strength_tesla(55, 40) * 1e9, 53130, 145 + 531); - EXPECT_NEAR(get_mag_strength_tesla(55, 45) * 1e9, 53859, 145 + 539); - EXPECT_NEAR(get_mag_strength_tesla(55, 50) * 1e9, 54662, 145 + 547); - EXPECT_NEAR(get_mag_strength_tesla(55, 55) * 1e9, 55525, 145 + 555); - EXPECT_NEAR(get_mag_strength_tesla(55, 60) * 1e9, 56428, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(55, 65) * 1e9, 57346, 145 + 573); - EXPECT_NEAR(get_mag_strength_tesla(55, 70) * 1e9, 58245, 145 + 582); - EXPECT_NEAR(get_mag_strength_tesla(55, 75) * 1e9, 59091, 145 + 591); - EXPECT_NEAR(get_mag_strength_tesla(55, 80) * 1e9, 59848, 145 + 598); - EXPECT_NEAR(get_mag_strength_tesla(55, 85) * 1e9, 60482, 145 + 605); - EXPECT_NEAR(get_mag_strength_tesla(55, 90) * 1e9, 60963, 145 + 610); - EXPECT_NEAR(get_mag_strength_tesla(55, 95) * 1e9, 61268, 145 + 613); - EXPECT_NEAR(get_mag_strength_tesla(55, 100) * 1e9, 61382, 145 + 614); - EXPECT_NEAR(get_mag_strength_tesla(55, 105) * 1e9, 61296, 145 + 613); - EXPECT_NEAR(get_mag_strength_tesla(55, 110) * 1e9, 61013, 145 + 610); - EXPECT_NEAR(get_mag_strength_tesla(55, 115) * 1e9, 60546, 145 + 605); - EXPECT_NEAR(get_mag_strength_tesla(55, 120) * 1e9, 59915, 145 + 599); - EXPECT_NEAR(get_mag_strength_tesla(55, 125) * 1e9, 59151, 145 + 592); - EXPECT_NEAR(get_mag_strength_tesla(55, 130) * 1e9, 58290, 145 + 583); - EXPECT_NEAR(get_mag_strength_tesla(55, 135) * 1e9, 57371, 145 + 574); - EXPECT_NEAR(get_mag_strength_tesla(55, 140) * 1e9, 56433, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(55, 145) * 1e9, 55512, 145 + 555); - EXPECT_NEAR(get_mag_strength_tesla(55, 150) * 1e9, 54636, 145 + 546); - EXPECT_NEAR(get_mag_strength_tesla(55, 155) * 1e9, 53830, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(55, 160) * 1e9, 53110, 145 + 531); - EXPECT_NEAR(get_mag_strength_tesla(55, 165) * 1e9, 52488, 145 + 525); - EXPECT_NEAR(get_mag_strength_tesla(55, 170) * 1e9, 51976, 145 + 520); - EXPECT_NEAR(get_mag_strength_tesla(55, 175) * 1e9, 51582, 145 + 516); - EXPECT_NEAR(get_mag_strength_tesla(55, 180) * 1e9, 51313, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(60, -180) * 1e9, 53927, 145 + 539); - EXPECT_NEAR(get_mag_strength_tesla(60, -175) * 1e9, 53791, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(60, -170) * 1e9, 53758, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(60, -165) * 1e9, 53828, 145 + 538); - EXPECT_NEAR(get_mag_strength_tesla(60, -160) * 1e9, 53996, 145 + 540); - EXPECT_NEAR(get_mag_strength_tesla(60, -155) * 1e9, 54255, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(60, -150) * 1e9, 54591, 145 + 546); - EXPECT_NEAR(get_mag_strength_tesla(60, -145) * 1e9, 54988, 145 + 550); - EXPECT_NEAR(get_mag_strength_tesla(60, -140) * 1e9, 55430, 145 + 554); - EXPECT_NEAR(get_mag_strength_tesla(60, -135) * 1e9, 55896, 145 + 559); - EXPECT_NEAR(get_mag_strength_tesla(60, -130) * 1e9, 56365, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(60, -125) * 1e9, 56820, 145 + 568); - EXPECT_NEAR(get_mag_strength_tesla(60, -120) * 1e9, 57241, 145 + 572); - EXPECT_NEAR(get_mag_strength_tesla(60, -115) * 1e9, 57612, 145 + 576); - EXPECT_NEAR(get_mag_strength_tesla(60, -110) * 1e9, 57916, 145 + 579); - EXPECT_NEAR(get_mag_strength_tesla(60, -105) * 1e9, 58139, 145 + 581); - EXPECT_NEAR(get_mag_strength_tesla(60, -100) * 1e9, 58266, 145 + 583); - EXPECT_NEAR(get_mag_strength_tesla(60, -95) * 1e9, 58288, 145 + 583); - EXPECT_NEAR(get_mag_strength_tesla(60, -90) * 1e9, 58198, 145 + 582); - EXPECT_NEAR(get_mag_strength_tesla(60, -85) * 1e9, 57993, 145 + 580); - EXPECT_NEAR(get_mag_strength_tesla(60, -80) * 1e9, 57676, 145 + 577); - EXPECT_NEAR(get_mag_strength_tesla(60, -75) * 1e9, 57258, 145 + 573); - EXPECT_NEAR(get_mag_strength_tesla(60, -70) * 1e9, 56752, 145 + 568); - EXPECT_NEAR(get_mag_strength_tesla(60, -65) * 1e9, 56180, 145 + 562); - EXPECT_NEAR(get_mag_strength_tesla(60, -60) * 1e9, 55564, 145 + 556); - EXPECT_NEAR(get_mag_strength_tesla(60, -55) * 1e9, 54928, 145 + 549); - EXPECT_NEAR(get_mag_strength_tesla(60, -50) * 1e9, 54297, 145 + 543); - EXPECT_NEAR(get_mag_strength_tesla(60, -45) * 1e9, 53690, 145 + 537); + EXPECT_NEAR(get_mag_strength_tesla(55, -30) * 1e9, 50754, 145 + 508); + EXPECT_NEAR(get_mag_strength_tesla(55, -25) * 1e9, 50399, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(55, -20) * 1e9, 50139, 145 + 501); + EXPECT_NEAR(get_mag_strength_tesla(55, -15) * 1e9, 49976, 145 + 500); + EXPECT_NEAR(get_mag_strength_tesla(55, -10) * 1e9, 49904, 145 + 499); + EXPECT_NEAR(get_mag_strength_tesla(55, -5) * 1e9, 49918, 145 + 499); + EXPECT_NEAR(get_mag_strength_tesla(55, 0) * 1e9, 50011, 145 + 500); + EXPECT_NEAR(get_mag_strength_tesla(55, 5) * 1e9, 50172, 145 + 502); + EXPECT_NEAR(get_mag_strength_tesla(55, 10) * 1e9, 50398, 145 + 504); + EXPECT_NEAR(get_mag_strength_tesla(55, 15) * 1e9, 50685, 145 + 507); + EXPECT_NEAR(get_mag_strength_tesla(55, 20) * 1e9, 51034, 145 + 510); + EXPECT_NEAR(get_mag_strength_tesla(55, 25) * 1e9, 51450, 145 + 514); + EXPECT_NEAR(get_mag_strength_tesla(55, 30) * 1e9, 51939, 145 + 519); + EXPECT_NEAR(get_mag_strength_tesla(55, 35) * 1e9, 52506, 145 + 525); + EXPECT_NEAR(get_mag_strength_tesla(55, 40) * 1e9, 53155, 145 + 532); + EXPECT_NEAR(get_mag_strength_tesla(55, 45) * 1e9, 53885, 145 + 539); + EXPECT_NEAR(get_mag_strength_tesla(55, 50) * 1e9, 54688, 145 + 547); + EXPECT_NEAR(get_mag_strength_tesla(55, 55) * 1e9, 55552, 145 + 556); + EXPECT_NEAR(get_mag_strength_tesla(55, 60) * 1e9, 56456, 145 + 565); + EXPECT_NEAR(get_mag_strength_tesla(55, 65) * 1e9, 57373, 145 + 574); + EXPECT_NEAR(get_mag_strength_tesla(55, 70) * 1e9, 58272, 145 + 583); + EXPECT_NEAR(get_mag_strength_tesla(55, 75) * 1e9, 59117, 145 + 591); + EXPECT_NEAR(get_mag_strength_tesla(55, 80) * 1e9, 59872, 145 + 599); + EXPECT_NEAR(get_mag_strength_tesla(55, 85) * 1e9, 60504, 145 + 605); + EXPECT_NEAR(get_mag_strength_tesla(55, 90) * 1e9, 60983, 145 + 610); + EXPECT_NEAR(get_mag_strength_tesla(55, 95) * 1e9, 61285, 145 + 613); + EXPECT_NEAR(get_mag_strength_tesla(55, 100) * 1e9, 61395, 145 + 614); + EXPECT_NEAR(get_mag_strength_tesla(55, 105) * 1e9, 61306, 145 + 613); + EXPECT_NEAR(get_mag_strength_tesla(55, 110) * 1e9, 61022, 145 + 610); + EXPECT_NEAR(get_mag_strength_tesla(55, 115) * 1e9, 60553, 145 + 606); + EXPECT_NEAR(get_mag_strength_tesla(55, 120) * 1e9, 59921, 145 + 599); + EXPECT_NEAR(get_mag_strength_tesla(55, 125) * 1e9, 59158, 145 + 592); + EXPECT_NEAR(get_mag_strength_tesla(55, 130) * 1e9, 58298, 145 + 583); + EXPECT_NEAR(get_mag_strength_tesla(55, 135) * 1e9, 57380, 145 + 574); + EXPECT_NEAR(get_mag_strength_tesla(55, 140) * 1e9, 56444, 145 + 564); + EXPECT_NEAR(get_mag_strength_tesla(55, 145) * 1e9, 55525, 145 + 555); + EXPECT_NEAR(get_mag_strength_tesla(55, 150) * 1e9, 54651, 145 + 547); + EXPECT_NEAR(get_mag_strength_tesla(55, 155) * 1e9, 53845, 145 + 538); + EXPECT_NEAR(get_mag_strength_tesla(55, 160) * 1e9, 53124, 145 + 531); + EXPECT_NEAR(get_mag_strength_tesla(55, 165) * 1e9, 52501, 145 + 525); + EXPECT_NEAR(get_mag_strength_tesla(55, 170) * 1e9, 51986, 145 + 520); + EXPECT_NEAR(get_mag_strength_tesla(55, 175) * 1e9, 51588, 145 + 516); + EXPECT_NEAR(get_mag_strength_tesla(55, 180) * 1e9, 51314, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(60, -180) * 1e9, 53929, 145 + 539); + EXPECT_NEAR(get_mag_strength_tesla(60, -175) * 1e9, 53787, 145 + 538); + EXPECT_NEAR(get_mag_strength_tesla(60, -170) * 1e9, 53749, 145 + 537); + EXPECT_NEAR(get_mag_strength_tesla(60, -165) * 1e9, 53814, 145 + 538); + EXPECT_NEAR(get_mag_strength_tesla(60, -160) * 1e9, 53978, 145 + 540); + EXPECT_NEAR(get_mag_strength_tesla(60, -155) * 1e9, 54232, 145 + 542); + EXPECT_NEAR(get_mag_strength_tesla(60, -150) * 1e9, 54564, 145 + 546); + EXPECT_NEAR(get_mag_strength_tesla(60, -145) * 1e9, 54959, 145 + 550); + EXPECT_NEAR(get_mag_strength_tesla(60, -140) * 1e9, 55398, 145 + 554); + EXPECT_NEAR(get_mag_strength_tesla(60, -135) * 1e9, 55863, 145 + 559); + EXPECT_NEAR(get_mag_strength_tesla(60, -130) * 1e9, 56332, 145 + 563); + EXPECT_NEAR(get_mag_strength_tesla(60, -125) * 1e9, 56788, 145 + 568); + EXPECT_NEAR(get_mag_strength_tesla(60, -120) * 1e9, 57210, 145 + 572); + EXPECT_NEAR(get_mag_strength_tesla(60, -115) * 1e9, 57582, 145 + 576); + EXPECT_NEAR(get_mag_strength_tesla(60, -110) * 1e9, 57888, 145 + 579); + EXPECT_NEAR(get_mag_strength_tesla(60, -105) * 1e9, 58112, 145 + 581); + EXPECT_NEAR(get_mag_strength_tesla(60, -100) * 1e9, 58242, 145 + 582); + EXPECT_NEAR(get_mag_strength_tesla(60, -95) * 1e9, 58266, 145 + 583); + EXPECT_NEAR(get_mag_strength_tesla(60, -90) * 1e9, 58178, 145 + 582); + EXPECT_NEAR(get_mag_strength_tesla(60, -85) * 1e9, 57975, 145 + 580); + EXPECT_NEAR(get_mag_strength_tesla(60, -80) * 1e9, 57660, 145 + 577); + EXPECT_NEAR(get_mag_strength_tesla(60, -75) * 1e9, 57244, 145 + 572); + EXPECT_NEAR(get_mag_strength_tesla(60, -70) * 1e9, 56741, 145 + 567); + EXPECT_NEAR(get_mag_strength_tesla(60, -65) * 1e9, 56171, 145 + 562); + EXPECT_NEAR(get_mag_strength_tesla(60, -60) * 1e9, 55557, 145 + 556); + EXPECT_NEAR(get_mag_strength_tesla(60, -55) * 1e9, 54923, 145 + 549); + EXPECT_NEAR(get_mag_strength_tesla(60, -50) * 1e9, 54293, 145 + 543); + EXPECT_NEAR(get_mag_strength_tesla(60, -45) * 1e9, 53688, 145 + 537); EXPECT_NEAR(get_mag_strength_tesla(60, -40) * 1e9, 53125, 145 + 531); - EXPECT_NEAR(get_mag_strength_tesla(60, -35) * 1e9, 52617, 145 + 526); - EXPECT_NEAR(get_mag_strength_tesla(60, -30) * 1e9, 52177, 145 + 522); - EXPECT_NEAR(get_mag_strength_tesla(60, -25) * 1e9, 51812, 145 + 518); - EXPECT_NEAR(get_mag_strength_tesla(60, -20) * 1e9, 51526, 145 + 515); - EXPECT_NEAR(get_mag_strength_tesla(60, -15) * 1e9, 51322, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(60, -10) * 1e9, 51200, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(60, -5) * 1e9, 51158, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(60, 0) * 1e9, 51192, 145 + 512); - EXPECT_NEAR(get_mag_strength_tesla(60, 5) * 1e9, 51300, 145 + 513); - EXPECT_NEAR(get_mag_strength_tesla(60, 10) * 1e9, 51480, 145 + 515); - EXPECT_NEAR(get_mag_strength_tesla(60, 15) * 1e9, 51731, 145 + 517); - EXPECT_NEAR(get_mag_strength_tesla(60, 20) * 1e9, 52054, 145 + 521); - EXPECT_NEAR(get_mag_strength_tesla(60, 25) * 1e9, 52452, 145 + 525); - EXPECT_NEAR(get_mag_strength_tesla(60, 30) * 1e9, 52927, 145 + 529); - EXPECT_NEAR(get_mag_strength_tesla(60, 35) * 1e9, 53482, 145 + 535); - EXPECT_NEAR(get_mag_strength_tesla(60, 40) * 1e9, 54115, 145 + 541); - EXPECT_NEAR(get_mag_strength_tesla(60, 45) * 1e9, 54822, 145 + 548); - EXPECT_NEAR(get_mag_strength_tesla(60, 50) * 1e9, 55592, 145 + 556); - EXPECT_NEAR(get_mag_strength_tesla(60, 55) * 1e9, 56411, 145 + 564); - EXPECT_NEAR(get_mag_strength_tesla(60, 60) * 1e9, 57259, 145 + 573); - EXPECT_NEAR(get_mag_strength_tesla(60, 65) * 1e9, 58110, 145 + 581); - EXPECT_NEAR(get_mag_strength_tesla(60, 70) * 1e9, 58937, 145 + 589); - EXPECT_NEAR(get_mag_strength_tesla(60, 75) * 1e9, 59709, 145 + 597); - EXPECT_NEAR(get_mag_strength_tesla(60, 80) * 1e9, 60397, 145 + 604); - EXPECT_NEAR(get_mag_strength_tesla(60, 85) * 1e9, 60974, 145 + 610); - EXPECT_NEAR(get_mag_strength_tesla(60, 90) * 1e9, 61417, 145 + 614); - EXPECT_NEAR(get_mag_strength_tesla(60, 95) * 1e9, 61707, 145 + 617); - EXPECT_NEAR(get_mag_strength_tesla(60, 100) * 1e9, 61834, 145 + 618); - EXPECT_NEAR(get_mag_strength_tesla(60, 105) * 1e9, 61796, 145 + 618); - EXPECT_NEAR(get_mag_strength_tesla(60, 110) * 1e9, 61596, 145 + 616); - EXPECT_NEAR(get_mag_strength_tesla(60, 115) * 1e9, 61246, 145 + 612); - EXPECT_NEAR(get_mag_strength_tesla(60, 120) * 1e9, 60766, 145 + 608); - EXPECT_NEAR(get_mag_strength_tesla(60, 125) * 1e9, 60179, 145 + 602); - EXPECT_NEAR(get_mag_strength_tesla(60, 130) * 1e9, 59515, 145 + 595); - EXPECT_NEAR(get_mag_strength_tesla(60, 135) * 1e9, 58802, 145 + 588); - EXPECT_NEAR(get_mag_strength_tesla(60, 140) * 1e9, 58070, 145 + 581); - EXPECT_NEAR(get_mag_strength_tesla(60, 145) * 1e9, 57346, 145 + 573); - EXPECT_NEAR(get_mag_strength_tesla(60, 150) * 1e9, 56653, 145 + 567); - EXPECT_NEAR(get_mag_strength_tesla(60, 155) * 1e9, 56009, 145 + 560); - EXPECT_NEAR(get_mag_strength_tesla(60, 160) * 1e9, 55428, 145 + 554); - EXPECT_NEAR(get_mag_strength_tesla(60, 165) * 1e9, 54921, 145 + 549); - EXPECT_NEAR(get_mag_strength_tesla(60, 170) * 1e9, 54497, 145 + 545); - EXPECT_NEAR(get_mag_strength_tesla(60, 175) * 1e9, 54164, 145 + 542); - EXPECT_NEAR(get_mag_strength_tesla(60, 180) * 1e9, 53927, 145 + 539); + EXPECT_NEAR(get_mag_strength_tesla(60, -35) * 1e9, 52620, 145 + 526); + EXPECT_NEAR(get_mag_strength_tesla(60, -30) * 1e9, 52181, 145 + 522); + EXPECT_NEAR(get_mag_strength_tesla(60, -25) * 1e9, 51818, 145 + 518); + EXPECT_NEAR(get_mag_strength_tesla(60, -20) * 1e9, 51534, 145 + 515); + EXPECT_NEAR(get_mag_strength_tesla(60, -15) * 1e9, 51332, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(60, -10) * 1e9, 51211, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(60, -5) * 1e9, 51170, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(60, 0) * 1e9, 51206, 145 + 512); + EXPECT_NEAR(get_mag_strength_tesla(60, 5) * 1e9, 51316, 145 + 513); + EXPECT_NEAR(get_mag_strength_tesla(60, 10) * 1e9, 51496, 145 + 515); + EXPECT_NEAR(get_mag_strength_tesla(60, 15) * 1e9, 51748, 145 + 517); + EXPECT_NEAR(get_mag_strength_tesla(60, 20) * 1e9, 52073, 145 + 521); + EXPECT_NEAR(get_mag_strength_tesla(60, 25) * 1e9, 52472, 145 + 525); + EXPECT_NEAR(get_mag_strength_tesla(60, 30) * 1e9, 52949, 145 + 529); + EXPECT_NEAR(get_mag_strength_tesla(60, 35) * 1e9, 53505, 145 + 535); + EXPECT_NEAR(get_mag_strength_tesla(60, 40) * 1e9, 54139, 145 + 541); + EXPECT_NEAR(get_mag_strength_tesla(60, 45) * 1e9, 54846, 145 + 548); + EXPECT_NEAR(get_mag_strength_tesla(60, 50) * 1e9, 55617, 145 + 556); + EXPECT_NEAR(get_mag_strength_tesla(60, 55) * 1e9, 56437, 145 + 564); + EXPECT_NEAR(get_mag_strength_tesla(60, 60) * 1e9, 57284, 145 + 573); + EXPECT_NEAR(get_mag_strength_tesla(60, 65) * 1e9, 58136, 145 + 581); + EXPECT_NEAR(get_mag_strength_tesla(60, 70) * 1e9, 58961, 145 + 590); + EXPECT_NEAR(get_mag_strength_tesla(60, 75) * 1e9, 59732, 145 + 597); + EXPECT_NEAR(get_mag_strength_tesla(60, 80) * 1e9, 60419, 145 + 604); + EXPECT_NEAR(get_mag_strength_tesla(60, 85) * 1e9, 60993, 145 + 610); + EXPECT_NEAR(get_mag_strength_tesla(60, 90) * 1e9, 61433, 145 + 614); + EXPECT_NEAR(get_mag_strength_tesla(60, 95) * 1e9, 61720, 145 + 617); + EXPECT_NEAR(get_mag_strength_tesla(60, 100) * 1e9, 61846, 145 + 618); + EXPECT_NEAR(get_mag_strength_tesla(60, 105) * 1e9, 61805, 145 + 618); + EXPECT_NEAR(get_mag_strength_tesla(60, 110) * 1e9, 61603, 145 + 616); + EXPECT_NEAR(get_mag_strength_tesla(60, 115) * 1e9, 61253, 145 + 613); + EXPECT_NEAR(get_mag_strength_tesla(60, 120) * 1e9, 60772, 145 + 608); + EXPECT_NEAR(get_mag_strength_tesla(60, 125) * 1e9, 60186, 145 + 602); + EXPECT_NEAR(get_mag_strength_tesla(60, 130) * 1e9, 59523, 145 + 595); + EXPECT_NEAR(get_mag_strength_tesla(60, 135) * 1e9, 58812, 145 + 588); + EXPECT_NEAR(get_mag_strength_tesla(60, 140) * 1e9, 58082, 145 + 581); + EXPECT_NEAR(get_mag_strength_tesla(60, 145) * 1e9, 57360, 145 + 574); + EXPECT_NEAR(get_mag_strength_tesla(60, 150) * 1e9, 56668, 145 + 567); + EXPECT_NEAR(get_mag_strength_tesla(60, 155) * 1e9, 56024, 145 + 560); + EXPECT_NEAR(get_mag_strength_tesla(60, 160) * 1e9, 55442, 145 + 554); + EXPECT_NEAR(get_mag_strength_tesla(60, 165) * 1e9, 54934, 145 + 549); + EXPECT_NEAR(get_mag_strength_tesla(60, 170) * 1e9, 54507, 145 + 545); + EXPECT_NEAR(get_mag_strength_tesla(60, 175) * 1e9, 54170, 145 + 542); + EXPECT_NEAR(get_mag_strength_tesla(60, 180) * 1e9, 53929, 145 + 539); } 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 6d57f7ba8743..88fa6eb85faa 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.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,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 6590000,1,-0.0094,-0.011,0.00016,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,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 6690000,1,-0.0093,-0.011,9e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,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 -6790000,0.78,-0.024,0.005,-0.63,-0.22,-0.047,-0.11,-0.13,-0.028,-3.7e+02,-0.00035,-0.011,-0.0002,0,0,0.0012,-0.092,-0.02,0.51,-0.00079,-0.075,-0.061,0,0,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 -6890000,0.78,-0.025,0.0059,-0.63,-0.27,-0.062,-0.12,-0.16,-0.038,-3.7e+02,-0.00018,-0.011,-0.00022,0,0,0.0013,-0.1,-0.022,0.51,-0.0012,-0.083,-0.067,0,0,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00089,0.0014,0.0013,1,1 -6990000,0.78,-0.025,0.0061,-0.63,-0.3,-0.073,-0.12,-0.2,-0.048,-3.7e+02,-7.9e-05,-0.011,-0.00022,-0.00057,-6.5e-05,0.00098,-0.1,-0.022,0.5,-0.0016,-0.084,-0.067,0,0,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1 -7090000,0.78,-0.025,0.0064,-0.63,-0.33,-0.084,-0.12,-0.23,-0.06,-3.7e+02,3.5e-05,-0.011,-0.00023,-0.0013,-0.00028,0.00063,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00083,0.0014,0.0013,1,1 -7190000,0.78,-0.025,0.0066,-0.63,-0.36,-0.093,-0.15,-0.27,-0.071,-3.7e+02,0.0001,-0.011,-0.00023,-0.0017,-0.00044,0.00086,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00082,0.0013,0.0013,1,1 -7290000,0.78,-0.025,0.0068,-0.63,-0.38,-0.094,-0.14,-0.3,-0.078,-3.7e+02,4.4e-05,-0.011,-0.00022,-0.0016,-0.0004,0.00018,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1 -7390000,0.78,-0.024,0.007,-0.63,-0.41,-0.1,-0.16,-0.34,-0.089,-3.7e+02,6.5e-05,-0.011,-0.00022,-0.0017,-0.00044,2.8e-05,-0.1,-0.023,0.5,-0.0018,-0.085,-0.068,0,0,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00081,0.0013,0.0013,1,1 -7490000,0.78,-0.024,0.007,-0.63,-0.43,-0.11,-0.16,-0.38,-0.11,-3.7e+02,0.0002,-0.011,-0.00023,-0.0019,-0.00051,-0.00073,-0.1,-0.023,0.5,-0.0019,-0.085,-0.069,0,0,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1 -7590000,0.78,-0.024,0.0071,-0.63,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00019,-0.011,-0.00022,-0.0018,-0.00049,-0.0016,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1 -7690000,0.78,-0.024,0.0072,-0.63,0,0,-0.16,-0.46,-0.14,-3.7e+02,0.00028,-0.011,-0.00022,-0.002,-0.00046,-0.0036,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0013,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.0008,0.0013,0.0013,1,1 -7790000,0.78,-0.024,0.0074,-0.63,-0.028,-0.004,-0.16,-0.46,-0.14,-3.7e+02,0.00034,-0.011,-0.00023,-0.002,-0.00046,-0.0056,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00079,0.0013,0.0013,1,1 -7890000,0.78,-0.024,0.0074,-0.63,-0.053,-0.0088,-0.15,-0.46,-0.14,-3.7e+02,0.00038,-0.011,-0.00022,-0.002,-0.00046,-0.0081,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.11,1e+02,1e+02,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00079,0.0013,0.0013,1,1 -7990000,0.78,-0.024,0.0074,-0.63,-0.079,-0.013,-0.16,-0.47,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.002,-0.00046,-0.0093,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00079,0.0013,0.0013,1,1 -8090000,0.78,-0.024,0.0072,-0.63,-0.1,-0.018,-0.17,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.0095,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,52,52,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00079,0.0013,0.0013,1,1 -8190000,0.78,-0.024,0.0074,-0.63,-0.13,-0.021,-0.18,-0.48,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.012,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,25,0.099,35,35,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.4e-05,0.0013,0.00078,0.0013,0.0013,1,1 -8290000,0.78,-0.024,0.0074,-0.63,-0.15,-0.026,-0.17,-0.49,-0.14,-3.7e+02,0.00052,-0.01,-0.00021,-0.002,-0.00046,-0.016,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,25,25,0.097,37,37,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00078,0.0013,0.0013,1,1 -8390000,0.78,-0.024,0.0072,-0.63,-0.17,-0.031,-0.17,-0.5,-0.14,-3.7e+02,0.00054,-0.01,-0.00021,-0.002,-0.00046,-0.019,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.1e-05,0.0013,0.00078,0.0013,0.0013,1,1 -8490000,0.78,-0.023,0.0072,-0.63,-0.2,-0.036,-0.17,-0.51,-0.15,-3.7e+02,0.00055,-0.0099,-0.0002,-0.002,-0.00046,-0.024,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.096,31,31,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00077,0.0013,0.0013,1,1 -8590000,0.78,-0.023,0.0074,-0.63,-0.21,-0.033,-0.17,-0.52,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.002,-0.00046,-0.028,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.095,25,25,0.088,5.7e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.9e-05,0.0013,0.00077,0.0013,0.0013,1,1 -8690000,0.78,-0.023,0.007,-0.63,-0.23,-0.038,-0.16,-0.54,-0.15,-3.7e+02,0.00037,-0.0096,-0.00019,-0.002,-0.00046,-0.033,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,28,28,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.8e-05,0.0013,0.00077,0.0013,0.0013,1,1 -8790000,0.78,-0.023,0.0071,-0.63,-0.24,-0.041,-0.15,-0.54,-0.15,-3.7e+02,0.00039,-0.0095,-0.00019,-0.002,-0.00046,-0.039,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.096,24,24,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,7.7e-05,0.0013,0.00076,0.0013,0.0013,1,1 -8890000,0.78,-0.023,0.007,-0.63,-0.26,-0.045,-0.15,-0.56,-0.16,-3.7e+02,0.00039,-0.0094,-0.00018,-0.002,-0.00046,-0.043,-0.1,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.095,26,26,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0013,7.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 -8990000,0.78,-0.023,0.007,-0.63,-0.28,-0.05,-0.14,-0.59,-0.16,-3.7e+02,0.00044,-0.0093,-0.00018,-0.0021,-0.00036,-0.049,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.096,29,29,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0013,7.6e-05,0.0013,0.00075,0.0013,0.0013,1,1 -9090000,0.78,-0.022,0.007,-0.63,-0.3,-0.05,-0.14,-0.61,-0.17,-3.7e+02,0.00036,-0.0092,-0.00018,-0.0021,-0.00019,-0.052,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.095,33,33,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0013,7.5e-05,0.0013,0.00075,0.0013,0.0013,1,1 -9190000,0.77,-0.022,0.0063,-0.63,-0.3,-0.06,-0.14,-0.63,-0.18,-3.7e+02,0.00037,-0.0088,-0.00017,-0.0019,4e-05,-0.055,-0.11,-0.023,0.5,-0.0027,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.094,37,37,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,7.4e-05,0.0013,0.00074,0.0013,0.0013,1,1 -9290000,0.77,-0.022,0.006,-0.63,-0.32,-0.068,-0.14,-0.66,-0.19,-3.7e+02,0.0004,-0.0086,-0.00016,-0.002,0.00028,-0.059,-0.11,-0.023,0.5,-0.0028,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,41,41,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1 -9390000,0.77,-0.022,0.0059,-0.63,-0.34,-0.077,-0.13,-0.69,-0.2,-3.7e+02,0.00042,-0.0085,-0.00016,-0.0021,0.00046,-0.063,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,46,46,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1 -9490000,0.77,-0.022,0.0054,-0.63,-0.34,-0.09,-0.13,-0.71,-0.21,-3.7e+02,0.00045,-0.0082,-0.00015,-0.002,0.00072,-0.067,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.091,51,51,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1 -9590000,0.77,-0.022,0.0051,-0.63,-0.35,-0.089,-0.13,-0.73,-0.22,-3.7e+02,0.0003,-0.008,-0.00014,-0.002,0.001,-0.07,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0013,0.054,21,21,0.09,57,57,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1 -9690000,0.77,-0.022,0.0053,-0.63,-0.37,-0.086,-0.12,-0.77,-0.22,-3.7e+02,0.00022,-0.0081,-0.00014,-0.0022,0.0012,-0.075,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.089,63,63,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1 -9790000,0.77,-0.022,0.0049,-0.63,-0.37,-0.099,-0.11,-0.79,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0023,0.0016,-0.081,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.087,69,69,0.085,3.1e-05,3.4e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1 -9890000,0.77,-0.021,0.0047,-0.63,-0.38,-0.1,-0.11,-0.82,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0023,0.0018,-0.083,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,22,0.084,76,76,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7e-05,0.0013,0.00072,0.0013,0.0013,1,1 -9990000,0.77,-0.021,0.0047,-0.63,-0.4,-0.1,-0.1,-0.85,-0.25,-3.7e+02,9.4e-05,-0.0077,-0.00013,-0.0025,0.002,-0.087,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,22,22,0.083,83,83,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1 -10090000,0.77,-0.021,0.0044,-0.63,-0.4,-0.099,-0.096,-0.87,-0.26,-3.7e+02,-1.2e-05,-0.0075,-0.00012,-0.0025,0.0022,-0.09,-0.11,-0.023,0.5,-0.003,-0.088,-0.069,0,0,0.0011,0.0012,0.054,22,22,0.08,91,91,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1 -10190000,0.77,-0.021,0.0047,-0.63,-0.42,-0.097,-0.096,-0.92,-0.26,-3.7e+02,-4.4e-05,-0.0076,-0.00012,-0.0025,0.0022,-0.091,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.078,99,99,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,6.9e-05,0.0013,0.00071,0.0013,0.0013,1,1 -10290000,0.77,-0.021,0.0049,-0.63,-0.44,-0.096,-0.083,-0.96,-0.27,-3.7e+02,-7.1e-05,-0.0076,-0.00012,-0.0028,0.0025,-0.097,-0.11,-0.023,0.5,-0.0028,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.076,1.1e+02,1.1e+02,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10390000,0.77,-0.021,0.0047,-0.63,-0.0086,-0.022,0.0097,7.7e-05,-0.0019,-3.7e+02,-6e-05,-0.0075,-0.00012,-0.0028,0.0027,-0.1,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10490000,0.77,-0.021,0.0048,-0.63,-0.028,-0.024,0.023,-0.0017,-0.0042,-3.7e+02,-8.3e-05,-0.0075,-0.00012,-0.0029,0.0028,-0.1,-0.11,-0.024,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10590000,0.77,-0.02,0.0045,-0.63,-0.026,-0.013,0.026,0.0015,-0.0009,-3.7e+02,-0.00027,-0.0074,-0.00011,-0.0021,0.0027,-0.1,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10690000,0.77,-0.02,0.0044,-0.63,-0.043,-0.014,0.03,-0.002,-0.0023,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0021,0.0028,-0.11,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 -10790000,0.77,-0.02,0.004,-0.63,-0.04,-0.0098,0.024,0.001,-0.001,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00033,0.0016,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.001,0.001,0.054,0.091,0.092,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 -10890000,0.77,-0.02,0.0039,-0.63,-0.057,-0.012,0.02,-0.0037,-0.0022,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.00027,0.0017,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.00098,0.00098,0.053,0.099,0.1,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 -10990000,0.77,-0.02,0.0031,-0.63,-0.048,-0.0092,0.015,0.00014,-0.0011,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0035,-0.0006,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00093,0.00093,0.053,0.078,0.079,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.9e-05,0.0013,0.00069,0.0013,0.0013,1,1 -11090000,0.77,-0.02,0.0028,-0.63,-0.06,-0.013,0.02,-0.0047,-0.0024,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0035,-0.00017,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0013,1,1 -11190000,0.77,-0.019,0.0023,-0.63,-0.054,-0.0091,0.0082,0.0007,-0.00036,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.008,-0.0035,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00085,0.00085,0.053,0.073,0.074,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0013,1,1 -11290000,0.77,-0.019,0.0024,-0.63,-0.069,-0.011,0.008,-0.0057,-0.0014,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0081,-0.0036,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.069,0,0,0.00084,0.00084,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0013,1,1 -11390000,0.78,-0.019,0.002,-0.63,-0.064,-0.0096,0.0024,0.00035,-0.00029,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.068,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0012,1,1 -11490000,0.78,-0.019,0.0022,-0.63,-0.078,-0.011,0.0032,-0.0072,-0.0011,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.024,0.5,-0.0032,-0.089,-0.07,0,0,0.00075,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.8e-05,0.0013,0.00068,0.0013,0.0012,1,1 -11590000,0.78,-0.019,0.0017,-0.63,-0.069,-0.011,-0.0027,-0.0022,-0.00067,-3.7e+02,-0.0006,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0033,-0.089,-0.07,0,0,0.00067,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11690000,0.78,-0.019,0.0018,-0.63,-0.08,-0.014,-0.0071,-0.0098,-0.0021,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0034,-0.089,-0.07,0,0,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11790000,0.78,-0.019,0.0012,-0.63,-0.072,-0.0097,-0.0089,-0.0061,-4.1e-05,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.00061,0.051,0.065,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11890000,0.78,-0.019,0.0013,-0.63,-0.084,-0.01,-0.0098,-0.014,-0.001,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.0006,0.051,0.075,0.076,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.8e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11990000,0.78,-0.019,0.00071,-0.63,-0.072,-0.0052,-0.015,-0.009,0.0011,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00052,0.00053,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8.1e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.8e-05,0.0013,0.00066,0.0013,0.0012,1,1 -12090000,0.78,-0.018,0.00055,-0.63,-0.078,-0.0073,-0.021,-0.016,0.00038,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00051,0.00053,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.5e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.8e-05,0.0013,0.00066,0.0013,0.0012,1,1 -12190000,0.78,-0.018,-0.00013,-0.63,-0.064,-0.0098,-0.016,-0.0085,-0.00012,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.8e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12290000,0.78,-0.018,-0.00015,-0.63,-0.07,-0.012,-0.015,-0.015,-0.0016,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.071,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.6e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.8e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12390000,0.78,-0.018,-0.00055,-0.63,-0.057,-0.01,-0.013,-0.0083,-0.00071,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.5e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.7e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12490000,0.78,-0.018,-0.00042,-0.63,-0.064,-0.012,-0.016,-0.015,-0.0018,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.037,-0.027,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00041,0.05,0.068,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.7e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12590000,0.78,-0.018,-0.00062,-0.63,-0.06,-0.01,-0.022,-0.013,-0.00071,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00036,0.00037,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.9e-06,6.4e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12690000,0.78,-0.018,-0.00055,-0.63,-0.065,-0.0094,-0.025,-0.019,-0.00092,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.024,0.5,-0.0035,-0.091,-0.07,0,0,0.00035,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.7e-06,6.2e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12790000,0.78,-0.018,-0.00083,-0.63,-0.061,-0.0086,-0.029,-0.017,-0.00085,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12890000,0.78,-0.018,-0.00082,-0.63,-0.068,-0.0098,-0.028,-0.024,-0.0022,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.2e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12990000,0.78,-0.018,-0.0013,-0.63,-0.055,-0.0092,-0.028,-0.018,-0.0022,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.054,0.055,0.025,0.057,0.057,0.052,4.9e-06,5.4e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.7e-05,0.0012,0.00065,0.0013,0.0012,1,1 -13090000,0.78,-0.018,-0.0012,-0.63,-0.061,-0.009,-0.028,-0.024,-0.0029,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.7e-05,0.0012,0.00065,0.0012,0.0012,1,1 -13190000,0.78,-0.018,-0.0015,-0.63,-0.049,-0.0085,-0.025,-0.017,-0.0023,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.035,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00027,0.00028,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13290000,0.78,-0.018,-0.0016,-0.63,-0.053,-0.011,-0.022,-0.022,-0.0043,-3.7e+02,-0.00094,-0.0062,-8.2e-05,0.049,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00026,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.018,0.0091,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13390000,0.78,-0.018,-0.0018,-0.63,-0.044,-0.011,-0.018,-0.016,-0.0036,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13490000,0.78,-0.018,-0.0019,-0.63,-0.047,-0.012,-0.016,-0.021,-0.0051,-3.7e+02,-0.00097,-0.0062,-8e-05,0.051,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.5e-06,2.3e-06,0.017,0.017,0.0087,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13590000,0.78,-0.018,-0.002,-0.63,-0.038,-0.011,-0.019,-0.014,-0.0037,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13690000,0.78,-0.018,-0.0021,-0.63,-0.041,-0.014,-0.023,-0.018,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.8e-06,4.2e-06,2.3e-06,0.016,0.017,0.0083,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13790000,0.78,-0.018,-0.0023,-0.63,-0.03,-0.012,-0.024,-0.0066,-0.0043,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13890000,0.78,-0.018,-0.0023,-0.63,-0.033,-0.014,-0.029,-0.01,-0.0061,-3.7e+02,-0.00099,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00021,0.00022,0.049,0.048,0.048,0.03,0.079,0.08,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13990000,0.78,-0.018,-0.0025,-0.63,-0.025,-0.013,-0.028,-0.0036,-0.0053,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.4e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,6.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 -14090000,0.78,-0.018,-0.0025,-0.63,-0.026,-0.014,-0.029,-0.0058,-0.0068,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.055,-0.037,-0.12,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00019,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.3e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,6.7e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14190000,0.78,-0.017,-0.0027,-0.63,-0.021,-0.012,-0.031,-0.00022,-0.0047,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.013,0.014,0.0069,0.0012,6.7e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14290000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.014,-0.03,-0.0022,-0.006,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.036,-0.12,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3.1e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,6.7e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14390000,0.78,-0.017,-0.0029,-0.63,-0.017,-0.014,-0.032,0.0018,-0.0047,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.059,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14490000,0.78,-0.017,-0.0029,-0.63,-0.019,-0.017,-0.035,-0.00046,-0.0066,-3.7e+02,-0.001,-0.006,-7.4e-05,0.061,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.9e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14590000,0.78,-0.017,-0.0028,-0.63,-0.02,-0.017,-0.035,-0.0013,-0.0063,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.062,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00017,0.00018,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14690000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.032,-0.0035,-0.0082,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00018,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14790000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.028,-0.0036,-0.0076,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.019,-0.031,-0.0061,-0.0095,-3.7e+02,-0.00097,-0.006,-7.3e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14990000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.027,-0.0046,-0.0074,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.011,0.012,0.0048,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -15090000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.03,-0.0072,-0.009,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -15190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.015,-0.027,-0.0058,-0.0073,-3.7e+02,-0.00096,-0.006,-7.5e-05,0.066,-0.038,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,6.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 -15290000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.017,-0.025,-0.0081,-0.0089,-3.7e+02,-0.00097,-0.006,-7.3e-05,0.066,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15390000,0.78,-0.017,-0.0029,-0.63,-0.025,-0.017,-0.023,-0.0076,-0.0091,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.066,-0.036,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15490000,0.78,-0.017,-0.0028,-0.63,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.5e-06,2.4e-06,0.011,0.011,0.0037,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15590000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.022,-0.0097,-0.0098,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.01,0.011,0.0035,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15690000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15790000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.015,-0.025,-0.0085,-0.0096,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.3e-06,2.4e-06,0.01,0.011,0.0031,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15890000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.0099,0.011,0.003,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.016,-0.018,-0.0079,-0.0099,-3.7e+02,-0.001,-0.006,-7.1e-05,0.065,-0.037,-0.13,-0.11,-0.024,0.5,-0.004,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0028,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16090000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0096,0.01,0.0027,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16190000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.014,-0.0074,-0.0092,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.064,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0094,0.01,0.0025,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16290000,0.78,-0.017,-0.003,-0.63,-0.026,-0.018,-0.015,-0.0099,-0.011,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.065,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0093,0.01,0.0024,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16390000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.014,-0.014,-0.0074,-0.0088,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0022,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16490000,0.78,-0.017,-0.0029,-0.63,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0091,0.01,0.0021,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16590000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.012,-0.018,-0.0097,-0.0063,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.9e-06,2.4e-06,0.0089,0.0098,0.002,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16690000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.012,-0.014,-0.012,-0.0073,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.0088,0.0097,0.0019,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0091,-0.013,-0.012,-0.004,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0087,0.0096,0.0018,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16890000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.01,-0.01,-0.014,-0.0048,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0086,0.0095,0.0017,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0099,-0.0099,-0.013,-0.0047,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.062,-0.037,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0085,0.0094,0.0016,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -17090000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.012,-0.0098,-0.015,-0.0057,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0084,0.0093,0.0015,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -17190000,0.78,-0.017,-0.0028,-0.63,-0.023,-0.014,-0.011,-0.014,-0.006,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.4e-06,1.6e-06,2.4e-06,0.0083,0.0092,0.0015,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -17290000,0.78,-0.017,-0.0027,-0.63,-0.026,-0.015,-0.0061,-0.016,-0.0071,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0083,0.0091,0.0014,0.0012,6.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 -17390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.017,-0.0042,-0.013,-0.0073,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.091,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0082,0.009,0.0013,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17490000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.018,-0.0025,-0.016,-0.0092,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0081,0.0089,0.0013,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17590000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.018,0.003,-0.014,-0.0088,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.008,0.0088,0.0012,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17690000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.5e-06,2.4e-06,0.0079,0.0087,0.0011,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.06,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.0011,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.022,0.0012,-0.017,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.001,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17990000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0077,0.0085,0.00099,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18090000,0.78,-0.017,-0.0028,-0.63,-0.027,-0.02,0.0047,-0.018,-0.015,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00096,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0083,0.0009,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18290000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.019,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0075,0.0082,0.00087,0.0012,6.6e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.02,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0082,0.00083,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18490000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0081,-0.014,-0.014,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0081,0.0008,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18590000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.022,0.0062,-0.011,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0073,0.008,0.00076,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18690000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0072,0.008,0.00074,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18790000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.0007,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18890000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.023,0.0046,-0.014,-0.015,-3.7e+02,-0.0013,-0.006,-3.9e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.00068,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18990000,0.78,-0.016,-0.0029,-0.63,-0.019,-0.023,0.0033,-0.0094,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.00065,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19090000,0.78,-0.016,-0.0028,-0.63,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.007,0.0077,0.00063,0.0012,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19190000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.024,0.0063,-0.0074,-0.013,-3.7e+02,-0.0013,-0.006,-3.1e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0069,0.0076,0.0006,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19290000,0.78,-0.016,-0.0029,-0.63,-0.016,-0.024,0.0091,-0.0091,-0.015,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.0069,0.0076,0.00058,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19390000,0.78,-0.016,-0.0028,-0.63,-0.015,-0.022,0.013,-0.0081,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.0068,0.0075,0.00056,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19490000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.023,0.0093,-0.0097,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0068,0.0075,0.00055,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19590000,0.78,-0.016,-0.003,-0.63,-0.014,-0.022,0.0085,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,-1.9e-05,0.06,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,8e-07,9.7e-07,2.3e-06,0.0067,0.0074,0.00052,0.0011,6.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19690000,0.78,-0.016,-0.003,-0.63,-0.014,-0.02,0.01,-0.0091,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.9e-07,9.6e-07,2.3e-06,0.0067,0.0074,0.00051,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -19790000,0.78,-0.016,-0.003,-0.63,-0.012,-0.018,0.01,-0.0077,-0.015,-3.7e+02,-0.0013,-0.006,-1.7e-05,0.058,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0066,0.0073,0.00049,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -19890000,0.78,-0.016,-0.003,-0.63,-0.012,-0.02,0.012,-0.0093,-0.018,-3.7e+02,-0.0013,-0.0059,-1.3e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0031,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0066,0.0073,0.00048,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -19990000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.02,0.014,-0.0081,-0.016,-3.7e+02,-0.0013,-0.0059,-4.6e-06,0.06,-0.031,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0066,0.0072,0.00046,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20090000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.021,0.015,-0.0088,-0.019,-3.7e+02,-0.0013,-0.0059,1.3e-07,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0065,0.0072,0.00045,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20190000,0.78,-0.016,-0.0032,-0.63,-0.01,-0.019,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,6.1e-06,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0065,0.0071,0.00043,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20290000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.019,0.015,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,7.8e-06,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0064,0.0071,0.00042,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20390000,0.78,-0.016,-0.0032,-0.63,-0.0087,-0.016,0.017,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0064,0.007,0.00041,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20490000,0.78,-0.016,-0.0032,-0.63,-0.0089,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,1e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0064,0.007,0.0004,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20590000,0.78,-0.016,-0.0032,-0.63,-0.0084,-0.014,0.014,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0063,0.0069,0.00038,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20690000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.015,0.015,-0.0096,-0.018,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0063,0.0069,0.00037,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20790000,0.78,-0.016,-0.0032,-0.63,-0.0068,-0.014,0.015,-0.008,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0062,0.0068,0.00036,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20890000,0.78,-0.016,-0.0033,-0.63,-0.007,-0.014,0.014,-0.0086,-0.018,-3.7e+02,-0.0013,-0.0059,2.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0062,0.0068,0.00035,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20990000,0.78,-0.016,-0.0033,-0.63,-0.0054,-0.012,0.015,-0.0083,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0062,0.0067,0.00034,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21090000,0.78,-0.016,-0.0033,-0.63,-0.0065,-0.012,0.015,-0.0092,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0061,0.0067,0.00034,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21190000,0.78,-0.016,-0.0033,-0.63,-0.0066,-0.011,0.014,-0.0097,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.4e-07,2.3e-06,0.0061,0.0067,0.00033,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21290000,0.78,-0.016,-0.0034,-0.63,-0.0062,-0.012,0.016,-0.0097,-0.022,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,9.3e-05,9.8e-05,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0061,0.0066,0.00032,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21390000,0.78,-0.016,-0.0034,-0.63,-0.0055,-0.0074,0.016,-0.0085,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.006,0.0066,0.00031,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21490000,0.78,-0.016,-0.0034,-0.63,-0.0061,-0.0083,0.016,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21590000,0.78,-0.016,-0.0034,-0.63,-0.0047,-0.0066,0.016,-0.008,-0.014,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21690000,0.78,-0.016,-0.0034,-0.63,-0.0063,-0.0077,0.017,-0.0093,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.0059,0.0065,0.00029,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21790000,0.78,-0.016,-0.0032,-0.63,-0.0054,-0.0054,0.016,-0.0081,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21890000,0.78,-0.016,-0.0033,-0.63,-0.006,-0.0063,0.016,-0.0088,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21990000,0.78,-0.016,-0.0032,-0.63,-0.0059,-0.0035,0.017,-0.0082,-0.0069,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0058,0.0064,0.00027,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1 -22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22190000,0.78,-0.016,-0.0032,-0.63,-0.0043,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22490000,0.78,-0.016,-0.0033,-0.63,-0.00016,-0.006,0.018,-0.0055,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0056,0.02,-0.0026,-0.0059,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0057,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0048,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00046,-0.043,-0.0096,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.0059,0.00019,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00037,-0.00011,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00053,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.044,-0.4,0.0006,0.0037,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00058,0.0012,0.0012,1,1 -24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.9e-05,0.0012,0.00058,0.0012,0.0012,1,1 -24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0069,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0068,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.2e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.7e-05,0.0012,0.00057,0.0011,0.0012,1,1 -25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.7e-05,0.0012,0.00057,0.0011,0.0012,1,1 -25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.9e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,5.6e-05,0.0012,0.00057,0.0011,0.0012,1,1 -25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.5e-05,0.0012,0.00057,0.0011,0.0011,1,1 -25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00062,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.5e-05,0.0011,0.00057,0.0011,0.0011,1,1 -25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.4e-05,0.0011,0.00056,0.0011,0.0011,1,1 -25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.3e-05,0.0011,0.00056,0.001,0.0011,1,1 -25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.061,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,5.2e-05,0.0011,0.00056,0.001,0.0011,1,1 -25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,5.1e-05,0.0011,0.00055,0.001,0.0011,1,1 -26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,5e-05,0.0011,0.00055,0.00098,0.0011,1,1 -26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.035,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,4.9e-05,0.001,0.00054,0.00094,0.001,1,1 -26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0057,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,4.7e-05,0.001,0.00053,0.00091,0.00099,1,1 -26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,4.6e-05,0.00097,0.00051,0.00088,0.00096,1,1 -26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0065,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.4e-05,0.00093,0.00049,0.00084,0.00093,1,1 -26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,4.2e-05,0.00088,0.00047,0.0008,0.00088,1,1 -26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,3.9e-05,0.00082,0.00045,0.00074,0.00082,1,1 -26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,3.7e-05,0.00078,0.00042,0.00069,0.00077,1,1 -26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,3.5e-05,0.00073,0.00039,0.00065,0.00073,1,1 -26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00057,3.2e-05,0.00066,0.00035,0.00059,0.00066,1,1 -27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,2.9e-05,0.00059,0.00032,0.00053,0.00059,1,1 -27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.036,0.47,-0.0074,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,2.7e-05,0.00055,0.00029,0.00049,0.00054,1,1 -27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,2.6e-05,0.00052,0.00026,0.00046,0.00051,1,1 -27390000,0.76,0.078,-0.034,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,2.5e-05,0.0005,0.00023,0.00044,0.00049,1,1 -27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.4e-05,0.00049,0.00021,0.00043,0.00048,1,1 -27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.4e-05,0.00048,0.0002,0.00042,0.00048,1,1 -27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.9e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.0004,2.4e-05,0.00048,0.00018,0.00042,0.00047,1,1 -27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.4e-05,0.082,-0.026,-0.13,-0.17,-0.037,0.47,-0.0056,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.3e-05,0.00047,0.00017,0.00041,0.00047,1,1 -27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0056,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.3e-05,0.00047,0.00016,0.0004,0.00047,1,1 -27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0055,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.3e-05,0.00047,0.00016,0.0004,0.00046,1,1 -28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2.2e-05,0.00046,0.00015,0.00039,0.00046,1,1 -28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2.2e-05,0.00046,0.00014,0.00038,0.00045,1,1 -28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0047,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00014,0.00038,0.00045,1,1 -28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.7e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00013,0.00037,0.00045,1,1 -28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00013,0.00037,0.00045,1,1 -28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00012,0.00037,0.00044,1,1 -28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00012,0.00037,0.00044,1,1 -28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.2e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00044,0.00012,0.00037,0.00044,1,1 -28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.1e-05,0.00044,0.00011,0.00037,0.00044,1,1 -28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00044,1,1 -29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0036,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.0001,0.00037,0.00043,1,1 -29390000,0.78,7.2e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.6e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1 -29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1 -29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1 -29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.9e-05,0.00037,0.00043,1,1 -29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.2e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.8e-05,0.00037,0.00042,1,1 -29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.6e-05,0.00037,0.00042,1,1 -29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2e-05,0.00043,9.5e-05,0.00036,0.00042,1,1 -30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.5e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1 -30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1 -30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1 -30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.4e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1 -30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.3e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1 -30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-8.2e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1 -30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4.1e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9e-05,0.00036,0.00042,1,1 -30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.2e-06,0.075,-0.0096,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9e-05,0.00036,0.00042,1,1 -30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1 -30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1 -31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 -31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 -31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 -31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00034,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 -31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 -31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0038,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 -31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 -31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 -31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0014,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1 -31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00053,-0.12,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.14,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1 -32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00016,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 -32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 -32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 -32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2e-05,0.00041,8.4e-05,0.00036,0.0004,1,1 -32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 -32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 -33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 -33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 -33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1 -33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.0009,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,1.8e-05,0.0004,8e-05,0.00032,0.00039,1,1 -33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.6e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00041,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,1.5e-05,0.00039,7.3e-05,0.00024,0.00039,1,1 -33590000,0.99,-0.0082,-3.1e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,1.1e-05,0.00039,6e-05,0.00015,0.00039,1,1 -33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00018,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,8.4e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1 -33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00052,-0.0066,-0.025,0,0,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,6.8e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1 -33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.9e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00074,-0.0053,-0.025,0,0,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5.1e-05,5.9e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1 -33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.7e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,5.4e-06,0.00038,2.1e-05,3e-05,0.00038,1,1 -34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.065,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,5.1e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1 -34190000,0.75,-0.014,0.0071,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,4.9e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1 -34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.6e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,4.7e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1 -34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0041,-0.11,-0.2,-0.044,0.46,9e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.5e-05,4.6e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1 -34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,4.8e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.005,8.8e-05,2.3e-05,4.6e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1 -34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0039,-0.11,-0.2,-0.044,0.46,-4.8e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0012,0.056,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.2e-05,4.5e-06,0.00038,9e-06,1.1e-05,0.00038,1,1 -34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.5e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.1e-05,4.5e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1 -34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.067,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,4.4e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1 -34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.6e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,4.4e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1 -34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.3e-05,0.0012,0.09,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,4.3e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1 -35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00021,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0012,0.098,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,4.3e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1 -35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00025,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.3e-06,0.00038,6.2e-06,7e-06,0.00038,1,1 -35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.3e-06,0.00038,6e-06,6.6e-06,0.00038,1,1 -35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.13,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.2e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1 -35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00044,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.13,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.6e-06,6e-06,0.00037,1,1 -35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00041,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1 -35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1 -35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.17,0.23,0.01,0.73,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1 -35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.18,0.25,0.0096,0.78,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5e-06,5.2e-06,0.00037,1,1 -35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00046,-0.0016,-0.025,0,0,0.00013,9e-05,0.0011,0.19,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.9e-06,5e-06,0.00037,1,1 -36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.2,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1 -36190000,0.65,-0.0066,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.22,0.3,0.0086,0.96,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1 -36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.23,0.32,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1 -36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00057,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1 -36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00054,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,4.1e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1 -36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1 -36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1 -36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00064,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.3e-06,4e-06,0.00037,1,1 -36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00067,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.32,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 -36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 -37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0011,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1 -37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00068,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 -37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.5e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0011,0.39,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 -37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00071,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.41,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.6e-06,0.00037,1,1 -37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.6e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.43,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 -37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.2e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.45,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 -37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.042,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.47,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 -37790000,0.65,-0.0069,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.49,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 -37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.2e-05,0.068,0.0043,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.001,0.51,0.65,0.0065,3.3,4.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 -37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.001,0.53,0.67,0.0065,3.5,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 -38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.078,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.55,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1 -38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.001,0.58,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1 -38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.001,0.6,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 -38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0039,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.62,0.77,0.0065,4.6,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 -38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.64,0.8,0.0065,5,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 -38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.67,0.82,0.0065,5.3,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 -38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0045,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.69,0.85,0.0065,5.6,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 -38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.72,0.88,0.0065,6,7.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1 -38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.3e-05,0.001,0.73,0.89,0.0065,6.4,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.7e-06,2.9e-06,0.00037,1,1 +6790000,0.78,-0.024,0.0048,-0.62,-0.22,-0.051,-0.11,-0.13,-0.03,-3.7e+02,-0.00029,-0.01,-0.0002,0,0,0.0012,-0.092,-0.021,0.51,-0.00079,-0.075,-0.061,0,0,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 +6890000,0.78,-0.025,0.0057,-0.62,-0.27,-0.065,-0.12,-0.16,-0.04,-3.7e+02,-0.0001,-0.011,-0.00022,0,0,0.0012,-0.1,-0.023,0.51,-0.0012,-0.083,-0.067,0,0,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00025,0.0013,0.00089,0.0014,0.0013,1,1 +6990000,0.78,-0.025,0.006,-0.62,-0.3,-0.077,-0.12,-0.2,-0.05,-3.7e+02,-6.9e-06,-0.011,-0.00022,-0.00057,-7.3e-05,0.00095,-0.1,-0.024,0.5,-0.0016,-0.084,-0.067,0,0,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1 +7090000,0.78,-0.025,0.0062,-0.62,-0.33,-0.088,-0.12,-0.23,-0.063,-3.7e+02,0.00011,-0.011,-0.00023,-0.0013,-0.0003,0.00061,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00016,0.0013,0.00083,0.0014,0.0013,1,1 +7190000,0.78,-0.025,0.0064,-0.62,-0.36,-0.097,-0.15,-0.26,-0.075,-3.7e+02,0.00017,-0.011,-0.00023,-0.0017,-0.00046,0.00083,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00082,0.0013,0.0013,1,1 +7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.099,-0.14,-0.3,-0.082,-3.7e+02,0.00012,-0.011,-0.00023,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1 +7390000,0.78,-0.025,0.0069,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,0.00014,-0.011,-0.00022,-0.0016,-0.00046,9.1e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1 +7490000,0.78,-0.025,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00027,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.0019,-0.085,-0.069,0,0,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1 +7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00026,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1 +7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1 +7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0062,-0.16,-0.44,-0.14,-3.7e+02,0.00041,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1 +7890000,0.78,-0.024,0.0073,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00045,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1 +7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.00046,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1 +8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.0005,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1 +8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00049,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1 +8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00059,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1 +8390000,0.78,-0.024,0.0071,-0.63,-0.18,-0.036,-0.17,-0.49,-0.15,-3.7e+02,0.0006,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1 +8490000,0.78,-0.024,0.0071,-0.63,-0.2,-0.039,-0.17,-0.49,-0.15,-3.7e+02,0.00061,-0.0099,-0.00021,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1 +8590000,0.78,-0.023,0.0073,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00041,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1 +8690000,0.78,-0.023,0.0069,-0.63,-0.24,-0.044,-0.16,-0.53,-0.15,-3.7e+02,0.00042,-0.0096,-0.00019,-0.0019,-0.00051,-0.033,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,29,29,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,8.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 +8790000,0.78,-0.023,0.007,-0.63,-0.25,-0.047,-0.15,-0.53,-0.15,-3.7e+02,0.00045,-0.0095,-0.00019,-0.0019,-0.00051,-0.039,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.096,25,25,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,8.5e-05,0.0013,0.00076,0.0013,0.0013,1,1 +8890000,0.78,-0.023,0.0069,-0.63,-0.27,-0.051,-0.15,-0.55,-0.16,-3.7e+02,0.00044,-0.0094,-0.00018,-0.0019,-0.00051,-0.043,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.095,27,27,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0012,8.4e-05,0.0013,0.00076,0.0013,0.0013,1,1 +8990000,0.78,-0.023,0.0069,-0.63,-0.28,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00049,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1 +9090000,0.78,-0.022,0.0069,-0.63,-0.29,-0.053,-0.14,-0.58,-0.17,-3.7e+02,0.00041,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1 +9190000,0.78,-0.022,0.0062,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00042,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1 +9290000,0.78,-0.022,0.0059,-0.63,-0.31,-0.072,-0.14,-0.62,-0.18,-3.7e+02,0.00044,-0.0086,-0.00016,-0.0018,-6.2e-05,-0.059,-0.11,-0.025,0.5,-0.0028,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1 +9390000,0.78,-0.022,0.0058,-0.63,-0.33,-0.081,-0.13,-0.65,-0.19,-3.7e+02,0.00046,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1 +9490000,0.78,-0.022,0.0053,-0.63,-0.34,-0.094,-0.13,-0.67,-0.21,-3.7e+02,0.00049,-0.0082,-0.00015,-0.0018,0.00039,-0.067,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1 +9590000,0.78,-0.022,0.005,-0.63,-0.34,-0.093,-0.13,-0.7,-0.21,-3.7e+02,0.00034,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1 +9690000,0.78,-0.022,0.0052,-0.63,-0.36,-0.09,-0.12,-0.73,-0.22,-3.7e+02,0.00025,-0.008,-0.00014,-0.0021,0.00091,-0.075,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1 +9790000,0.78,-0.022,0.0048,-0.63,-0.37,-0.1,-0.11,-0.75,-0.23,-3.7e+02,0.00026,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1 +9890000,0.78,-0.021,0.0046,-0.63,-0.38,-0.1,-0.11,-0.78,-0.24,-3.7e+02,0.00017,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1 +9990000,0.78,-0.021,0.0046,-0.63,-0.39,-0.1,-0.1,-0.82,-0.25,-3.7e+02,0.00012,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1 +10090000,0.78,-0.021,0.0043,-0.63,-0.4,-0.1,-0.096,-0.84,-0.26,-3.7e+02,1.3e-05,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1 +10190000,0.78,-0.021,0.0046,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-2e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1 +10290000,0.78,-0.021,0.0048,-0.63,-0.44,-0.1,-0.083,-0.93,-0.27,-3.7e+02,-4.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10390000,0.78,-0.021,0.0046,-0.63,-0.0086,-0.022,0.0097,7.5e-05,-0.0019,-3.7e+02,-3.9e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10490000,0.78,-0.021,0.0047,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-6.2e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10590000,0.78,-0.02,0.0044,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00025,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 +10690000,0.78,-0.02,0.0043,-0.63,-0.044,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00026,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 +10790000,0.78,-0.02,0.0039,-0.63,-0.041,-0.01,0.024,0.001,-0.0011,-3.7e+02,-0.00032,-0.0072,-0.00011,-0.00017,0.0013,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 +10890000,0.78,-0.02,0.0038,-0.63,-0.057,-0.013,0.02,-0.0037,-0.0023,-3.7e+02,-0.00033,-0.0071,-0.0001,-0.00011,0.0014,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 +10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.01,0.015,0.00013,-0.0011,-3.7e+02,-0.00036,-0.0069,-9.7e-05,0.0036,-0.00089,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.069,0,0,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 +11090000,0.78,-0.02,0.0027,-0.63,-0.06,-0.014,0.02,-0.0048,-0.0026,-3.7e+02,-0.00041,-0.0068,-9.2e-05,0.0036,-0.00047,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.07,0,0,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1 +11190000,0.78,-0.019,0.0022,-0.63,-0.054,-0.01,0.0082,0.00068,-0.00048,-3.7e+02,-0.00051,-0.0067,-8.9e-05,0.0082,-0.0037,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1 +11290000,0.78,-0.019,0.0023,-0.63,-0.07,-0.012,0.008,-0.0058,-0.0016,-3.7e+02,-0.00047,-0.0067,-9.1e-05,0.0083,-0.0039,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1 +11390000,0.78,-0.019,0.0019,-0.63,-0.064,-0.011,0.0024,0.00033,-0.00038,-3.7e+02,-0.00057,-0.0067,-9e-05,0.012,-0.0076,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1 +11490000,0.78,-0.019,0.0021,-0.63,-0.078,-0.012,0.0032,-0.0072,-0.0013,-3.7e+02,-0.00055,-0.0068,-9.2e-05,0.012,-0.0081,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11590000,0.78,-0.019,0.0016,-0.63,-0.069,-0.012,-0.0027,-0.0022,-0.00077,-3.7e+02,-0.0006,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11690000,0.78,-0.019,0.0017,-0.63,-0.08,-0.015,-0.0071,-0.0098,-0.0023,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.013,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11790000,0.78,-0.019,0.0011,-0.63,-0.072,-0.011,-0.0089,-0.0062,-0.00016,-3.7e+02,-0.0006,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11890000,0.78,-0.019,0.0012,-0.63,-0.084,-0.011,-0.0098,-0.014,-0.0012,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 +11990000,0.78,-0.019,0.0006,-0.63,-0.072,-0.0062,-0.015,-0.009,0.00097,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1 +12090000,0.78,-0.018,0.00044,-0.63,-0.078,-0.0083,-0.021,-0.016,0.00015,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0033,-0.09,-0.07,0,0,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1 +12190000,0.78,-0.018,-0.00024,-0.62,-0.064,-0.011,-0.016,-0.0086,-0.00028,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12290000,0.78,-0.019,-0.00026,-0.62,-0.07,-0.013,-0.015,-0.015,-0.0019,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12390000,0.78,-0.018,-0.00067,-0.62,-0.058,-0.011,-0.013,-0.0083,-0.00087,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12490000,0.78,-0.018,-0.00053,-0.62,-0.065,-0.013,-0.016,-0.015,-0.002,-3.7e+02,-0.00082,-0.0064,-8.5e-05,0.038,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 +12590000,0.78,-0.018,-0.00073,-0.62,-0.06,-0.011,-0.022,-0.013,-0.00087,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12690000,0.78,-0.018,-0.00066,-0.62,-0.065,-0.01,-0.025,-0.019,-0.0011,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.025,0.5,-0.0034,-0.091,-0.07,0,0,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12790000,0.78,-0.018,-0.00094,-0.62,-0.061,-0.0093,-0.029,-0.017,-0.001,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12890000,0.78,-0.018,-0.00093,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0025,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 +12990000,0.78,-0.018,-0.0014,-0.62,-0.055,-0.0099,-0.028,-0.018,-0.0024,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 +13090000,0.78,-0.018,-0.0013,-0.62,-0.061,-0.0097,-0.028,-0.024,-0.0032,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0012,0.0012,1,1 +13190000,0.78,-0.018,-0.0016,-0.62,-0.049,-0.0091,-0.025,-0.017,-0.0025,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.036,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,0.00027,0.00029,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13290000,0.78,-0.018,-0.0017,-0.62,-0.054,-0.012,-0.022,-0.023,-0.0046,-3.7e+02,-0.00094,-0.0062,-8.3e-05,0.049,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00027,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13390000,0.78,-0.018,-0.002,-0.62,-0.044,-0.011,-0.018,-0.016,-0.0038,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00025,0.00027,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13490000,0.78,-0.018,-0.002,-0.62,-0.047,-0.013,-0.016,-0.021,-0.0055,-3.7e+02,-0.00097,-0.0061,-8e-05,0.052,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00025,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.4e-06,2.3e-06,0.017,0.018,0.0087,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13590000,0.78,-0.018,-0.0022,-0.62,-0.038,-0.011,-0.019,-0.014,-0.004,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00025,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13690000,0.78,-0.018,-0.0022,-0.62,-0.041,-0.015,-0.023,-0.018,-0.0057,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13790000,0.78,-0.018,-0.0024,-0.62,-0.03,-0.013,-0.024,-0.0067,-0.0045,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13890000,0.78,-0.018,-0.0024,-0.62,-0.033,-0.014,-0.029,-0.01,-0.0064,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 +13990000,0.78,-0.018,-0.0026,-0.62,-0.026,-0.013,-0.028,-0.0037,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0069,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00028,-0.0049,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14290000,0.78,-0.017,-0.0028,-0.62,-0.022,-0.014,-0.03,-0.0023,-0.0062,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0017,-0.0048,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.06,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14490000,0.78,-0.017,-0.003,-0.62,-0.019,-0.017,-0.035,-0.00051,-0.0068,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0064,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.063,-0.037,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14690000,0.78,-0.017,-0.003,-0.62,-0.023,-0.017,-0.032,-0.0035,-0.0084,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0078,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.019,-0.031,-0.0061,-0.0097,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +14990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0047,-0.0076,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +15090000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0092,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +15190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0074,-3.7e+02,-0.00097,-0.006,-7.5e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 +15290000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.025,-0.0081,-0.0091,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15390000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.023,-0.0076,-0.0093,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15490000,0.78,-0.017,-0.0029,-0.62,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0098,-0.01,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15790000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.015,-0.025,-0.0086,-0.0097,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.039,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15890000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +15990000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.018,-0.0079,-0.01,-3.7e+02,-0.001,-0.006,-7.1e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.014,-0.0074,-0.0094,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0096,0.011,0.0025,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16290000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0098,-0.012,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0095,0.01,0.0024,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.015,-0.014,-0.0074,-0.0089,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0093,0.01,0.0022,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16490000,0.78,-0.017,-0.003,-0.62,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0021,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16590000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.012,-0.018,-0.0097,-0.0064,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.8e-06,2.4e-06,0.0091,0.01,0.002,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16690000,0.78,-0.017,-0.003,-0.62,-0.024,-0.013,-0.014,-0.012,-0.0074,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.009,0.0099,0.0019,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.0094,-0.013,-0.012,-0.0041,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0089,0.0098,0.0018,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16890000,0.78,-0.017,-0.003,-0.62,-0.024,-0.01,-0.01,-0.014,-0.0049,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0088,0.0097,0.0017,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +16990000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.01,-0.0099,-0.013,-0.0048,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.037,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0087,0.0095,0.0016,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +17090000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.012,-0.0098,-0.015,-0.0059,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.037,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0086,0.0094,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +17190000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.014,-0.011,-0.014,-0.0061,-3.7e+02,-0.0012,-0.006,-6e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.3e-06,1.6e-06,2.4e-06,0.0085,0.0093,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 +17290000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.0061,-0.016,-0.0072,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0084,0.0092,0.0014,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.017,-0.0042,-0.013,-0.0075,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.091,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0083,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17490000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0093,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17590000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.018,0.003,-0.014,-0.009,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.023,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 +17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18090000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18290000,0.78,-0.017,-0.0028,-0.62,-0.025,-0.02,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18490000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18590000,0.78,-0.016,-0.0029,-0.62,-0.022,-0.022,0.0062,-0.011,-0.013,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0074,0.0082,0.00076,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18690000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0074,0.0081,0.00074,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18790000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0073,0.008,0.0007,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18890000,0.78,-0.016,-0.003,-0.62,-0.022,-0.024,0.0046,-0.013,-0.015,-3.7e+02,-0.0013,-0.006,-4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0072,0.008,0.00068,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +18990000,0.78,-0.016,-0.003,-0.62,-0.019,-0.023,0.0033,-0.0093,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.00065,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19090000,0.78,-0.016,-0.003,-0.62,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.0071,0.0079,0.00063,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19190000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0063,-0.0072,-0.014,-3.7e+02,-0.0013,-0.006,-3.2e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.0006,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19290000,0.78,-0.016,-0.003,-0.62,-0.016,-0.024,0.0091,-0.0089,-0.016,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.06,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.007,0.0077,0.00058,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19390000,0.78,-0.016,-0.003,-0.62,-0.015,-0.022,0.013,-0.008,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.007,0.0077,0.00056,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19490000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0093,-0.0095,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0069,0.0076,0.00055,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 +19590000,0.78,-0.016,-0.0031,-0.62,-0.013,-0.022,0.0085,-0.008,-0.015,-3.7e+02,-0.0013,-0.0059,-2e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,7.9e-07,9.7e-07,2.3e-06,0.0069,0.0075,0.00052,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +19690000,0.78,-0.016,-0.0031,-0.62,-0.014,-0.021,0.01,-0.0088,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.8e-07,9.6e-07,2.3e-06,0.0068,0.0075,0.00051,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +19790000,0.78,-0.016,-0.0031,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.8e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +19890000,0.78,-0.016,-0.0031,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.4e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-4.8e-06,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,-9.5e-08,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20190000,0.78,-0.016,-0.0033,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,5.9e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20290000,0.78,-0.016,-0.0033,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,7.6e-06,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20390000,0.78,-0.016,-0.0033,-0.62,-0.0085,-0.017,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20490000,0.78,-0.016,-0.0033,-0.62,-0.0087,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,9.8e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20590000,0.78,-0.016,-0.0033,-0.62,-0.0082,-0.014,0.014,-0.0085,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0064,0.007,0.00038,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20690000,0.78,-0.016,-0.0033,-0.62,-0.0089,-0.015,0.015,-0.0094,-0.018,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0064,0.007,0.00037,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20790000,0.78,-0.016,-0.0034,-0.62,-0.0066,-0.014,0.015,-0.0078,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0063,0.0069,0.00036,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20890000,0.78,-0.016,-0.0034,-0.62,-0.0068,-0.014,0.014,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,2.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0063,0.0069,0.00035,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +20990000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.012,0.015,-0.008,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0063,0.0069,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21090000,0.78,-0.016,-0.0034,-0.62,-0.0063,-0.012,0.015,-0.009,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0062,0.0068,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21190000,0.78,-0.016,-0.0034,-0.62,-0.0064,-0.011,0.014,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.3e-05,0.0001,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00033,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21290000,0.78,-0.016,-0.0036,-0.62,-0.006,-0.012,0.016,-0.0094,-0.023,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00032,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21390000,0.78,-0.016,-0.0035,-0.62,-0.0054,-0.0074,0.016,-0.0083,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.0061,0.0067,0.00031,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21490000,0.78,-0.016,-0.0035,-0.62,-0.006,-0.0084,0.016,-0.0093,-0.019,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.0061,0.0067,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21590000,0.78,-0.016,-0.0035,-0.62,-0.0046,-0.0067,0.016,-0.0078,-0.015,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.7e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.0061,0.0066,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21690000,0.78,-0.016,-0.0035,-0.62,-0.0062,-0.0078,0.017,-0.009,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.006,0.0066,0.00029,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21790000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.0055,0.016,-0.0079,-0.01,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.5e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21890000,0.78,-0.016,-0.0034,-0.62,-0.0059,-0.0064,0.016,-0.0086,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9e-05,9.6e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 +21990000,0.78,-0.016,-0.0033,-0.62,-0.0057,-0.0036,0.017,-0.0081,-0.007,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22090000,0.78,-0.016,-0.0033,-0.62,-0.0054,-0.0052,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22190000,0.78,-0.016,-0.0033,-0.62,-0.0041,-0.0057,0.015,-0.007,-0.0067,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0054,0.016,-0.0077,-0.0071,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22390000,0.78,-0.016,-0.0034,-0.62,-0.0012,-0.0053,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22490000,0.78,-0.016,-0.0034,-0.62,-4.6e-06,-0.006,0.018,-0.0054,-0.0068,-3.7e+02,-0.0014,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22590000,0.78,-0.016,-0.0034,-0.62,0.0018,-0.0049,0.017,-0.0036,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22690000,0.78,-0.016,-0.0034,-0.62,0.0034,-0.0063,0.019,-0.0029,-0.0073,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22790000,0.78,-0.016,-0.0033,-0.62,0.0044,-0.0055,0.02,-0.0024,-0.0059,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22890000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0064,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 +22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0066,0.022,-0.0026,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0063,0.023,-0.0024,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23190000,0.78,-0.016,-0.0033,-0.62,0.0026,-0.0052,0.024,-0.0051,-0.0072,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0057,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23290000,0.78,-0.016,-0.0032,-0.62,0.0023,-0.005,0.025,-0.0054,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,9.1e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23390000,0.78,-0.016,-0.0033,-0.62,-0.001,-0.0047,0.022,-0.0096,-0.0083,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23490000,0.78,-0.013,-0.0054,-0.62,0.0046,-0.0043,-0.011,-0.01,-0.0099,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00021,-0.043,-0.0095,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23690000,0.78,0.0011,-0.0086,-0.62,0.043,0.014,-0.093,-0.007,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23790000,0.78,-0.0026,-0.0061,-0.62,0.064,0.031,-0.15,-0.007,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23890000,0.78,-0.0089,-0.0042,-0.62,0.077,0.043,-0.2,0.00048,-2e-05,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +23990000,0.78,-0.014,-0.0034,-0.62,0.072,0.043,-0.25,-0.005,-0.0015,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.0019,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.067,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24190000,0.78,-0.01,-0.0054,-0.62,0.07,0.041,-0.35,-0.0059,-0.0003,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 +24290000,0.78,-0.0092,-0.0058,-0.62,0.078,0.046,-0.4,0.00062,0.0041,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1 +24390000,0.79,-0.0096,-0.0059,-0.62,0.075,0.044,-0.46,-0.012,-0.0023,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.6e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1 +24490000,0.79,-0.0054,-0.0063,-0.62,0.086,0.051,-0.51,-0.0038,0.0024,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1 +24590000,0.79,-0.0019,-0.0064,-0.62,0.09,0.055,-0.56,-0.017,-0.0064,-3.7e+02,-0.0012,-0.0059,6.4e-05,0.067,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.6e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.6e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24690000,0.79,-0.00099,-0.0064,-0.62,0.11,0.071,-0.64,-0.0079,-0.0014,-3.7e+02,-0.0012,-0.0059,7.1e-05,0.068,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.09,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24790000,0.79,-0.0025,-0.0063,-0.62,0.11,0.08,-0.73,-0.027,-0.0061,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0026,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.018,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24890000,0.79,-0.00064,-0.0078,-0.62,0.13,0.095,-0.75,-0.016,0.0027,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.089,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0058,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1 +24990000,0.79,0.0011,-0.0095,-0.62,0.13,0.1,-0.81,-0.038,-0.0036,-3.7e+02,-0.0011,-0.0059,4.5e-05,0.071,-0.03,-0.13,-0.11,-0.026,0.5,-0.0024,-0.089,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25090000,0.79,0.00055,-0.0098,-0.62,0.16,0.12,-0.86,-0.024,0.0078,-3.7e+02,-0.0011,-0.0059,4.3e-05,0.071,-0.03,-0.13,-0.11,-0.027,0.5,-0.0025,-0.088,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1 +25190000,0.79,-0.0014,-0.0096,-0.61,0.15,0.11,-0.91,-0.068,-0.014,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0022,-0.088,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00057,0.0011,0.0012,1,1 +25290000,0.79,0.0056,-0.011,-0.62,0.18,0.13,-0.96,-0.052,-0.003,-3.7e+02,-0.0011,-0.0058,2.6e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.0011,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1 +25390000,0.79,0.012,-0.011,-0.61,0.18,0.13,-1,-0.1,-0.027,-3.7e+02,-0.001,-0.0058,7.5e-06,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0021,-0.087,-0.07,0,0,8.1e-05,8.5e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.001,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1 +25490000,0.79,0.013,-0.011,-0.61,0.21,0.16,-1.1,-0.081,-0.014,-3.7e+02,-0.001,-0.0058,1.6e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0024,-0.086,-0.069,0,0,8.2e-05,8.5e-05,0.046,0.022,0.022,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.2e-05,0.0012,0.00057,0.0011,0.0011,1,1 +25590000,0.79,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.058,0.0024,-3.7e+02,-0.001,-0.0058,2.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.6e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.1e-05,0.0011,0.00056,0.0011,0.0011,1,1 +25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,2.9e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1 +25790000,0.79,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0013,0.041,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.079,-0.03,-0.13,-0.12,-0.028,0.5,-0.0035,-0.083,-0.067,0,0,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1 +25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.04,0.065,-3.7e+02,-0.00099,-0.0058,5.6e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1 +25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.5e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0045,-0.08,-0.065,0,0,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1 +26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.079,-0.031,-0.13,-0.12,-0.029,0.5,-0.0046,-0.079,-0.065,0,0,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1 +26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.031,-0.13,-0.13,-0.03,0.5,-0.0054,-0.075,-0.063,0,0,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1 +26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.7e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00052,0.00091,0.00099,1,1 +26390000,0.78,0.041,-0.021,-0.62,0.75,0.51,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,8.5e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,9e-05,0.041,0.042,0.046,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00084,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1 +26490000,0.78,0.057,-0.027,-0.63,0.84,0.57,-1.3,0.4,0.3,-3.7e+02,-0.00097,-0.0058,9e-05,0.08,-0.032,-0.13,-0.13,-0.031,0.49,-0.0066,-0.069,-0.058,0,0,8.9e-05,9.1e-05,0.039,0.045,0.05,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00081,4.9e-05,0.00093,0.00049,0.00084,0.00093,1,1 +26590000,0.78,0.074,-0.032,-0.62,0.95,0.65,-1.3,0.49,0.36,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.081,-0.032,-0.13,-0.14,-0.032,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9.1e-05,0.038,0.049,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00076,4.6e-05,0.00088,0.00047,0.0008,0.00088,1,1 +26690000,0.77,0.077,-0.033,-0.63,1.1,0.72,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,0.0001,0.08,-0.032,-0.13,-0.14,-0.033,0.49,-0.0073,-0.061,-0.052,0,0,9.1e-05,9.2e-05,0.035,0.053,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00071,4.3e-05,0.00082,0.00045,0.00074,0.00082,1,1 +26790000,0.77,0.071,-0.032,-0.63,1.2,0.8,-1.3,0.71,0.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.032,-0.13,-0.14,-0.034,0.48,-0.0071,-0.057,-0.049,0,0,9.2e-05,9.3e-05,0.032,0.056,0.067,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0057,0.00014,0.00067,4.1e-05,0.00078,0.00042,0.00069,0.00077,1,1 +26890000,0.77,0.094,-0.039,-0.63,1.3,0.88,-1.3,0.84,0.58,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.035,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.3e-05,0.03,0.059,0.072,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00063,3.9e-05,0.00073,0.00039,0.00065,0.00073,1,1 +26990000,0.76,0.12,-0.044,-0.63,1.5,0.99,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.032,-0.13,-0.15,-0.036,0.48,-0.0079,-0.047,-0.043,0,0,9.3e-05,9.4e-05,0.027,0.063,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00013,0.00057,3.5e-05,0.00066,0.00035,0.00059,0.00066,1,1 +27090000,0.76,0.12,-0.045,-0.63,1.7,1.1,-1.3,1.1,0.77,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.037,0.47,-0.0078,-0.043,-0.039,0,0,9.3e-05,9.4e-05,0.024,0.067,0.085,0.0061,0.36,0.37,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00052,3.2e-05,0.00059,0.00032,0.00053,0.00059,1,1 +27190000,0.76,0.11,-0.042,-0.63,1.9,1.2,-1.2,1.3,0.89,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.038,0.47,-0.0074,-0.04,-0.035,0,0,9.4e-05,9.5e-05,0.021,0.071,0.091,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00048,3e-05,0.00055,0.00029,0.00049,0.00054,1,1 +27290000,0.77,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.5e-05,0.019,0.072,0.094,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00045,2.9e-05,0.00052,0.00026,0.00046,0.00051,1,1 +27390000,0.77,0.078,-0.033,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0074,-0.035,-0.032,0,0,9.5e-05,9.6e-05,0.017,0.073,0.094,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00043,2.8e-05,0.0005,0.00023,0.00044,0.00049,1,1 +27490000,0.77,0.062,-0.029,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0071,-0.034,-0.032,0,0,9.6e-05,9.6e-05,0.015,0.074,0.093,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00042,2.7e-05,0.00049,0.00021,0.00043,0.00048,1,1 +27590000,0.77,0.05,-0.025,-0.63,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.028,-0.13,-0.17,-0.039,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.7e-05,0.014,0.074,0.092,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00041,2.6e-05,0.00048,0.0002,0.00042,0.00048,1,1 +27690000,0.77,0.048,-0.025,-0.63,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.028,-0.13,-0.17,-0.04,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.7e-05,0.013,0.074,0.09,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.0004,2.6e-05,0.00048,0.00019,0.00042,0.00047,1,1 +27790000,0.77,0.05,-0.025,-0.63,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,9.7e-05,0.082,-0.027,-0.13,-0.17,-0.04,0.47,-0.0056,-0.032,-0.031,0,0,9.8e-05,9.8e-05,0.012,0.074,0.089,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00039,2.6e-05,0.00047,0.00017,0.00041,0.00047,1,1 +27890000,0.77,0.048,-0.024,-0.63,2.3,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,9.6e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.46,-0.0056,-0.031,-0.031,0,0,9.9e-05,9.8e-05,0.011,0.075,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00039,2.5e-05,0.00047,0.00016,0.0004,0.00047,1,1 +27990000,0.77,0.044,-0.023,-0.63,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.5e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.47,-0.0056,-0.031,-0.031,0,0,0.0001,9.9e-05,0.01,0.075,0.088,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.5e-05,0.00047,0.00016,0.0004,0.00046,1,1 +28090000,0.78,0.058,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0096,0.076,0.088,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00038,2.4e-05,0.00046,0.00015,0.00039,0.00046,1,1 +28190000,0.77,0.071,-0.031,-0.63,2.4,1.7,-0.93,3.5,2.4,-3.7e+02,-0.00095,-0.0058,8.9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,0.0001,0.0001,0.0091,0.077,0.088,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00037,2.4e-05,0.00046,0.00014,0.00038,0.00045,1,1 +28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.5e-05,0.083,-0.024,-0.13,-0.17,-0.04,0.46,-0.0048,-0.029,-0.029,0,0,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1 +28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,8e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.077,0.084,0.0061,0.75,0.79,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1 +28490000,0.78,0.0015,-0.0059,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.5e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1 +28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.083,-0.022,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1 +28690000,0.78,-0.0032,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,7e-05,0.082,-0.022,-0.12,-0.17,-0.041,0.46,-0.0044,-0.028,-0.029,0,0,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1 +28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.5e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1 +28890000,0.78,-0.0033,-0.0037,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6.1e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1 +28990000,0.78,-0.0028,-0.0039,-0.62,2.1,1.5,0.98,5.4,3.8,-3.7e+02,-0.001,-0.0058,5.5e-05,0.081,-0.02,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29090000,0.78,-0.0024,-0.004,-0.62,2,1.5,0.97,5.6,4,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.085,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29190000,0.78,-0.0021,-0.0041,-0.62,2,1.5,0.97,5.8,4.1,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.083,0.087,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1 +29290000,0.78,-0.0013,-0.0043,-0.62,1.9,1.5,0.99,6,4.2,-3.7e+02,-0.001,-0.0058,4.6e-05,0.08,-0.019,-0.12,-0.17,-0.041,0.46,-0.0036,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.00011,0.00037,0.00043,1,1 +29390000,0.78,9e-05,-0.0046,-0.62,1.9,1.4,1,6.2,4.4,-3.7e+02,-0.001,-0.0058,3.9e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1 +29490000,0.78,0.0013,-0.005,-0.62,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.7e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1 +29590000,0.78,0.0023,-0.0052,-0.62,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0057,3.4e-05,0.079,-0.017,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1 +29690000,0.78,0.003,-0.0055,-0.62,1.7,1.4,0.99,6.7,4.8,-3.7e+02,-0.001,-0.0057,2.9e-05,0.079,-0.016,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.9e-05,0.00037,0.00043,1,1 +29790000,0.78,0.0034,-0.0056,-0.62,1.7,1.4,0.98,6.9,5,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.015,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.027,0,0,0.00011,0.0001,0.0054,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.8e-05,0.00037,0.00042,1,1 +29890000,0.78,0.0036,-0.0057,-0.62,1.7,1.3,0.97,7.1,5.1,-3.7e+02,-0.001,-0.0057,2e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.7e-05,0.00037,0.00042,1,1 +29990000,0.78,0.0036,-0.0057,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1 +30090000,0.78,0.0035,-0.0057,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1.2e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1 +30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.3e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1 +30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,1e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1 +30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,5.8e-06,0.077,-0.012,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.11,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1 +30490000,0.78,0.0025,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,4.7e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1 +30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,2.6e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1 +30690000,0.78,0.0017,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-7.1e-07,0.076,-0.0098,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1 +30790000,0.78,0.0013,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-3.8e-06,0.076,-0.0096,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1 +30890000,0.78,0.00091,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-6.8e-06,0.075,-0.0088,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1 +30990000,0.78,0.00032,-0.005,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1e-05,0.075,-0.008,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1 +31090000,0.78,-0.00023,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.5e-05,0.074,-0.0073,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 +31190000,0.78,-0.00064,-0.0047,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0064,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 +31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2e-05,0.074,-0.0057,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 +31390000,0.78,-0.002,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.074,-0.0051,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 +31490000,0.78,-0.0026,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-2.9e-05,0.073,-0.0044,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 +31590000,0.78,-0.0029,-0.0042,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3e-05,0.073,-0.0037,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1 +31690000,0.78,-0.0037,-0.004,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.072,-0.003,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 +31790000,0.78,-0.0044,-0.0038,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.4e-05,0.072,-0.0021,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 +31890000,0.78,-0.0051,-0.0037,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-3.8e-05,0.071,-0.0012,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 +31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.071,-0.0003,-0.12,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1 +32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.95,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-4.8e-05,0.07,0.0004,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 +32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-5.7e-05,0.07,0.0013,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 +32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.1e-05,0.069,0.0024,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 +32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.069,0.003,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 +32490000,0.78,-0.009,-0.0029,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.068,0.0038,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32590000,0.78,-0.0093,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.8e-05,0.068,0.0041,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.067,0.0047,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.067,0.0051,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 +32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.066,0.0056,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 +32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0062,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 +33090000,0.79,-0.0092,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.065,0.0064,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 +33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.065,0.0065,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 +33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.065,0.0063,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1 +33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.064,0.006,-0.11,-0.18,-0.041,0.46,-0.0009,-0.027,-0.024,0,0,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8e-05,0.00032,0.00039,1,1 +33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.3e-05,0.064,0.0061,-0.11,-0.18,-0.043,0.46,-0.0004,-0.02,-0.024,0,0,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1 +33590000,0.99,-0.0083,-0.00011,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.8e-05,0.064,0.0061,-0.11,-0.19,-0.044,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1 +33690000,1,-0.012,0.0041,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.064,0.0061,-0.11,-0.19,-0.045,0.46,0.00018,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1 +33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00053,-0.0066,-0.025,0,0,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1 +33890000,0.93,-0.013,0.0086,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.1e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00075,-0.0053,-0.025,0,0,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1 +33990000,0.86,-0.015,0.0072,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0058,-0.11,-0.2,-0.046,0.46,0.00053,-0.0039,-0.025,0,0,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1 +34090000,0.8,-0.016,0.0064,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0052,-0.11,-0.2,-0.046,0.46,0.0002,-0.0033,-0.025,0,0,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1 +34190000,0.75,-0.014,0.0071,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1 +34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0047,-0.11,-0.2,-0.047,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1 +34390000,0.69,-0.0077,0.01,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0044,-0.11,-0.2,-0.047,0.46,9.4e-05,-0.002,-0.025,0,0,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1 +34490000,0.67,-0.0055,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0043,-0.11,-0.2,-0.047,0.46,5.2e-05,-0.002,-0.025,0,0,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1 +34590000,0.66,-0.0041,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0042,-0.11,-0.2,-0.047,0.46,-4.5e-05,-0.0019,-0.025,0,0,0.00014,9.7e-05,0.0012,0.057,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1 +34690000,0.65,-0.0033,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0042,-0.11,-0.2,-0.047,0.46,1.8e-05,-0.0016,-0.025,0,0,0.00014,9.7e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1 +34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0041,-0.11,-0.2,-0.047,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1 +34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0039,-0.11,-0.2,-0.047,0.46,8.8e-05,-0.0016,-0.025,0,0,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1 +34990000,0.64,-0.0061,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1 +35090000,0.64,-0.0062,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00022,-0.0016,-0.025,0,0,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1 +35190000,0.64,-0.0063,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00025,-0.0015,-0.025,0,0,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1 +35290000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1 +35390000,0.64,-0.0064,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1 +35490000,0.64,-0.0065,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00045,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1 +35590000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00042,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1 +35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1 +35790000,0.64,-0.0065,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1 +35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1 +35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1 +36090000,0.64,-0.0066,0.02,0.77,-3.4,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1 +36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1 +36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0016,-0.025,0,0,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1 +36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1 +36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00055,-0.0015,-0.025,0,0,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1 +36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1 +36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1 +36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00064,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1 +36890000,0.64,-0.0069,0.021,0.77,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0041,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 +36990000,0.64,-0.0069,0.021,0.77,-3.7,-4.1,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0042,-0.11,-0.2,-0.047,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 +37090000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0064,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1 +37190000,0.64,-0.0069,0.021,0.77,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 +37290000,0.64,-0.0069,0.021,0.77,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.7e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 +37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.017,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00071,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1 +37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.7e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0011,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 +37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.067,0.0045,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 +37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 +37790000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 +37890000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0046,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 +37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 +38090000,0.64,-0.0071,0.021,0.77,-4,-4.9,0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1 +38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1 +38290000,0.64,-0.0071,0.021,0.77,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 +38390000,0.64,-0.007,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 +38490000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 +38590000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 +38690000,0.64,-0.007,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.71,0.85,0.0065,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 +38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0046,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1 +38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index aac40d267e0d..c5ad1dd6f49a 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.0089,-0.011,0.00052,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,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 6790000,1,-0.009,-0.011,0.00048,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-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 6890000,1,-0.0088,-0.011,0.0004,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-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 -6990000,-0.29,0.024,-0.0063,0.96,-0.2,-0.03,-0.037,-0.11,-0.017,-0.055,-0.00076,-0.0097,-0.0002,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1 -7090000,-0.28,0.025,-0.0064,0.96,-0.24,-0.045,-0.038,-0.15,-0.025,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.022,0.51,0.075,-0.029,-0.065,0,0,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1 -7190000,-0.28,0.025,-0.0064,0.96,-0.26,-0.053,-0.037,-0.17,-0.031,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.2e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1 -7290000,-0.28,0.025,-0.0065,0.96,-0.29,-0.062,-0.034,-0.2,-0.038,-0.055,-0.00059,-0.01,-0.00021,-0.00088,-0.00017,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1 -7390000,-0.28,0.024,-0.0064,0.96,-0.3,-0.068,-0.032,-0.23,-0.044,-0.052,-0.00058,-0.01,-0.00021,-0.0011,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00086,0.0013,1,1 -7490000,-0.28,0.024,-0.0065,0.96,-0.32,-0.075,-0.026,-0.26,-0.052,-0.046,-0.00057,-0.0099,-0.00021,-0.0015,-0.00025,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1 -7590000,-0.28,0.024,-0.0066,0.96,-0.34,-0.082,-0.022,-0.28,-0.061,-0.041,-0.00055,-0.0098,-0.00021,-0.0016,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00085,0.0013,1,1 -7690000,-0.28,0.024,-0.0066,0.96,-0.35,-0.091,-0.022,-0.31,-0.071,-0.036,-0.00053,-0.0097,-0.00021,-0.0017,-0.00019,-0.13,-0.1,-0.022,0.5,0.079,-0.031,-0.068,0,0,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.00084,0.0013,1,1 -7790000,-0.28,0.023,-0.0064,0.96,-0.36,-0.1,-0.024,-0.34,-0.085,-0.041,-0.00046,-0.0096,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.00084,0.0013,1,1 -7890000,-0.28,0.023,-0.0065,0.96,-0.37,-0.11,-0.025,-0.37,-0.097,-0.045,-0.00044,-0.0095,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00085,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.00083,0.0013,1,1 -7990000,-0.28,0.023,-0.0065,0.96,-0.39,-0.11,-0.021,-0.4,-0.11,-0.041,-0.00047,-0.0094,-0.0002,-0.0016,-0.00017,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0012,0.00083,0.0013,1,1 -8090000,-0.28,0.023,-0.0064,0.96,-0.41,-0.12,-0.022,-0.44,-0.12,-0.044,-0.0004,-0.0094,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0008,0.00082,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,8.8e-05,0.0013,0.0012,0.00083,0.0013,1,1 -8190000,-0.28,0.022,-0.0064,0.96,-0.41,-0.14,-0.017,-0.46,-0.14,-0.038,-0.00033,-0.0092,-0.0002,-0.0016,-0.00023,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00077,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.6e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8290000,-0.28,0.022,-0.0066,0.96,-0.44,-0.14,-0.016,-0.51,-0.15,-0.038,-0.00039,-0.0093,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00075,0.00077,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.4e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8390000,-0.28,0.022,-0.0066,0.96,-0.45,-0.14,-0.015,-0.55,-0.16,-0.036,-0.00039,-0.0092,-0.0002,-0.0017,-0.00018,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8490000,-0.28,0.022,-0.0066,0.96,-0.46,-0.14,-0.016,-0.58,-0.17,-0.041,-0.00048,-0.0091,-0.00019,-0.0016,-9.5e-05,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0007,0.00072,0.053,0.82,0.82,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8590000,-0.28,0.021,-0.0064,0.96,-0.45,-0.15,-0.012,-0.6,-0.19,-0.036,-0.00042,-0.0089,-0.00019,-0.0016,-9.3e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.068,0,0,0.00068,0.0007,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8e-05,0.0013,0.0012,0.00081,0.0013,1,1 -8690000,-0.28,0.021,-0.0066,0.96,-0.47,-0.15,-0.014,-0.64,-0.2,-0.037,-0.00048,-0.0088,-0.00019,-0.0016,-5.5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00066,0.00068,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,7.9e-05,0.0013,0.0012,0.00081,0.0013,1,1 -8790000,-0.28,0.021,-0.0066,0.96,-0.48,-0.16,-0.013,-0.68,-0.22,-0.035,-0.00046,-0.0088,-0.00018,-0.0016,-5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00064,0.00066,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,7.8e-05,0.0013,0.0012,0.00081,0.0013,1,1 -8890000,-0.28,0.021,-0.0066,0.96,-0.47,-0.16,-0.0094,-0.68,-0.23,-0.029,-0.00051,-0.0085,-0.00018,-0.0016,5.8e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00063,0.00064,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,7.7e-05,0.0013,0.0012,0.0008,0.0013,1,1 -8990000,-0.28,0.02,-0.0064,0.96,-0.45,-0.16,-0.0089,-0.68,-0.24,-0.032,-0.00055,-0.0082,-0.00017,-0.0013,0.00016,-0.13,-0.1,-0.023,0.5,0.08,-0.032,-0.069,0,0,0.00061,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,7.6e-05,0.0013,0.0012,0.0008,0.0013,1,1 -9090000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.01,-0.72,-0.22,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00033,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.0006,0.00061,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,7.5e-05,0.0013,0.0012,0.0008,0.0013,1,1 -9190000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.0096,-0.74,-0.22,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00058,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9290000,-0.28,0.02,-0.0062,0.96,-0.46,-0.15,-0.0082,-0.74,-0.24,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00057,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9390000,-0.28,0.019,-0.006,0.96,-0.45,-0.17,-0.0071,-0.75,-0.27,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.0005,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00056,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,7.3e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9490000,-0.28,0.019,-0.0061,0.96,-0.46,-0.16,-0.0055,-0.78,-0.27,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00059,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00055,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,7.2e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9590000,-0.28,0.019,-0.0061,0.96,-0.47,-0.18,-0.0054,-0.82,-0.32,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00046,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.2e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9690000,-0.28,0.019,-0.006,0.96,-0.47,-0.19,-0.0026,-0.83,-0.35,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00045,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00055,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9790000,-0.28,0.019,-0.006,0.96,-0.48,-0.2,-0.004,-0.88,-0.39,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00038,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9890000,-0.28,0.019,-0.0059,0.96,-0.47,-0.21,-0.0028,-0.88,-0.41,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00044,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9990000,-0.28,0.019,-0.0059,0.96,-0.49,-0.22,-0.0021,-0.93,-0.44,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00037,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10090000,-0.28,0.019,-0.0058,0.96,-0.49,-0.23,-0.00087,-0.96,-0.5,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10190000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-3e-05,-0.97,-0.56,-0.031,-0.00028,-0.007,-0.00015,-0.00026,0.00016,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10290000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-0.0012,-0.98,-0.57,-0.03,-0.00034,-0.0069,-0.00014,-0.00014,0.00022,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10390000,-0.28,0.019,-0.0056,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00014,-0.03,-0.00038,-0.0067,-0.00014,1.3e-05,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10490000,-0.28,0.019,-0.0056,0.96,-0.01,-0.0085,0.0071,0.00025,-0.0008,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00023,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00051,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10590000,-0.28,0.019,-0.0055,0.96,-0.021,-0.0072,0.013,-0.0011,-0.00056,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00057,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10690000,-0.28,0.019,-0.0054,0.96,-0.033,-0.0096,0.016,-0.0038,-0.0014,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00056,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10790000,-0.28,0.019,-0.0053,0.96,-0.033,-0.013,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,2.6e-05,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10890000,-0.28,0.019,-0.0052,0.96,-0.043,-0.018,0.01,-0.0036,-0.0034,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.00017,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,6.9e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10990000,-0.28,0.019,-0.0052,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00057,-0.0064,-0.00012,0.0058,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.9e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11090000,-0.28,0.019,-0.0053,0.96,-0.05,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00046,-0.0063,-0.00013,0.006,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.9e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11190000,-0.28,0.018,-0.0054,0.96,-0.041,-0.025,0.027,-0.002,-0.0027,-0.0011,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.8e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11290000,-0.28,0.018,-0.0054,0.96,-0.05,-0.027,0.026,-0.0065,-0.0052,-0.00073,-0.00048,-0.0063,-0.00013,0.013,0.0014,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.8e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11390000,-0.28,0.018,-0.0053,0.96,-0.043,-0.023,0.017,-0.0037,-0.0033,-0.0092,-0.00053,-0.0063,-0.00013,0.019,0.0028,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11490000,-0.28,0.018,-0.0052,0.96,-0.05,-0.025,0.021,-0.0082,-0.0059,-0.003,-0.00054,-0.0063,-0.00012,0.019,0.003,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11590000,-0.28,0.018,-0.0053,0.96,-0.044,-0.021,0.019,-0.005,-0.0038,-0.0041,-0.00058,-0.0063,-0.00012,0.025,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00031,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11690000,-0.28,0.017,-0.0053,0.96,-0.051,-0.025,0.019,-0.0097,-0.0061,-0.0053,-0.00062,-0.0063,-0.00012,0.024,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.088,0.088,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.8e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11790000,-0.28,0.017,-0.0052,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.00071,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 -11890000,-0.28,0.017,-0.0054,0.96,-0.049,-0.027,0.018,-0.01,-0.0079,-0.0016,-0.0007,-0.0063,-0.00012,0.03,0.0044,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 -11990000,-0.28,0.017,-0.0054,0.96,-0.039,-0.021,0.015,-0.0064,-0.0052,-0.0052,-0.00073,-0.0063,-0.00012,0.036,0.0065,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 -12090000,-0.28,0.017,-0.0053,0.96,-0.045,-0.022,0.018,-0.011,-0.0074,0.00087,-0.0007,-0.0062,-0.00012,0.037,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,6.8e-05,0.0013,0.0012,0.00073,0.0013,1,1 -12190000,-0.28,0.017,-0.0053,0.96,-0.038,-0.013,0.017,-0.0054,-0.0028,0.0028,-0.00066,-0.0062,-0.00012,0.042,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12290000,-0.28,0.017,-0.0054,0.96,-0.04,-0.011,0.016,-0.0094,-0.004,0.0038,-0.00064,-0.0062,-0.00012,0.043,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12390000,-0.28,0.016,-0.0054,0.96,-0.033,-0.0082,0.014,-0.0051,-0.0026,-0.0022,-0.00063,-0.0062,-0.00012,0.046,0.0086,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12490000,-0.28,0.016,-0.0054,0.96,-0.036,-0.0092,0.018,-0.0087,-0.0035,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12590000,-0.28,0.016,-0.0053,0.96,-0.03,-0.008,0.019,-0.0035,-0.0039,0.0017,-0.00062,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12690000,-0.28,0.016,-0.0053,0.96,-0.033,-0.0061,0.019,-0.0066,-0.0046,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.8e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12790000,-0.28,0.016,-0.0051,0.96,-0.023,-0.012,0.02,-0.0016,-0.0076,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.5e-06,7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 -12890000,-0.28,0.016,-0.0051,0.96,-0.025,-0.012,0.021,-0.0039,-0.0089,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0071,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 -12990000,-0.28,0.016,-0.0051,0.96,-0.021,-0.0096,0.022,-0.0012,-0.0062,0.0096,-0.00076,-0.0061,-0.00012,0.054,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 -13090000,-0.28,0.016,-0.0051,0.96,-0.023,-0.011,0.019,-0.0033,-0.0075,0.0084,-0.0008,-0.006,-0.00011,0.054,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.0079,0.0082,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 -13190000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.018,-0.0017,-0.0085,0.009,-0.00082,-0.006,-0.00011,0.055,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0013,1,1 -13290000,-0.28,0.016,-0.005,0.96,-0.02,-0.011,0.016,-0.0037,-0.0097,0.0083,-0.00081,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0073,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13390000,-0.28,0.016,-0.005,0.96,-0.017,-0.0081,0.015,-0.0014,-0.0067,0.0089,-0.00079,-0.006,-0.00011,0.057,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.9e-05,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13490000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.015,-0.0032,-0.0078,0.0051,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,0.0001,0.0001,0.051,0.053,0.053,0.009,0.068,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13590000,-0.28,0.016,-0.005,0.96,-0.014,-0.0072,0.016,0.0017,-0.0055,0.0036,-0.00077,-0.006,-0.00011,0.059,0.0088,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,9.2e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13690000,-0.28,0.016,-0.0049,0.96,-0.015,-0.0064,0.016,0.00027,-0.0063,0.0062,-0.0008,-0.0059,-0.00011,0.059,0.0091,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.3e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0055,0.0058,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -13790000,-0.28,0.015,-0.0049,0.96,-0.011,-0.0044,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.06,0.0089,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.7e-05,8.6e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -13890000,-0.28,0.015,-0.0048,0.96,-0.012,-0.0055,0.017,0.0044,-0.0038,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0091,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.8e-05,8.7e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -13990000,-0.28,0.015,-0.0048,0.96,-0.014,-0.0093,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0095,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.07,0,0,8.3e-05,8.2e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14090000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0034,0.017,0.0023,-0.0048,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14190000,-0.28,0.015,-0.005,0.96,-0.01,-0.0023,0.017,0.0036,-0.0038,0.0033,-0.00074,-0.0059,-0.00011,0.062,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14290000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0026,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.062,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0042,0.0045,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14390000,-0.28,0.015,-0.0049,0.96,-0.012,-0.0022,0.017,0.0036,-0.0046,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0088,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14490000,-0.28,0.015,-0.0051,0.96,-0.012,-0.0015,0.02,0.0023,-0.0046,0.014,-0.00071,-0.0059,-0.00012,0.063,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14590000,-0.28,0.015,-0.0051,0.96,-0.015,-0.0032,0.018,0.0007,-0.0051,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.4e-05,7.3e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14690000,-0.28,0.015,-0.0051,0.96,-0.016,-0.0035,0.018,-0.00089,-0.0056,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0088,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.5e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14790000,-0.28,0.015,-0.0052,0.96,-0.019,-0.00093,0.018,-0.00059,-0.0012,0.013,-0.00073,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14890000,-0.28,0.015,-0.0051,0.96,-0.02,0.00099,0.022,-0.0027,-0.0015,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.3e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14990000,-0.28,0.015,-0.0051,0.96,-0.02,-0.001,0.025,-0.0022,-0.0027,0.016,-0.00074,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.1e-05,6.9e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0033,0.0036,0.00044,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -15090000,-0.28,0.015,-0.005,0.96,-0.021,-0.0021,0.029,-0.0043,-0.0028,0.018,-0.00075,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -15190000,-0.28,0.016,-0.0052,0.96,-0.021,-0.00028,0.029,-0.0034,-0.0022,0.02,-0.00073,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -15290000,-0.28,0.016,-0.0052,0.96,-0.024,-0.00035,0.029,-0.0059,-0.0026,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.0007,0.0012,1,1 -15390000,-0.28,0.016,-0.0053,0.96,-0.023,-0.0023,0.028,-0.0046,-0.0022,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15490000,-0.28,0.016,-0.0053,0.96,-0.025,0.00021,0.028,-0.007,-0.0024,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.003,0.0033,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15590000,-0.28,0.016,-0.0053,0.96,-0.022,-0.0041,0.028,-0.0033,-0.0056,0.017,-0.00079,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15690000,-0.28,0.016,-0.0052,0.96,-0.024,-0.0021,0.028,-0.0049,-0.0059,0.018,-0.00083,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15790000,-0.28,0.015,-0.0052,0.96,-0.021,-0.00088,0.028,-0.0035,-0.0051,0.019,-0.00087,-0.0058,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15890000,-0.28,0.016,-0.0053,0.96,-0.021,-0.0021,0.029,-0.0059,-0.005,0.019,-0.00084,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15990000,-0.28,0.015,-0.0052,0.96,-0.02,-0.0017,0.026,-0.0049,-0.0043,0.018,-0.00083,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16090000,-0.28,0.016,-0.0052,0.96,-0.022,-0.00036,0.024,-0.0072,-0.0042,0.018,-0.00082,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16190000,-0.28,0.016,-0.0052,0.96,-0.02,-0.0002,0.023,-0.0071,-0.0035,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16290000,-0.28,0.015,-0.0052,0.96,-0.022,0.00077,0.022,-0.009,-0.0035,0.016,-0.00081,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00042,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16390000,-0.28,0.015,-0.0051,0.96,-0.023,0.00023,0.023,-0.007,-0.0034,0.017,-0.00082,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16490000,-0.28,0.016,-0.0052,0.96,-0.027,0.0013,0.025,-0.0098,-0.0033,0.021,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16590000,-0.28,0.016,-0.0052,0.96,-0.031,0.0017,0.029,-0.0085,-0.0028,0.021,-0.00082,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16690000,-0.28,0.015,-0.0053,0.96,-0.034,0.0053,0.029,-0.011,-0.0026,0.021,-0.00084,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16790000,-0.28,0.015,-0.0051,0.96,-0.035,0.005,0.028,-0.0096,-0.0024,0.021,-0.00086,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16890000,-0.28,0.015,-0.005,0.96,-0.035,0.0046,0.029,-0.013,-0.0023,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16990000,-0.28,0.015,-0.0051,0.96,-0.032,0.005,0.029,-0.011,-0.0025,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0024,0.0027,0.0004,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17090000,-0.28,0.015,-0.0052,0.96,-0.037,0.007,0.028,-0.015,-0.0019,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17190000,-0.28,0.015,-0.0053,0.96,-0.036,0.0088,0.03,-0.014,-0.0036,0.021,-0.00089,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17290000,-0.28,0.015,-0.0053,0.96,-0.039,0.0095,0.029,-0.017,-0.0023,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00039,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17390000,-0.28,0.015,-0.0052,0.96,-0.029,0.014,0.029,-0.01,-0.001,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17490000,-0.28,0.015,-0.0053,0.96,-0.029,0.016,0.029,-0.013,0.00056,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0023,0.0026,0.00038,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17590000,-0.28,0.015,-0.0053,0.96,-0.029,0.014,0.028,-0.012,0.0001,0.02,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.7e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17690000,-0.28,0.015,-0.0054,0.96,-0.03,0.014,0.029,-0.015,0.0013,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17790000,-0.28,0.015,-0.0054,0.96,-0.031,0.014,0.029,-0.015,0.0021,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17890000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.017,0.0033,0.032,-0.00094,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17990000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.014,0.0055,0.033,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00036,0.0012,6.7e-05,0.0012,0.0012,0.00069,0.0012,1,1 -18090000,-0.28,0.015,-0.0054,0.96,-0.035,0.017,0.028,-0.018,0.0071,0.031,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18190000,-0.28,0.015,-0.0053,0.96,-0.032,0.015,0.028,-0.013,0.0048,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18290000,-0.28,0.015,-0.0053,0.96,-0.036,0.015,0.027,-0.017,0.006,0.028,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18390000,-0.28,0.015,-0.0052,0.96,-0.032,0.014,0.027,-0.012,0.005,0.027,-0.00099,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0024,0.00034,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18490000,-0.28,0.015,-0.0052,0.96,-0.036,0.013,0.026,-0.015,0.006,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.5e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18590000,-0.28,0.015,-0.0051,0.96,-0.034,0.013,0.026,-0.013,0.0053,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18690000,-0.28,0.015,-0.0051,0.96,-0.034,0.012,0.024,-0.015,0.0063,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18790000,-0.28,0.015,-0.0051,0.96,-0.031,0.012,0.024,-0.012,0.0054,0.028,-0.001,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0021,0.0024,0.00032,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18890000,-0.28,0.015,-0.005,0.96,-0.031,0.012,0.022,-0.015,0.0067,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18990000,-0.28,0.015,-0.005,0.96,-0.029,0.013,0.023,-0.013,0.0058,0.027,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19090000,-0.28,0.015,-0.005,0.96,-0.028,0.013,0.023,-0.016,0.0066,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19190000,-0.28,0.015,-0.005,0.96,-0.026,0.014,0.023,-0.014,0.0065,0.023,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19290000,-0.28,0.015,-0.0049,0.96,-0.027,0.014,0.024,-0.016,0.0078,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19390000,-0.28,0.015,-0.0051,0.96,-0.025,0.013,0.025,-0.014,0.0076,0.021,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19490000,-0.28,0.015,-0.0052,0.96,-0.028,0.014,0.024,-0.018,0.0091,0.021,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19590000,-0.28,0.015,-0.005,0.96,-0.024,0.015,0.026,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19690000,-0.28,0.015,-0.005,0.96,-0.025,0.013,0.025,-0.018,0.0081,0.02,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19790000,-0.28,0.015,-0.0051,0.96,-0.022,0.013,0.023,-0.018,0.0088,0.017,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19890000,-0.28,0.015,-0.0052,0.96,-0.023,0.013,0.023,-0.02,0.01,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19990000,-0.28,0.015,-0.0052,0.96,-0.02,0.014,0.021,-0.015,0.0093,0.012,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20090000,-0.28,0.015,-0.0052,0.96,-0.023,0.017,0.021,-0.018,0.011,0.015,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.6e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20990000,-0.29,0.0064,0.0073,0.96,0.0086,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.5e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0057,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0041,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0098,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22590000,-0.29,0.015,-0.0054,0.96,-0.057,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1 -22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1 -22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.075,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0089,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00081,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0082,0.0099,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0083,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26990000,-0.29,0.015,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27490000,-0.29,0.02,-0.0069,0.96,0.071,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.05,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.064,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29890000,-0.29,0.015,-0.0025,0.96,0.07,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.095,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30590000,-0.29,0.016,-0.0031,0.96,0.061,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30790000,-0.29,0.016,-0.0032,0.96,0.052,-0.015,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.099,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0032,0.8,0.096,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31390000,-0.29,0.015,-0.003,0.96,0.036,0.0017,0.8,0.09,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31490000,-0.29,0.016,-0.0027,0.96,0.037,0.0051,0.8,0.095,-0.037,-0.52,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0068,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-4.3e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31990000,-0.29,0.016,-0.0028,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,1.1e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32090000,-0.28,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,6.9e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.0059,-0.028,-0.0012,-0.0058,3.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.097,-0.0033,0.042,-0.0012,-0.0058,7.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32390000,-0.28,0.016,-0.0034,0.96,0.024,0.032,0.79,0.093,0.00043,0.12,-0.0012,-0.0058,5.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0081,0.12,-0.0012,-0.0058,3.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0012,0.1,-0.0012,-0.0058,-1.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32690000,-0.29,0.015,-0.0065,0.96,-0.0087,0.091,-0.082,0.091,0.0099,0.087,-0.0012,-0.0058,-1.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32790000,-0.29,0.015,-0.0063,0.96,-0.0048,0.09,-0.083,0.092,0.0024,0.072,-0.0012,-0.0058,-7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32890000,-0.29,0.015,-0.0063,0.96,-0.0052,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32990000,-0.29,0.015,-0.0062,0.96,-0.0014,0.091,-0.084,0.092,-0.0018,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33090000,-0.29,0.015,-0.0061,0.96,0.0025,0.097,-0.081,0.092,0.0074,0.036,-0.0013,-0.0058,-9.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33190000,-0.29,0.015,-0.0061,0.96,0.0066,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0015,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0067,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.096,0.0027,0.0017,-0.0013,-0.0058,-2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0013,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0054,-0.028,-0.0013,-0.0058,-2.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.014,-0.032,-0.0013,-0.0057,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.0041,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.0061,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34390000,-0.29,0.015,-0.0053,0.96,0.043,0.097,-0.055,0.093,-0.018,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0082,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.091,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.096,-0.012,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34790000,-0.29,0.014,-0.0052,0.96,0.052,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.095,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1 +6990000,-0.29,0.024,-0.0061,0.96,-0.2,-0.033,-0.037,-0.11,-0.019,-0.055,-0.00071,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1 +7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.049,-0.038,-0.15,-0.027,-0.056,-0.00058,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1 +7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.00054,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1 +7290000,-0.29,0.025,-0.0063,0.96,-0.28,-0.066,-0.034,-0.2,-0.04,-0.055,-0.00053,-0.01,-0.00021,-0.00088,-0.00019,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1 +7390000,-0.29,0.025,-0.0063,0.96,-0.3,-0.072,-0.032,-0.23,-0.048,-0.052,-0.00052,-0.01,-0.00021,-0.0011,-0.00023,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00014,0.0013,0.0013,0.00086,0.0013,1,1 +7490000,-0.29,0.024,-0.0063,0.96,-0.32,-0.08,-0.026,-0.25,-0.056,-0.046,-0.00051,-0.0099,-0.00021,-0.0015,-0.00027,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1 +7590000,-0.29,0.024,-0.0065,0.96,-0.34,-0.087,-0.022,-0.28,-0.065,-0.041,-0.00049,-0.0098,-0.00021,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1 +7690000,-0.29,0.024,-0.0065,0.96,-0.35,-0.096,-0.022,-0.31,-0.076,-0.036,-0.00047,-0.0097,-0.00021,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1 +7790000,-0.29,0.023,-0.0063,0.96,-0.36,-0.11,-0.024,-0.34,-0.09,-0.041,-0.0004,-0.0096,-0.00021,-0.0017,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1 +7890000,-0.29,0.023,-0.0063,0.96,-0.37,-0.11,-0.025,-0.37,-0.1,-0.045,-0.00038,-0.0095,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00086,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.0001,0.0013,0.0013,0.00083,0.0013,1,1 +7990000,-0.29,0.023,-0.0064,0.96,-0.39,-0.12,-0.021,-0.4,-0.11,-0.041,-0.00041,-0.0094,-0.0002,-0.0016,-0.00019,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.8e-05,0.0013,0.0012,0.00083,0.0013,1,1 +8090000,-0.29,0.023,-0.0062,0.96,-0.41,-0.13,-0.022,-0.43,-0.13,-0.044,-0.00034,-0.0094,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.0008,0.00083,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,9.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 +8190000,-0.29,0.022,-0.0063,0.96,-0.41,-0.14,-0.017,-0.46,-0.15,-0.038,-0.00028,-0.0092,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00078,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.4e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8290000,-0.29,0.022,-0.0064,0.96,-0.44,-0.15,-0.016,-0.51,-0.16,-0.038,-0.00033,-0.0093,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00075,0.00078,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.2e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8390000,-0.29,0.022,-0.0065,0.96,-0.45,-0.15,-0.015,-0.55,-0.17,-0.036,-0.00034,-0.0092,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0012,9e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8490000,-0.29,0.022,-0.0065,0.96,-0.46,-0.15,-0.016,-0.58,-0.18,-0.041,-0.00043,-0.0091,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00071,0.00073,0.053,0.82,0.81,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.9e-05,0.0013,0.0012,0.00082,0.0013,1,1 +8590000,-0.29,0.022,-0.0063,0.96,-0.45,-0.16,-0.012,-0.6,-0.2,-0.036,-0.00037,-0.0089,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00069,0.00071,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.7e-05,0.0013,0.0012,0.00081,0.0013,1,1 +8690000,-0.29,0.021,-0.0064,0.96,-0.46,-0.16,-0.014,-0.64,-0.21,-0.037,-0.00042,-0.0088,-0.00019,-0.0016,-7.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00067,0.00069,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,8.6e-05,0.0013,0.0012,0.00081,0.0013,1,1 +8790000,-0.29,0.021,-0.0065,0.96,-0.48,-0.16,-0.013,-0.67,-0.23,-0.035,-0.00041,-0.0088,-0.00019,-0.0016,-6.7e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00065,0.00067,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,8.5e-05,0.0013,0.0012,0.00081,0.0013,1,1 +8890000,-0.29,0.021,-0.0064,0.96,-0.47,-0.16,-0.0093,-0.68,-0.24,-0.029,-0.00046,-0.0085,-0.00018,-0.0016,4.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00063,0.00065,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,8.4e-05,0.0013,0.0012,0.0008,0.0013,1,1 +8990000,-0.29,0.02,-0.0063,0.96,-0.45,-0.17,-0.0088,-0.68,-0.25,-0.032,-0.0005,-0.0082,-0.00017,-0.0013,0.00015,-0.13,-0.1,-0.024,0.5,0.08,-0.032,-0.069,0,0,0.00062,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,8.3e-05,0.0013,0.0012,0.0008,0.0013,1,1 +9090000,-0.29,0.02,-0.0064,0.96,-0.46,-0.16,-0.0099,-0.72,-0.23,-0.032,-0.00067,-0.0082,-0.00016,-0.0012,0.00032,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1 +9190000,-0.29,0.02,-0.0064,0.96,-0.46,-0.15,-0.0095,-0.74,-0.23,-0.033,-0.00077,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9290000,-0.29,0.02,-0.0061,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00077,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9390000,-0.29,0.02,-0.0059,0.96,-0.45,-0.17,-0.007,-0.75,-0.28,-0.031,-0.00069,-0.0077,-0.00015,-0.00085,0.00049,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9490000,-0.29,0.019,-0.006,0.96,-0.46,-0.17,-0.0055,-0.78,-0.28,-0.028,-0.00077,-0.0076,-0.00015,-0.00093,0.00058,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1 +9590000,-0.29,0.019,-0.006,0.96,-0.47,-0.19,-0.0054,-0.82,-0.33,-0.029,-0.00064,-0.0075,-0.00015,-0.00087,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9690000,-0.29,0.019,-0.0059,0.96,-0.47,-0.2,-0.0026,-0.83,-0.36,-0.028,-0.0006,-0.0074,-0.00015,-0.00078,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9790000,-0.29,0.019,-0.0059,0.96,-0.48,-0.21,-0.0039,-0.88,-0.4,-0.029,-0.00052,-0.0074,-0.00015,-0.00077,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9890000,-0.29,0.019,-0.0058,0.96,-0.47,-0.21,-0.0027,-0.88,-0.42,-0.03,-0.00055,-0.0072,-0.00014,-0.00053,0.00044,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1 +9990000,-0.29,0.019,-0.0058,0.96,-0.49,-0.22,-0.002,-0.93,-0.46,-0.032,-0.00049,-0.0072,-0.00015,-0.00044,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10090000,-0.29,0.019,-0.0057,0.96,-0.49,-0.24,-0.00079,-0.96,-0.51,-0.03,-0.00039,-0.0071,-0.00015,-0.00045,0.0003,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10190000,-0.29,0.019,-0.0057,0.96,-0.49,-0.26,4.4e-05,-0.97,-0.58,-0.031,-0.00025,-0.007,-0.00015,-0.00028,0.00017,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10290000,-0.29,0.019,-0.0056,0.96,-0.49,-0.26,-0.0011,-0.98,-0.59,-0.03,-0.00032,-0.0069,-0.00014,-0.00016,0.00024,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10390000,-0.29,0.019,-0.0055,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00015,-0.029,-0.00036,-0.0067,-0.00014,-6.4e-06,0.0003,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1 +10490000,-0.29,0.019,-0.0055,0.96,-0.01,-0.0087,0.0071,0.00024,-0.00081,-0.024,-0.00029,-0.0067,-0.00014,-0.00015,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10590000,-0.29,0.019,-0.0054,0.96,-0.021,-0.0074,0.013,-0.0011,-0.00057,-0.022,-0.00039,-0.0066,-0.00013,0.0001,0.0006,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10690000,-0.29,0.019,-0.0053,0.96,-0.034,-0.01,0.016,-0.0038,-0.0015,-0.018,-0.00037,-0.0065,-0.00013,0.00013,0.00058,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10790000,-0.29,0.019,-0.0052,0.96,-0.034,-0.014,0.014,0.00012,-0.0018,-0.016,-0.0004,-0.0064,-0.00013,0.002,5.7e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10890000,-0.29,0.019,-0.0051,0.96,-0.043,-0.019,0.01,-0.0037,-0.0034,-0.019,-0.00052,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 +10990000,-0.29,0.019,-0.0051,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00056,-0.0064,-0.00012,0.0058,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11090000,-0.29,0.019,-0.0052,0.96,-0.051,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00045,-0.0063,-0.00013,0.006,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11190000,-0.29,0.018,-0.0053,0.96,-0.041,-0.026,0.027,-0.0021,-0.0027,-0.0011,-0.00045,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11290000,-0.29,0.018,-0.0053,0.96,-0.05,-0.027,0.026,-0.0066,-0.0053,-0.00072,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 +11390000,-0.29,0.018,-0.0052,0.96,-0.043,-0.024,0.017,-0.0037,-0.0034,-0.0091,-0.00052,-0.0063,-0.00013,0.019,0.0029,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00037,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11490000,-0.29,0.018,-0.0051,0.96,-0.05,-0.026,0.021,-0.0082,-0.006,-0.003,-0.00053,-0.0062,-0.00012,0.019,0.003,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00037,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11590000,-0.29,0.018,-0.0052,0.96,-0.045,-0.021,0.019,-0.005,-0.0039,-0.004,-0.00057,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11690000,-0.29,0.017,-0.0052,0.96,-0.051,-0.026,0.019,-0.0097,-0.0062,-0.0053,-0.00061,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.087,0.087,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1 +11790000,-0.29,0.017,-0.0051,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.0007,-0.0063,-0.00012,0.03,0.0046,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 +11890000,-0.29,0.017,-0.0053,0.96,-0.049,-0.028,0.018,-0.01,-0.008,-0.0016,-0.00069,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 +11990000,-0.29,0.017,-0.0053,0.96,-0.039,-0.021,0.015,-0.0064,-0.0053,-0.0052,-0.00072,-0.0063,-0.00012,0.037,0.0066,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 +12090000,-0.29,0.017,-0.0052,0.96,-0.045,-0.022,0.018,-0.011,-0.0076,0.00088,-0.0007,-0.0062,-0.00012,0.037,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 +12190000,-0.29,0.017,-0.0052,0.96,-0.038,-0.013,0.017,-0.0054,-0.0029,0.0028,-0.00066,-0.0062,-0.00012,0.043,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12290000,-0.29,0.017,-0.0053,0.96,-0.04,-0.012,0.016,-0.0094,-0.0041,0.0038,-0.00063,-0.0062,-0.00012,0.043,0.0085,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12390000,-0.29,0.016,-0.0053,0.96,-0.033,-0.0087,0.014,-0.0051,-0.0027,-0.0022,-0.00063,-0.0062,-0.00012,0.047,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12490000,-0.29,0.016,-0.0053,0.96,-0.036,-0.0097,0.018,-0.0087,-0.0037,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12590000,-0.29,0.016,-0.0052,0.96,-0.03,-0.0084,0.02,-0.0035,-0.0039,0.0017,-0.00061,-0.0061,-0.00012,0.05,0.0078,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12690000,-0.29,0.016,-0.0052,0.96,-0.033,-0.0065,0.019,-0.0066,-0.0047,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 +12790000,-0.29,0.016,-0.005,0.96,-0.023,-0.012,0.02,-0.0016,-0.0077,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.4e-06,7e-06,2.2e-06,0.0093,0.0096,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1 +12890000,-0.29,0.016,-0.005,0.96,-0.025,-0.013,0.021,-0.004,-0.009,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0073,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1 +12990000,-0.29,0.016,-0.005,0.96,-0.021,-0.0099,0.022,-0.0012,-0.0063,0.0096,-0.00075,-0.0061,-0.00012,0.054,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0083,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1 +13090000,-0.29,0.016,-0.0049,0.96,-0.023,-0.011,0.019,-0.0033,-0.0076,0.0084,-0.00079,-0.006,-0.00011,0.054,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1 +13190000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.018,-0.0017,-0.0086,0.009,-0.00082,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0072,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1 +13290000,-0.29,0.016,-0.0049,0.96,-0.021,-0.011,0.016,-0.0038,-0.0099,0.0084,-0.00081,-0.006,-0.00011,0.056,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13390000,-0.29,0.016,-0.0049,0.96,-0.017,-0.0083,0.015,-0.0014,-0.0068,0.009,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.0001,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13490000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.015,-0.0032,-0.0079,0.0051,-0.00079,-0.006,-0.00011,0.057,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.0001,0.0001,0.051,0.053,0.053,0.009,0.067,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13590000,-0.29,0.016,-0.0049,0.96,-0.014,-0.0075,0.016,0.0017,-0.0056,0.0036,-0.00077,-0.006,-0.00011,0.059,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,9.3e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0059,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 +13690000,-0.29,0.016,-0.0048,0.96,-0.015,-0.0066,0.016,0.00026,-0.0063,0.0062,-0.00079,-0.0059,-0.00011,0.059,0.0093,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,9.4e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +13790000,-0.29,0.015,-0.0048,0.96,-0.011,-0.0047,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.061,0.0092,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,8.7e-05,8.7e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +13890000,-0.29,0.015,-0.0047,0.96,-0.012,-0.0058,0.017,0.0044,-0.0039,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0093,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,8.8e-05,8.8e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +13990000,-0.29,0.015,-0.0047,0.96,-0.014,-0.0096,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0097,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,8.3e-05,8.3e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0047,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14090000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0037,0.017,0.0022,-0.0049,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14190000,-0.29,0.015,-0.0048,0.96,-0.01,-0.0025,0.017,0.0035,-0.0039,0.0033,-0.00073,-0.006,-0.00011,0.063,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0046,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14290000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0029,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.063,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,8.1e-05,8e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14390000,-0.29,0.015,-0.0048,0.96,-0.012,-0.0025,0.017,0.0036,-0.0047,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0043,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14490000,-0.29,0.015,-0.005,0.96,-0.012,-0.0018,0.02,0.0022,-0.0047,0.014,-0.00071,-0.0059,-0.00012,0.064,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.8e-05,7.7e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14590000,-0.29,0.015,-0.005,0.96,-0.015,-0.0035,0.018,0.00068,-0.0052,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.5e-05,7.4e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0038,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14690000,-0.29,0.015,-0.005,0.96,-0.016,-0.0038,0.018,-0.00092,-0.0057,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14790000,-0.29,0.015,-0.0051,0.96,-0.019,-0.0012,0.018,-0.00061,-0.0012,0.013,-0.00072,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.0007,0.022,-0.0027,-0.0016,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +14990000,-0.29,0.015,-0.005,0.96,-0.02,-0.0013,0.025,-0.0022,-0.0028,0.016,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +15090000,-0.29,0.016,-0.0049,0.96,-0.021,-0.0024,0.029,-0.0043,-0.0029,0.018,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00056,0.029,-0.0034,-0.0023,0.02,-0.00073,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 +15290000,-0.29,0.016,-0.0051,0.96,-0.024,-0.00067,0.029,-0.0059,-0.0028,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15390000,-0.29,0.016,-0.0052,0.96,-0.023,-0.0026,0.028,-0.0046,-0.0023,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15490000,-0.29,0.016,-0.0052,0.96,-0.025,-0.00012,0.028,-0.007,-0.0025,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0045,0.028,-0.0033,-0.0057,0.017,-0.00078,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15690000,-0.29,0.016,-0.0051,0.96,-0.024,-0.0024,0.028,-0.0049,-0.0061,0.018,-0.00083,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15790000,-0.29,0.015,-0.0051,0.96,-0.021,-0.0012,0.028,-0.0035,-0.0052,0.019,-0.00087,-0.0058,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15890000,-0.29,0.016,-0.0052,0.96,-0.021,-0.0024,0.029,-0.0059,-0.0052,0.019,-0.00084,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0019,0.026,-0.0049,-0.0044,0.018,-0.00083,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00065,0.024,-0.0072,-0.0044,0.018,-0.00082,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00046,0.023,-0.0071,-0.0036,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16290000,-0.29,0.016,-0.0051,0.96,-0.022,0.00049,0.022,-0.0091,-0.0037,0.017,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16390000,-0.29,0.016,-0.005,0.96,-0.023,-6.6e-05,0.023,-0.007,-0.0036,0.017,-0.00082,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16490000,-0.29,0.016,-0.0051,0.96,-0.027,0.0009,0.025,-0.0098,-0.0035,0.021,-0.00081,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16590000,-0.29,0.016,-0.0051,0.96,-0.031,0.0013,0.029,-0.0085,-0.003,0.021,-0.00082,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16690000,-0.29,0.015,-0.0051,0.96,-0.034,0.0049,0.029,-0.011,-0.0028,0.021,-0.00084,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16790000,-0.29,0.015,-0.005,0.96,-0.035,0.0046,0.028,-0.0096,-0.0025,0.021,-0.00086,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0028,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16890000,-0.29,0.015,-0.0049,0.96,-0.035,0.0041,0.029,-0.013,-0.0025,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6.1e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +16990000,-0.29,0.015,-0.005,0.96,-0.032,0.0045,0.029,-0.011,-0.0027,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17090000,-0.29,0.015,-0.0051,0.96,-0.037,0.0065,0.028,-0.015,-0.0022,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17190000,-0.29,0.015,-0.0052,0.96,-0.036,0.0083,0.03,-0.014,-0.0038,0.021,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17290000,-0.29,0.015,-0.0052,0.96,-0.039,0.009,0.03,-0.018,-0.0026,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17390000,-0.29,0.015,-0.0051,0.96,-0.029,0.014,0.029,-0.01,-0.0013,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17490000,-0.29,0.015,-0.0052,0.96,-0.029,0.015,0.029,-0.013,0.00029,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17590000,-0.29,0.015,-0.0052,0.96,-0.029,0.013,0.028,-0.012,-0.00011,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17690000,-0.29,0.015,-0.0052,0.96,-0.03,0.014,0.029,-0.016,0.001,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17790000,-0.29,0.015,-0.0053,0.96,-0.031,0.014,0.029,-0.015,0.0018,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0026,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17890000,-0.29,0.015,-0.0052,0.96,-0.035,0.015,0.029,-0.017,0.003,0.032,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 +17990000,-0.29,0.015,-0.0052,0.96,-0.034,0.016,0.029,-0.014,0.0053,0.033,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18090000,-0.29,0.015,-0.0052,0.96,-0.036,0.017,0.028,-0.018,0.0068,0.031,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18190000,-0.29,0.015,-0.0052,0.96,-0.032,0.014,0.028,-0.013,0.0046,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18290000,-0.29,0.015,-0.0052,0.96,-0.036,0.014,0.027,-0.017,0.0057,0.028,-0.00098,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18390000,-0.29,0.015,-0.0051,0.96,-0.032,0.014,0.027,-0.012,0.0048,0.027,-0.00099,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18490000,-0.29,0.015,-0.0051,0.96,-0.036,0.013,0.026,-0.015,0.0057,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0025,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18590000,-0.29,0.015,-0.005,0.96,-0.034,0.013,0.026,-0.013,0.0051,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18690000,-0.29,0.015,-0.005,0.96,-0.034,0.012,0.025,-0.015,0.006,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18790000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.024,-0.012,0.0052,0.028,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18890000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.022,-0.015,0.0065,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +18990000,-0.29,0.015,-0.0049,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19090000,-0.29,0.015,-0.0049,0.96,-0.028,0.013,0.024,-0.016,0.0064,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19190000,-0.29,0.015,-0.0049,0.96,-0.026,0.014,0.023,-0.014,0.0063,0.023,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19390000,-0.29,0.015,-0.005,0.96,-0.026,0.012,0.025,-0.015,0.0074,0.021,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19690000,-0.29,0.015,-0.0049,0.96,-0.025,0.013,0.025,-0.018,0.0078,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19790000,-0.29,0.015,-0.005,0.96,-0.022,0.013,0.023,-0.018,0.0085,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19890000,-0.29,0.015,-0.005,0.96,-0.023,0.013,0.023,-0.02,0.0098,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +19990000,-0.29,0.015,-0.005,0.96,-0.02,0.014,0.021,-0.016,0.009,0.012,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20090000,-0.29,0.015,-0.005,0.96,-0.023,0.016,0.021,-0.018,0.01,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20190000,-0.29,0.015,-0.005,0.96,-0.024,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20290000,-0.29,0.015,-0.005,0.96,-0.022,0.016,0.022,-0.021,0.012,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20390000,-0.29,0.015,-0.005,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1 +20490000,-0.29,0.015,-0.005,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.3e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20590000,-0.29,0.015,-0.0049,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.2e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20690000,-0.29,0.015,-0.0048,0.96,-0.017,0.016,0.023,-0.025,0.014,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20790000,-0.29,0.015,-0.0042,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20890000,-0.29,0.01,0.0044,0.96,-0.0063,0.0016,-0.11,-0.021,0.011,0.0066,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 +20990000,-0.29,0.0063,0.0074,0.96,0.0088,-0.015,-0.25,-0.017,0.0081,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21090000,-0.29,0.0069,0.0058,0.96,0.023,-0.028,-0.37,-0.015,0.0062,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21190000,-0.29,0.0088,0.0033,0.96,0.029,-0.033,-0.5,-0.013,0.0046,-0.075,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.8e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21290000,-0.29,0.01,0.0012,0.96,0.027,-0.036,-0.63,-0.01,0.002,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21390000,-0.29,0.011,-0.00024,0.96,0.021,-0.029,-0.75,-0.012,0.0052,-0.2,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21490000,-0.29,0.012,-0.00099,0.96,0.014,-0.028,-0.89,-0.0097,0.0021,-0.28,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21590000,-0.29,0.012,-0.0015,0.96,0.0028,-0.022,-1,-0.014,0.0068,-0.37,-0.0011,-0.0058,-0.00012,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.002,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21690000,-0.29,0.012,-0.0018,0.96,-0.0025,-0.019,-1.1,-0.014,0.004,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21790000,-0.29,0.012,-0.0022,0.96,-0.0083,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0072,-1.4,-0.016,0.0097,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.001,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22090000,-0.29,0.013,-0.0039,0.96,-0.023,0.0043,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22190000,-0.29,0.013,-0.0043,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22290000,-0.29,0.014,-0.005,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22390000,-0.29,0.014,-0.0053,0.96,-0.045,0.022,-1.4,-0.038,0.029,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22490000,-0.29,0.015,-0.0054,0.96,-0.052,0.028,-1.4,-0.043,0.032,-1.6,-0.001,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22590000,-0.29,0.015,-0.0052,0.96,-0.057,0.034,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22690000,-0.29,0.015,-0.0052,0.96,-0.062,0.039,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 +22790000,-0.29,0.016,-0.0051,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1 +22890000,-0.29,0.016,-0.0052,0.96,-0.073,0.048,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1 +22990000,-0.29,0.016,-0.005,0.96,-0.076,0.048,-1.4,-0.065,0.045,-2.3,-0.0011,-0.0058,-7e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23090000,-0.29,0.017,-0.005,0.96,-0.082,0.052,-1.4,-0.072,0.05,-2.5,-0.0011,-0.0058,-6.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23190000,-0.29,0.017,-0.0049,0.96,-0.084,0.047,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.1e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23290000,-0.29,0.017,-0.0054,0.96,-0.09,0.051,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23390000,-0.29,0.017,-0.0053,0.96,-0.09,0.054,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.8e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23490000,-0.29,0.017,-0.0053,0.96,-0.096,0.054,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23590000,-0.29,0.017,-0.0055,0.96,-0.095,0.048,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23690000,-0.29,0.018,-0.006,0.96,-0.094,0.051,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.2e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23790000,-0.29,0.021,-0.0075,0.96,-0.079,0.048,-0.95,-0.08,0.047,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23890000,-0.29,0.025,-0.01,0.96,-0.074,0.051,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +23990000,-0.29,0.028,-0.012,0.96,-0.065,0.05,-0.13,-0.074,0.046,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24090000,-0.29,0.027,-0.012,0.96,-0.072,0.058,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.7e-05,0.0012,0.0011,0.00066,0.0012,1,1 +24190000,-0.29,0.023,-0.0092,0.96,-0.076,0.055,0.088,-0.066,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24290000,-0.29,0.019,-0.0072,0.96,-0.08,0.057,0.066,-0.074,0.044,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24390000,-0.29,0.018,-0.0064,0.96,-0.064,0.05,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24490000,-0.29,0.018,-0.0066,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24590000,-0.29,0.018,-0.0072,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24690000,-0.29,0.018,-0.0077,0.96,-0.045,0.044,0.075,-0.046,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24790000,-0.29,0.017,-0.0078,0.96,-0.039,0.042,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24890000,-0.29,0.017,-0.0077,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25090000,-0.29,0.016,-0.0078,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25190000,-0.29,0.016,-0.008,0.96,-0.011,0.042,0.047,-0.0079,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25290000,-0.3,0.016,-0.0082,0.96,-0.006,0.045,0.042,-0.0086,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25390000,-0.3,0.015,-0.0083,0.96,0.003,0.043,0.04,0.0014,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25490000,-0.3,0.015,-0.0084,0.96,0.0074,0.044,0.04,0.0011,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25590000,-0.3,0.015,-0.0085,0.96,0.012,0.04,0.041,0.0086,0.0097,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25690000,-0.3,0.014,-0.008,0.96,0.013,0.039,0.03,0.0099,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25790000,-0.3,0.014,-0.0078,0.96,0.024,0.034,0.03,0.017,0.0035,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25890000,-0.3,0.014,-0.0079,0.96,0.03,0.034,0.033,0.02,0.0078,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +25990000,-0.3,0.014,-0.0079,0.96,0.032,0.029,0.026,0.017,-0.0034,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26090000,-0.3,0.014,-0.0076,0.96,0.037,0.029,0.025,0.021,-0.0013,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26190000,-0.3,0.014,-0.0074,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26290000,-0.3,0.015,-0.0074,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26390000,-0.3,0.015,-0.0068,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26490000,-0.3,0.015,-0.0066,0.96,0.043,0.0087,0.028,0.023,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26590000,-0.3,0.015,-0.006,0.96,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26690000,-0.3,0.015,-0.0059,0.96,0.044,-0.0049,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26790000,-0.3,0.014,-0.0057,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +26990000,-0.3,0.015,-0.0045,0.96,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27090000,-0.3,0.015,-0.0043,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 +27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27290000,-0.3,0.016,-0.0044,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27390000,-0.3,0.018,-0.0056,0.96,0.067,-0.026,0.46,0.007,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27490000,-0.3,0.02,-0.0067,0.95,0.072,-0.028,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27590000,-0.3,0.019,-0.0067,0.96,0.063,-0.03,0.87,0.0077,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27690000,-0.3,0.016,-0.0058,0.96,0.058,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27790000,-0.3,0.015,-0.0047,0.96,0.054,-0.026,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27890000,-0.3,0.015,-0.0043,0.96,0.061,-0.031,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +27990000,-0.3,0.015,-0.0047,0.96,0.061,-0.034,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28090000,-0.3,0.015,-0.005,0.96,0.065,-0.034,0.8,0.026,-0.027,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28190000,-0.3,0.015,-0.0044,0.96,0.062,-0.033,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28290000,-0.3,0.016,-0.0038,0.96,0.066,-0.036,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28390000,-0.3,0.016,-0.0038,0.96,0.068,-0.038,0.81,0.035,-0.034,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28490000,-0.3,0.017,-0.004,0.96,0.07,-0.041,0.81,0.043,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28590000,-0.29,0.017,-0.004,0.96,0.063,-0.042,0.81,0.043,-0.041,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28690000,-0.29,0.016,-0.0039,0.96,0.062,-0.043,0.81,0.049,-0.045,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28790000,-0.29,0.016,-0.0032,0.96,0.06,-0.042,0.81,0.05,-0.044,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28890000,-0.29,0.015,-0.0031,0.96,0.064,-0.044,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +28990000,-0.29,0.016,-0.0028,0.96,0.062,-0.042,0.81,0.058,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29090000,-0.29,0.016,-0.0027,0.96,0.065,-0.043,0.81,0.065,-0.053,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29190000,-0.29,0.016,-0.0026,0.96,0.066,-0.043,0.8,0.067,-0.052,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29290000,-0.29,0.016,-0.0028,0.96,0.071,-0.048,0.81,0.075,-0.056,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29390000,-0.29,0.015,-0.0033,0.96,0.067,-0.045,0.81,0.074,-0.053,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29490000,-0.29,0.015,-0.0033,0.96,0.07,-0.046,0.81,0.081,-0.059,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29590000,-0.29,0.015,-0.0032,0.96,0.068,-0.045,0.81,0.079,-0.057,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29690000,-0.29,0.015,-0.0032,0.96,0.072,-0.044,0.81,0.087,-0.062,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29790000,-0.29,0.015,-0.003,0.96,0.069,-0.038,0.8,0.084,-0.059,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29890000,-0.29,0.015,-0.0024,0.96,0.071,-0.039,0.8,0.092,-0.063,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 +29990000,-0.29,0.016,-0.0025,0.96,0.066,-0.038,0.8,0.087,-0.062,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30090000,-0.29,0.016,-0.0027,0.96,0.067,-0.037,0.8,0.094,-0.064,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30190000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.089,-0.056,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30290000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.096,-0.059,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30390000,-0.29,0.015,-0.0027,0.96,0.06,-0.026,0.8,0.095,-0.053,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30490000,-0.29,0.015,-0.0027,0.96,0.063,-0.026,0.8,0.1,-0.056,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30590000,-0.29,0.016,-0.0029,0.96,0.062,-0.024,0.8,0.098,-0.053,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30690000,-0.29,0.016,-0.0033,0.96,0.059,-0.023,0.8,0.1,-0.056,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30790000,-0.29,0.016,-0.0031,0.96,0.053,-0.014,0.79,0.096,-0.044,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30890000,-0.29,0.015,-0.0025,0.96,0.052,-0.01,0.79,0.1,-0.045,-0.95,-0.0013,-0.0058,-4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +30990000,-0.29,0.015,-0.0026,0.96,0.047,-0.0087,0.79,0.095,-0.043,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31090000,-0.29,0.015,-0.0028,0.96,0.046,-0.0074,0.79,0.1,-0.043,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31190000,-0.29,0.016,-0.0029,0.96,0.043,-0.0043,0.8,0.094,-0.04,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31290000,-0.29,0.016,-0.0031,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31390000,-0.29,0.015,-0.0029,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31490000,-0.29,0.016,-0.0026,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31590000,-0.29,0.016,-0.0024,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-6.1e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31890000,-0.29,0.017,-0.0023,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.8e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +31990000,-0.29,0.016,-0.0026,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,9.1e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32090000,-0.29,0.016,-0.003,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,4.8e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32190000,-0.29,0.016,-0.0033,0.96,0.028,0.028,0.8,0.094,-0.0047,-0.028,-0.0012,-0.0058,3.6e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32290000,-0.29,0.016,-0.0031,0.96,0.027,0.03,0.79,0.098,-0.002,0.042,-0.0012,-0.0058,7.4e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 +32390000,-0.29,0.016,-0.0033,0.96,0.024,0.032,0.79,0.094,0.0016,0.12,-0.0012,-0.0058,5.6e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0093,0.12,-0.0012,-0.0058,3.3e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32590000,-0.29,0.015,-0.0064,0.96,-0.014,0.084,-0.081,0.093,0.0023,0.1,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-1.6e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32790000,-0.29,0.015,-0.0062,0.96,-0.0057,0.09,-0.083,0.093,0.0036,0.072,-0.0012,-0.0058,-7.2e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32890000,-0.29,0.015,-0.0062,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-2.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +32990000,-0.29,0.015,-0.0061,0.96,-0.0024,0.091,-0.084,0.092,-0.00065,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33090000,-0.29,0.015,-0.006,0.96,0.0014,0.097,-0.081,0.092,0.0086,0.036,-0.0013,-0.0058,-9.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.006,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0027,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33390000,-0.3,0.015,-0.0059,0.96,0.014,0.093,-0.078,0.094,-0.0055,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33490000,-0.3,0.015,-0.0059,0.96,0.019,0.097,-0.077,0.097,0.0039,0.0017,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33590000,-0.3,0.015,-0.0057,0.95,0.023,0.095,-0.074,0.096,-0.009,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33690000,-0.3,0.015,-0.0057,0.95,0.026,0.098,-0.075,0.097,-3.8e-05,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.069,0.094,-0.013,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33890000,-0.3,0.015,-0.0056,0.95,0.033,0.098,-0.069,0.097,-0.0041,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +33990000,-0.3,0.015,-0.0055,0.95,0.035,0.096,-0.065,0.096,-0.012,-0.032,-0.0013,-0.0058,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34090000,-0.3,0.015,-0.0055,0.95,0.038,0.1,-0.064,0.099,-0.0028,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 +34190000,-0.3,0.015,-0.0054,0.95,0.039,0.098,-0.061,0.094,-0.015,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34290000,-0.3,0.015,-0.0053,0.95,0.04,0.1,-0.06,0.098,-0.0048,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34390000,-0.3,0.015,-0.0052,0.95,0.042,0.097,-0.055,0.093,-0.016,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34490000,-0.3,0.015,-0.0052,0.95,0.045,0.1,-0.053,0.097,-0.0069,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34590000,-0.3,0.014,-0.0051,0.95,0.045,0.098,0.74,0.092,-0.021,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +34890000,-0.3,0.014,-0.0051,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 From 157f7cf40b943527d19db9eb0f8a4bd6f36d8f66 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 31 May 2024 15:49:26 -0400 Subject: [PATCH 312/652] simplify world_magnetic_model interface (degrees in, degrees out) - this hopefully helps avoid accidental mis-use - try to clarify units everywhere --- .../fake_magnetometer/FakeMagnetometer.cpp | 11 ++--- .../geo_mag_declination.cpp | 47 ++++++++----------- .../geo_mag_declination.h | 14 +++--- .../attitude_estimator_q_main.cpp | 4 +- src/modules/commander/mag_calibration.cpp | 25 +++++----- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 11 ++--- src/modules/ekf2/EKF/ekf_helper.cpp | 4 +- .../sensor_mag_sim/SensorMagSim.cpp | 8 ++-- 8 files changed, 52 insertions(+), 72 deletions(-) diff --git a/src/examples/fake_magnetometer/FakeMagnetometer.cpp b/src/examples/fake_magnetometer/FakeMagnetometer.cpp index 425c09f3a790..56878ec9855c 100644 --- a/src/examples/fake_magnetometer/FakeMagnetometer.cpp +++ b/src/examples/fake_magnetometer/FakeMagnetometer.cpp @@ -66,15 +66,12 @@ void FakeMagnetometer::Run() if (_vehicle_gps_position_sub.copy(&gps)) { if (gps.eph < 1000) { - const double lat = gps.latitude_deg; - const double lon = gps.longitude_deg; - // magnetic field data returned by the geo library using the current GPS position - const float mag_declination_gps = get_mag_declination_radians(lat, lon); - const float mag_inclination_gps = get_mag_inclination_radians(lat, lon); - const float mag_strength_gps = get_mag_strength_gauss(lat, lon); + const float declination_rad = math::radians(get_mag_declination_degrees(gps.latitude_deg, gps.longitude_deg)); + const float inclination_rad = math::radians(get_mag_inclination_degrees(gps.latitude_deg, gps.longitude_deg)); + const float field_strength_gauss = get_mag_strength_gauss(gps.latitude_deg, gps.longitude_deg); - _mag_earth_pred = Dcmf(Eulerf(0, -mag_inclination_gps, mag_declination_gps)) * Vector3f(mag_strength_gps, 0, 0); + _mag_earth_pred = Dcmf(Eulerf(0, -inclination_rad, declination_rad)) * Vector3f(field_strength_gauss, 0, 0); _mag_earth_available = true; } diff --git a/src/lib/world_magnetic_model/geo_mag_declination.cpp b/src/lib/world_magnetic_model/geo_mag_declination.cpp index 97105f4a11e8..64738426f501 100644 --- a/src/lib/world_magnetic_model/geo_mag_declination.cpp +++ b/src/lib/world_magnetic_model/geo_mag_declination.cpp @@ -66,21 +66,21 @@ static constexpr unsigned get_lookup_table_index(float *val, float min, float ma return static_cast((-(min) + *val) / SAMPLING_RES); } -static constexpr float get_table_data(float lat, float lon, const int16_t table[LAT_DIM][LON_DIM]) +static constexpr float get_table_data(float latitude_deg, float longitude_deg, const int16_t table[LAT_DIM][LON_DIM]) { - lat = math::constrain(lat, SAMPLING_MIN_LAT, SAMPLING_MAX_LAT); + latitude_deg = math::constrain(latitude_deg, SAMPLING_MIN_LAT, SAMPLING_MAX_LAT); - if (lon > SAMPLING_MAX_LON) { - lon -= 360; + if (longitude_deg > SAMPLING_MAX_LON) { + longitude_deg -= 360.f; } - if (lon < SAMPLING_MIN_LON) { - lon += 360; + if (longitude_deg < SAMPLING_MIN_LON) { + longitude_deg += 360.f; } /* round down to nearest sampling resolution */ - float min_lat = floorf(lat / SAMPLING_RES) * SAMPLING_RES; - float min_lon = floorf(lon / SAMPLING_RES) * SAMPLING_RES; + float min_lat = floorf(latitude_deg / SAMPLING_RES) * SAMPLING_RES; + float min_lon = floorf(longitude_deg / SAMPLING_RES) * SAMPLING_RES; /* find index of nearest low sampling point */ unsigned min_lat_index = get_lookup_table_index(&min_lat, SAMPLING_MIN_LAT, SAMPLING_MAX_LAT); @@ -92,8 +92,8 @@ static constexpr float get_table_data(float lat, float lon, const int16_t table[ const float data_nw = table[min_lat_index + 1][min_lon_index]; /* perform bilinear interpolation on the four grid corners */ - const float lat_scale = constrain((lat - min_lat) / SAMPLING_RES, 0.f, 1.f); - const float lon_scale = constrain((lon - min_lon) / SAMPLING_RES, 0.f, 1.f); + const float lat_scale = constrain((latitude_deg - min_lat) / SAMPLING_RES, 0.f, 1.f); + const float lon_scale = constrain((longitude_deg - min_lon) / SAMPLING_RES, 0.f, 1.f); const float data_min = lon_scale * (data_se - data_sw) + data_sw; const float data_max = lon_scale * (data_ne - data_nw) + data_nw; @@ -101,36 +101,27 @@ static constexpr float get_table_data(float lat, float lon, const int16_t table[ return lat_scale * (data_max - data_min) + data_min; } -float get_mag_declination_radians(float lat, float lon) -{ - return math::radians(get_mag_declination_degrees(lat, lon)); -} - -float get_mag_declination_degrees(float lat, float lon) +float get_mag_declination_degrees(float latitude_deg, float longitude_deg) { // table stored as scaled degrees - return get_table_data(lat, lon, declination_table) * WMM_DECLINATION_SCALE_TO_DEGREES; -} - -float get_mag_inclination_radians(float lat, float lon) -{ - return math::radians(get_mag_inclination_degrees(lat, lon)); + return get_table_data(latitude_deg, longitude_deg, declination_table) * WMM_DECLINATION_SCALE_TO_DEGREES; } -float get_mag_inclination_degrees(float lat, float lon) +float get_mag_inclination_degrees(float latitude_deg, float longitude_deg) { // table stored as scaled degrees - return get_table_data(lat, lon, inclination_table) * WMM_INCLINATION_SCALE_TO_DEGREES; + return get_table_data(latitude_deg, longitude_deg, inclination_table) * WMM_INCLINATION_SCALE_TO_DEGREES; } -float get_mag_strength_gauss(float lat, float lon) +float get_mag_strength_gauss(float latitude_deg, float longitude_deg) { // 1 Gauss = 1e4 Tesla - return get_mag_strength_tesla(lat, lon) * 1e4f; + return get_mag_strength_tesla(latitude_deg, longitude_deg) * 1e4f; } -float get_mag_strength_tesla(float lat, float lon) +float get_mag_strength_tesla(float latitude_deg, float longitude_deg) { // table stored as scaled nanotesla - return get_table_data(lat, lon, totalintensity_table) * WMM_TOTALINTENSITY_SCALE_TO_NANOTESLA * 1e-9f; + return get_table_data(latitude_deg, longitude_deg, totalintensity_table) + * WMM_TOTALINTENSITY_SCALE_TO_NANOTESLA * 1e-9f; } diff --git a/src/lib/world_magnetic_model/geo_mag_declination.h b/src/lib/world_magnetic_model/geo_mag_declination.h index 790f3b353a07..7e6f34670663 100644 --- a/src/lib/world_magnetic_model/geo_mag_declination.h +++ b/src/lib/world_magnetic_model/geo_mag_declination.h @@ -41,14 +41,12 @@ #pragma once -// Return magnetic declination in degrees or radians -float get_mag_declination_degrees(float lat, float lon); -float get_mag_declination_radians(float lat, float lon); +// Return magnetic declination in degrees +float get_mag_declination_degrees(float latitude_deg, float longitude_deg); -// Return magnetic field inclination in degrees or radians -float get_mag_inclination_degrees(float lat, float lon); -float get_mag_inclination_radians(float lat, float lon); +// Return magnetic field inclination in degrees +float get_mag_inclination_degrees(float latitude_deg, float longitude_deg); // return magnetic field strength in Gauss or Tesla -float get_mag_strength_gauss(float lat, float lon); -float get_mag_strength_tesla(float lat, float lon); +float get_mag_strength_gauss(float latitude_deg, float longitude_deg); +float get_mag_strength_tesla(float latitude_deg, float longitude_deg); diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index 7c47cfca30d6..f6b645397a3d 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -227,8 +227,8 @@ void AttitudeEstimatorQ::update_gps_position() if (_vehicle_gps_position_sub.update(&gps)) { if (_param_att_mag_decl_a.get() && (gps.eph < 20.0f)) { // set magnetic declination automatically - update_mag_declination(get_mag_declination_radians((float)gps.latitude_deg, - (float)gps.longitude_deg)); + float mag_decl_deg = get_mag_declination_degrees(gps.latitude_deg, gps.longitude_deg); + update_mag_declination(math::radians(mag_decl_deg)); } } } diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 02ab015e0f17..4121549bd2ac 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -237,11 +237,8 @@ static float get_sphere_radius() if (gps_sub.copy(&gps)) { if (hrt_elapsed_time(&gps.timestamp) < 100_s && (gps.fix_type >= 2) && (gps.eph < 1000)) { - const double lat = gps.latitude_deg; - const double lon = gps.longitude_deg; - // magnetic field data returned by the geo library using the current GPS position - return get_mag_strength_gauss(lat, lon); + return get_mag_strength_gauss(gps.latitude_deg, gps.longitude_deg); } } } @@ -954,13 +951,14 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma return result; } -int do_mag_calibration_quick(orb_advert_t *mavlink_log_pub, float heading_radians, float latitude, float longitude) +int do_mag_calibration_quick(orb_advert_t *mavlink_log_pub, float heading_radians, + float latitude_deg, float longitude_deg) { // magnetometer quick calibration // if GPS available use world magnetic model to zero mag offsets bool mag_earth_available = false; - if (PX4_ISFINITE(latitude) && PX4_ISFINITE(longitude)) { + if (PX4_ISFINITE(latitude_deg) && PX4_ISFINITE(longitude_deg)) { mag_earth_available = true; } else { @@ -969,8 +967,8 @@ int do_mag_calibration_quick(orb_advert_t *mavlink_log_pub, float heading_radian if (vehicle_gps_position_sub.copy(&gps)) { if ((gps.timestamp != 0) && (gps.eph < 1000)) { - latitude = (float)gps.latitude_deg; - longitude = (float)gps.longitude_deg; + latitude_deg = (float)gps.latitude_deg; + longitude_deg = (float)gps.longitude_deg; mag_earth_available = true; } } @@ -981,14 +979,13 @@ int do_mag_calibration_quick(orb_advert_t *mavlink_log_pub, float heading_radian return PX4_ERROR; } else { - // magnetic field data returned by the geo library using the current GPS position - const float mag_declination_gps = get_mag_declination_radians(latitude, longitude); - const float mag_inclination_gps = get_mag_inclination_radians(latitude, longitude); - const float mag_strength_gps = get_mag_strength_gauss(latitude, longitude); + 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 field_strength_gauss = get_mag_strength_gauss(latitude_deg, longitude_deg); - const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -mag_inclination_gps, mag_declination_gps)) * Vector3f(mag_strength_gps, - 0, 0); + const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -inclination_rad, declination_rad)) + * Vector3f(field_strength_gauss, 0, 0); uORB::Subscription vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; vehicle_attitude_s attitude{}; 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 71018df1c708..abdbec64fc1a 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -99,15 +99,12 @@ void Ekf::collect_gps(const gnssSample &gps) if (gps_rough_2d_fix && (_gps_checks_passed || !_NED_origin_initialised)) { // If we have good GPS data set the origin's WGS-84 position to the last gps fix - const double lat = gps.lat; - #if defined(CONFIG_EKF2_MAGNETOMETER) - const double lon = gps.lon; // set the magnetic field data returned by the geo library using the current GPS position - const float mag_declination_gps = get_mag_declination_radians(lat, lon); - const float mag_inclination_gps = get_mag_inclination_radians(lat, lon); - const float mag_strength_gps = get_mag_strength_gauss(lat, lon); + const float mag_declination_gps = math::radians(get_mag_declination_degrees(gps.lat, gps.lon)); + const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(gps.lat, gps.lon)); + const float mag_strength_gps = get_mag_strength_gauss(gps.lat, gps.lon); if (PX4_ISFINITE(mag_declination_gps) && PX4_ISFINITE(mag_inclination_gps) && PX4_ISFINITE(mag_strength_gps)) { @@ -130,7 +127,7 @@ void Ekf::collect_gps(const gnssSample &gps) } #endif // CONFIG_EKF2_MAGNETOMETER - _earth_rate_NED = calcEarthRateNED((float)math::radians(lat)); + _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); } _wmm_gps_time_last_checked = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 40b6a4239d40..7b6b0b0cace7 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -96,8 +96,8 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons _gps_alt_ref = altitude; #if defined(CONFIG_EKF2_MAGNETOMETER) - const float mag_declination_gps = get_mag_declination_radians(latitude, longitude); - const float mag_inclination_gps = get_mag_inclination_radians(latitude, longitude); + const float mag_declination_gps = math::radians(get_mag_declination_degrees(latitude, longitude)); + const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(latitude, longitude)); const float mag_strength_gps = get_mag_strength_gauss(latitude, longitude); if (PX4_ISFINITE(mag_declination_gps) && PX4_ISFINITE(mag_inclination_gps) && PX4_ISFINITE(mag_strength_gps)) { diff --git a/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp b/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp index ff5e5e31aae2..97c2626f75b4 100644 --- a/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp +++ b/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp @@ -113,11 +113,11 @@ void SensorMagSim::Run() if (gpos.eph < 1000) { // magnetic field data returned by the geo library using the current GPS position - const float mag_declination_gps = get_mag_declination_radians(gpos.lat, gpos.lon); - const float mag_inclination_gps = get_mag_inclination_radians(gpos.lat, gpos.lon); - const float mag_strength_gps = get_mag_strength_gauss(gpos.lat, gpos.lon); + const float declination_rad = math::radians(get_mag_declination_degrees(gpos.lat, gpos.lon)); + const float inclination_rad = math::radians(get_mag_inclination_degrees(gpos.lat, gpos.lon)); + const float field_strength_gauss = get_mag_strength_gauss(gpos.lat, gpos.lon); - _mag_earth_pred = Dcmf(Eulerf(0, -mag_inclination_gps, mag_declination_gps)) * Vector3f(mag_strength_gps, 0, 0); + _mag_earth_pred = Dcmf(Eulerf(0, -inclination_rad, declination_rad)) * Vector3f(field_strength_gauss, 0, 0); _mag_earth_available = true; } From 9a7a977625b15322ea2d267d3c1ddb813d614b5b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 30 May 2024 16:05:41 +0200 Subject: [PATCH 313/652] mavlink_receiver: put all message handling in the same function --- src/modules/mavlink/mavlink_receiver.cpp | 63 +++++++++++------------- 1 file changed, 29 insertions(+), 34 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 0385c6a1ebb6..c98c36b3d668 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -376,9 +376,34 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) } - /* If we've received a valid message, mark the flag indicating so. - This is used in the '-w' command-line flag. */ - _mavlink->set_has_received_messages(true); + /* handle packet with mission manager */ + _mission_manager.handle_message(msg); + + /* handle packet with parameter component */ + if (_mavlink->boot_complete()) { + // make sure mavlink app has booted before we start processing parameter sync + _parameters_manager.handle_message(msg); + + } else { + if (hrt_elapsed_time(&_mavlink->get_first_start_time()) > 20_s) { + PX4_ERR("system boot did not complete in 20 seconds"); + _mavlink->set_boot_complete(); + } + } + + if (_mavlink->ftp_enabled()) { + /* handle packet with ftp component */ + _mavlink_ftp.handle_message(msg); + } + + /* handle packet with log component */ + _mavlink_log_handler.handle_message(msg); + + /* handle packet with timesync component */ + _mavlink_timesync.handle_message(msg); + + /* handle packet with parent object */ + _mavlink->handle_message(msg); } bool @@ -3142,38 +3167,8 @@ MavlinkReceiver::run() _mavlink->set_proto_version(2); } - /* handle generic messages and commands */ handle_message(&msg); - - /* handle packet with mission manager */ - _mission_manager.handle_message(&msg); - - /* handle packet with parameter component */ - if (_mavlink->boot_complete()) { - // make sure mavlink app has booted before we start processing parameter sync - _parameters_manager.handle_message(&msg); - - } else { - if (hrt_elapsed_time(&_mavlink->get_first_start_time()) > 20_s) { - PX4_ERR("system boot did not complete in 20 seconds"); - _mavlink->set_boot_complete(); - } - } - - if (_mavlink->ftp_enabled()) { - /* handle packet with ftp component */ - _mavlink_ftp.handle_message(&msg); - } - - /* handle packet with log component */ - _mavlink_log_handler.handle_message(&msg); - - /* handle packet with timesync component */ - _mavlink_timesync.handle_message(&msg); - - /* handle packet with parent object */ - _mavlink->handle_message(&msg); - + _mavlink->set_has_received_messages(true); // Received first message, unlock wait to transmit '-w' command-line flag update_rx_stats(msg); if (_message_statistics_enabled) { From 68769ea0ec3a199ac12ded46e57d6a6d2fa2b032 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 3 Jun 2024 11:26:43 +0200 Subject: [PATCH 314/652] mavlink: use reference instead of pointer to access the MAVLink instance from protocol classes --- src/modules/mavlink/mavlink_ftp.cpp | 20 +-- src/modules/mavlink/mavlink_ftp.h | 8 +- src/modules/mavlink/mavlink_log_handler.cpp | 10 +- src/modules/mavlink/mavlink_log_handler.h | 4 +- src/modules/mavlink/mavlink_main.cpp | 6 +- src/modules/mavlink/mavlink_main.h | 2 +- src/modules/mavlink/mavlink_mission.cpp | 70 ++++----- src/modules/mavlink/mavlink_mission.h | 4 +- src/modules/mavlink/mavlink_parameters.cpp | 28 ++-- src/modules/mavlink/mavlink_parameters.h | 4 +- src/modules/mavlink/mavlink_receiver.cpp | 146 +++++++++--------- src/modules/mavlink/mavlink_receiver.h | 4 +- .../mavlink_tests/mavlink_ftp_test.cpp | 2 +- .../mavlink/mavlink_tests/mavlink_ftp_test.h | 6 +- src/modules/mavlink/mavlink_timesync.cpp | 4 +- src/modules/mavlink/mavlink_timesync.h | 4 +- 16 files changed, 156 insertions(+), 166 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 566c2ce38e14..a376392c00fd 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -45,17 +45,13 @@ #include "mavlink_ftp.h" #include "mavlink_tests/mavlink_ftp_test.h" -#ifndef MAVLINK_FTP_UNIT_TEST #include "mavlink_main.h" -#else -#include -#endif using namespace time_literals; constexpr const char MavlinkFTP::_root_dir[]; -MavlinkFTP::MavlinkFTP(Mavlink *mavlink) : +MavlinkFTP::MavlinkFTP(Mavlink &mavlink) : _mavlink(mavlink) { // initialize session @@ -96,7 +92,7 @@ MavlinkFTP::_getServerSystemId() return MavlinkFtpTest::serverSystemId; #else // Not unit testing, use the real thing - return _mavlink->get_system_id(); + return _mavlink.get_system_id(); #endif } @@ -108,7 +104,7 @@ MavlinkFTP::_getServerComponentId() return MavlinkFtpTest::serverComponentId; #else // Not unit testing, use the real thing - return _mavlink->get_component_id(); + return _mavlink.get_component_id(); #endif } @@ -120,7 +116,7 @@ MavlinkFTP::_getServerChannel() return MavlinkFtpTest::serverChannel; #else // Not unit testing, use the real thing - return _mavlink->get_channel(); + return _mavlink.get_channel(); #endif } @@ -180,7 +176,7 @@ MavlinkFTP::_process_request( #ifdef MAVLINK_FTP_UNIT_TEST _utRcvMsgFunc(last_reply, _worker_data); #else - mavlink_msg_file_transfer_protocol_send_struct(_mavlink->get_channel(), last_reply); + mavlink_msg_file_transfer_protocol_send_struct(_mavlink.get_channel(), last_reply); #endif return; } @@ -340,7 +336,7 @@ MavlinkFTP::_reply(mavlink_file_transfer_protocol_t *ftp_req) // Unit test hook is set, call that instead _utRcvMsgFunc(ftp_req, _worker_data); #else - mavlink_msg_file_transfer_protocol_send_struct(_mavlink->get_channel(), ftp_req); + mavlink_msg_file_transfer_protocol_send_struct(_mavlink.get_channel(), ftp_req); #endif } @@ -1055,8 +1051,8 @@ void MavlinkFTP::send() #ifndef MAVLINK_FTP_UNIT_TEST // Skip send if not enough room - unsigned max_bytes_to_send = _mavlink->get_free_tx_buf(); - PX4_DEBUG("MavlinkFTP::send max_bytes_to_send(%u) get_free_tx_buf(%u)", max_bytes_to_send, _mavlink->get_free_tx_buf()); + unsigned max_bytes_to_send = _mavlink.get_free_tx_buf(); + PX4_DEBUG("MavlinkFTP::send max_bytes_to_send(%u) get_free_tx_buf(%u)", max_bytes_to_send, _mavlink.get_free_tx_buf()); if (max_bytes_to_send < get_size()) { return; diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h index d6727d58b99a..d5b9ce294688 100644 --- a/src/modules/mavlink/mavlink_ftp.h +++ b/src/modules/mavlink/mavlink_ftp.h @@ -43,11 +43,7 @@ #include #include -#ifndef MAVLINK_FTP_UNIT_TEST #include "mavlink_bridge_header.h" -#else -#include -#endif class MavlinkFtpTest; class Mavlink; @@ -56,7 +52,7 @@ class Mavlink; class MavlinkFTP { public: - MavlinkFTP(Mavlink *mavlink); + MavlinkFTP(Mavlink &mavlink); ~MavlinkFTP(); /** @@ -190,7 +186,7 @@ class MavlinkFTP ReceiveMessageFunc_t _utRcvMsgFunc{}; ///< Unit test override for mavlink message sending void *_worker_data{nullptr}; ///< Additional parameter to _utRcvMsgFunc; - Mavlink *_mavlink; + Mavlink &_mavlink; /* do not allow copying this class */ MavlinkFTP(const MavlinkFTP &); diff --git a/src/modules/mavlink/mavlink_log_handler.cpp b/src/modules/mavlink/mavlink_log_handler.cpp index d4ed61d4285c..a75daf90bad7 100644 --- a/src/modules/mavlink/mavlink_log_handler.cpp +++ b/src/modules/mavlink/mavlink_log_handler.cpp @@ -80,7 +80,7 @@ stat_file(const char *file, time_t *date = nullptr, uint32_t *size = nullptr) } //------------------------------------------------------------------- -MavlinkLogHandler::MavlinkLogHandler(Mavlink *mavlink) +MavlinkLogHandler::MavlinkLogHandler(Mavlink &mavlink) : _mavlink(mavlink) { @@ -123,14 +123,14 @@ MavlinkLogHandler::send() //-- Log Entries while (_current_status == LogHandlerState::Listing - && _mavlink->get_free_tx_buf() > MAVLINK_MSG_ID_LOG_ENTRY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + && _mavlink.get_free_tx_buf() > MAVLINK_MSG_ID_LOG_ENTRY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES && count < MAX_BYTES_SEND) { count += _log_send_listing(); } //-- Log Data while (_current_status == LogHandlerState::SendingData - && _mavlink->get_free_tx_buf() > MAVLINK_MSG_ID_LOG_DATA_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + && _mavlink.get_free_tx_buf() > MAVLINK_MSG_ID_LOG_DATA_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES && count < MAX_BYTES_SEND) { count += _log_send_data(); } @@ -272,7 +272,7 @@ MavlinkLogHandler::_log_send_listing() response.id = _next_entry; response.num_logs = _log_count; response.last_log_num = _last_entry; - mavlink_msg_log_entry_send_struct(_mavlink->get_channel(), &response); + mavlink_msg_log_entry_send_struct(_mavlink.get_channel(), &response); //-- If we're done listing, flag it. if (_next_entry >= _last_entry) { @@ -309,7 +309,7 @@ MavlinkLogHandler::_log_send_data() response.ofs = _current_log_data_offset; response.id = _current_log_index; response.count = read_size; - mavlink_msg_log_data_send_struct(_mavlink->get_channel(), &response); + mavlink_msg_log_data_send_struct(_mavlink.get_channel(), &response); _current_log_data_offset += read_size; _current_log_data_remaining -= read_size; diff --git a/src/modules/mavlink/mavlink_log_handler.h b/src/modules/mavlink/mavlink_log_handler.h index 8993bf41004f..965c26712f1c 100644 --- a/src/modules/mavlink/mavlink_log_handler.h +++ b/src/modules/mavlink/mavlink_log_handler.h @@ -51,7 +51,7 @@ class Mavlink; class MavlinkLogHandler { public: - MavlinkLogHandler(Mavlink *mavlink); + MavlinkLogHandler(Mavlink &mavlink); ~MavlinkLogHandler(); // Handle possible LOG message @@ -93,7 +93,7 @@ class MavlinkLogHandler size_t _log_send_data(); LogHandlerState _current_status{LogHandlerState::Inactive}; - Mavlink *_mavlink; + Mavlink &_mavlink; int _next_entry{0}; int _last_entry{0}; diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 3abd4f71a2ae..aaae2464eeb5 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -100,7 +100,7 @@ bool Mavlink::_boot_complete = false; Mavlink::Mavlink() : ModuleParams(nullptr), - _receiver(this) + _receiver(*this) { // initialise parameter cache mavlink_update_parameters(); @@ -438,12 +438,12 @@ Mavlink::serial_instance_exists(const char *device_name, Mavlink *self) } bool -Mavlink::component_was_seen(int system_id, int component_id, Mavlink *self) +Mavlink::component_was_seen(int system_id, int component_id, Mavlink &self) { LockGuard lg{mavlink_module_mutex}; for (Mavlink *inst : mavlink_module_instances) { - if (inst && (inst != self) && (inst->_receiver.component_was_seen(system_id, component_id))) { + if (inst && (inst != &self) && (inst->_receiver.component_was_seen(system_id, component_id))) { return true; } } diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 17925f8ed8e4..d7a7307b3ebf 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -172,7 +172,7 @@ class Mavlink final : public ModuleParams static bool serial_instance_exists(const char *device_name, Mavlink *self); - static bool component_was_seen(int system_id, int component_id, Mavlink *self = nullptr); + static bool component_was_seen(int system_id, int component_id, Mavlink &self); static void forward_message(const mavlink_message_t *msg, Mavlink *self); diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 5057c1625dbe..1c5437270a1e 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -72,7 +72,7 @@ constexpr uint16_t MavlinkMissionManager::MAX_COUNT[]; (_msg.target_component == MAV_COMP_ID_MISSIONPLANNER) || \ (_msg.target_component == MAV_COMP_ID_ALL))) -MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : +MavlinkMissionManager::MavlinkMissionManager(Mavlink &mavlink) : _mavlink(mavlink) { if (!_dataman_init) { @@ -209,7 +209,7 @@ MavlinkMissionManager::update_geofence_count(dm_item_t fence_dataman_id, unsigne } else { if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { - _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD\t"); + _mavlink.send_statustext_critical("Mission storage: Unable to write to microSD\t"); events::send(events::ID("mavlink_mission_storage_write_failure2"), events::Log::Critical, "Mission: Unable to write to storage"); } @@ -245,7 +245,7 @@ MavlinkMissionManager::update_safepoint_count(dm_item_t safepoint_dataman_id, un } else { if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { - _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD\t"); + _mavlink.send_statustext_critical("Mission storage: Unable to write to microSD\t"); events::send(events::ID("mavlink_mission_storage_write_failure3"), events::Log::Critical, "Mission: Unable to write to storage"); } @@ -270,7 +270,7 @@ MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t t wpa.mission_type = _mission_type; wpa.opaque_id = opaque_id; - mavlink_msg_mission_ack_send_struct(_mavlink->get_channel(), &wpa); + mavlink_msg_mission_ack_send_struct(_mavlink.get_channel(), &wpa); PX4_DEBUG("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); } @@ -284,7 +284,7 @@ MavlinkMissionManager::send_mission_current(uint16_t seq) wpc.mission_id = _crc32[MAV_MISSION_TYPE_MISSION]; wpc.fence_id = _crc32[MAV_MISSION_TYPE_FENCE]; wpc.rally_points_id = _crc32[MAV_MISSION_TYPE_RALLY]; - mavlink_msg_mission_current_send_struct(_mavlink->get_channel(), &wpc); + mavlink_msg_mission_current_send_struct(_mavlink.get_channel(), &wpc); PX4_DEBUG("WPM: Send MISSION_CURRENT seq %d", seq); } @@ -303,7 +303,7 @@ MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_ wpc.mission_type = mission_type; wpc.opaque_id = opaque_id; - mavlink_msg_mission_count_send_struct(_mavlink->get_channel(), &wpc); + mavlink_msg_mission_count_send_struct(_mavlink.get_channel(), &wpc); PX4_DEBUG("WPM: Send MISSION_COUNT %u to ID %u, mission type=%i", wpc.count, wpc.target_system, mission_type); } @@ -350,7 +350,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t break; default: - _mavlink->send_statustext_critical("Received unknown mission type, abort.\t"); + _mavlink.send_statustext_critical("Received unknown mission type, abort.\t"); events::send(events::ID("mavlink_mission_recv_unknown_mis_type"), events::Log::Error, "Received unknown mission type, abort"); break; @@ -368,7 +368,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t wp.seq = seq; wp.current = (_current_seq == seq) ? 1 : 0; - mavlink_msg_mission_item_int_send_struct(_mavlink->get_channel(), &wp); + mavlink_msg_mission_item_int_send_struct(_mavlink.get_channel(), &wp); PX4_DEBUG("WPM: Send MISSION_ITEM_INT seq %u to ID %u", wp.seq, wp.target_system); @@ -381,7 +381,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t wp.seq = seq; wp.current = (_current_seq == seq) ? 1 : 0; - mavlink_msg_mission_item_send_struct(_mavlink->get_channel(), &wp); + mavlink_msg_mission_item_send_struct(_mavlink.get_channel(), &wp); PX4_DEBUG("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system); } @@ -390,7 +390,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { - mavlink_log_critical(_mavlink->get_mavlink_log_pub(), + mavlink_log_critical(_mavlink.get_mavlink_log_pub(), "Mission storage: Unable to read from storage, type: %" PRId8 "\t", (uint8_t)_mission_type); /* EVENT * @description Mission type: {1} @@ -448,7 +448,7 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 wpr.target_component = compid; wpr.seq = seq; wpr.mission_type = _mission_type; - mavlink_msg_mission_request_int_send_struct(_mavlink->get_channel(), &wpr); + mavlink_msg_mission_request_int_send_struct(_mavlink.get_channel(), &wpr); PX4_DEBUG("WPM: Send MISSION_REQUEST_INT seq %u to ID %u", wpr.seq, wpr.target_system); @@ -460,13 +460,13 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 wpr.seq = seq; wpr.mission_type = _mission_type; - mavlink_msg_mission_request_send_struct(_mavlink->get_channel(), &wpr); + mavlink_msg_mission_request_send_struct(_mavlink.get_channel(), &wpr); PX4_DEBUG("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); } } else { - _mavlink->send_statustext_critical("ERROR: Waypoint index exceeds list capacity\t"); + _mavlink.send_statustext_critical("ERROR: Waypoint index exceeds list capacity\t"); events::send(events::ID("mavlink_mission_wp_index_exceeds_list"), events::Log::Error, "Waypoint index eceeds list capacity (maximum: {1})", current_max_item_count()); @@ -481,7 +481,7 @@ MavlinkMissionManager::send_mission_item_reached(uint16_t seq) wp_reached.seq = seq; - mavlink_msg_mission_item_reached_send_struct(_mavlink->get_channel(), &wp_reached); + mavlink_msg_mission_item_reached_send_struct(_mavlink.get_channel(), &wp_reached); PX4_DEBUG("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq); } @@ -490,7 +490,7 @@ void MavlinkMissionManager::send() { // do not send anything over high latency communication - if (_mavlink->get_mode() == Mavlink::MAVLINK_MODE_IRIDIUM) { + if (_mavlink.get_mode() == Mavlink::MAVLINK_MODE_IRIDIUM) { return; } @@ -509,7 +509,7 @@ MavlinkMissionManager::send() send_mission_current(_current_seq); } else { - _mavlink->send_statustext_critical("ERROR: wp index out of bounds\t"); + _mavlink.send_statustext_critical("ERROR: wp index out of bounds\t"); events::send(events::ID("mavlink_mission_wp_index_out_of_bounds"), events::Log::Error, "Waypoint index out of bounds (current {1} \\>= total {2})", mission_result.seq_current, mission_result.seq_total); } @@ -562,7 +562,7 @@ MavlinkMissionManager::send() } else if (_state != MAVLINK_WPM_STATE_IDLE && (_time_last_recv > 0) && hrt_elapsed_time(&_time_last_recv) > MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT) { - _mavlink->send_statustext_critical("Operation timeout\t"); + _mavlink.send_statustext_critical("Operation timeout\t"); events::send(events::ID("mavlink_mission_op_timeout"), events::Log::Error, "Operation timeout, aborting transfer"); @@ -674,7 +674,7 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg) } } else { - _mavlink->send_statustext_critical("REJ. WP CMD: partner id mismatch\t"); + _mavlink.send_statustext_critical("REJ. WP CMD: partner id mismatch\t"); events::send(events::ID("mavlink_mission_partner_id_mismatch"), events::Log::Error, "Rejecting waypoint command, component or system ID mismatch"); @@ -699,7 +699,7 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg) } else { PX4_ERR("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq); - _mavlink->send_statustext_critical("WPM: WP CURR CMD: Not in list\t"); + _mavlink.send_statustext_critical("WPM: WP CURR CMD: Not in list\t"); events::send(events::ID("mavlink_mission_seq_out_of_bounds"), events::Log::Error, "New mission waypoint sequence out of bounds"); } @@ -707,7 +707,7 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_SET_CURRENT ERROR: busy"); - _mavlink->send_statustext_critical("WPM: IGN WP CURR CMD: Busy\t"); + _mavlink.send_statustext_critical("WPM: IGN WP CURR CMD: Busy\t"); events::send(events::ID("mavlink_mission_state_busy"), events::Log::Error, "Mission manager currently busy, ignoring new waypoint index"); } @@ -768,7 +768,7 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_REQUEST_LIST ERROR: busy"); - _mavlink->send_statustext_info("Mission download request ignored, already active\t"); + _mavlink.send_statustext_info("Mission download request ignored, already active\t"); events::send(events::ID("mavlink_mission_req_ignored"), events::Log::Warning, "Mission download request ignored, already active"); } @@ -843,7 +843,7 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) switch_to_idle_state(); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t"); + _mavlink.send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t"); events::send(events::ID("mavlink_mission_wp_unexpected"), events::Log::Error, "Unexpected waypoint index, aborting transfer"); return; @@ -860,7 +860,7 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) switch_to_idle_state(); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t"); + _mavlink.send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t"); events::send(events::ID("mavlink_mission_wp_unexpected2"), events::Log::Error, "Unexpected waypoint index, aborting mission transfer"); } @@ -869,18 +869,18 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: no transfer"); // Silently ignore this as some OSDs have buggy mission protocol implementations - //_mavlink->send_statustext_critical("IGN MISSION_ITEM_REQUEST(_INT): No active transfer"); + //_mavlink.send_statustext_critical("IGN MISSION_ITEM_REQUEST(_INT): No active transfer"); } else { PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: busy (state %d).", _state); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy\t"); + _mavlink.send_statustext_critical("WPM: REJ. CMD: Busy\t"); events::send(events::ID("mavlink_mission_mis_req_ignored_busy"), events::Log::Error, "Ignoring mission request, currently busy"); } } else { - _mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch\t"); + _mavlink.send_statustext_critical("WPM: REJ. CMD: partner id mismatch\t"); events::send(events::ID("mavlink_mission_partner_id_mismatch2"), events::Log::Error, "Rejecting mission request command, component or system ID mismatch"); @@ -1000,7 +1000,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy\t"); + _mavlink.send_statustext_critical("WPM: REJ. CMD: Busy\t"); events::send(events::ID("mavlink_mission_getlist_busy"), events::Log::Error, "Mission upload busy, already receiving waypoint"); @@ -1011,7 +1011,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, state %i", _state); - _mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy\t"); + _mavlink.send_statustext_critical("WPM: IGN MISSION_COUNT: Busy\t"); events::send(events::ID("mavlink_mission_ignore_mis_count"), events::Log::Error, "Mission upload busy, ignoring MISSION_COUNT"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); @@ -1088,7 +1088,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_ITEM ERROR: no transfer"); - _mavlink->send_statustext_critical("IGN MISSION_ITEM: No transfer\t"); + _mavlink.send_statustext_critical("IGN MISSION_ITEM: No transfer\t"); events::send(events::ID("mavlink_mission_no_transfer"), events::Log::Error, "Ignoring mission item, no transfer in progress"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); @@ -1099,7 +1099,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_ITEM ERROR: busy, state %i", _state); - _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy\t"); + _mavlink.send_statustext_critical("IGN MISSION_ITEM: Busy\t"); events::send(events::ID("mavlink_mission_mis_item_busy"), events::Log::Error, "Ignoring mission item, busy"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); @@ -1113,7 +1113,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) if (ret != PX4_OK) { PX4_DEBUG("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); - _mavlink->send_statustext_critical("IGN MISSION_ITEM: Invalid item\t"); + _mavlink.send_statustext_critical("IGN MISSION_ITEM: Invalid item\t"); events::send(events::ID("mavlink_mission_mis_item_invalid"), events::Log::Error, "Ignoring mission item, invalid item"); @@ -1208,7 +1208,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) break; default: - _mavlink->send_statustext_critical("Received unknown mission type, abort.\t"); + _mavlink.send_statustext_critical("Received unknown mission type, abort.\t"); events::send(events::ID("mavlink_mission_unknown_mis_type"), events::Log::Error, "Received unknown mission type, abort"); break; @@ -1220,7 +1220,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); if (write_failed) { - _mavlink->send_statustext_critical("Unable to write on micro SD\t"); + _mavlink.send_statustext_critical("Unable to write on micro SD\t"); events::send(events::ID("mavlink_mission_storage_failure"), events::Log::Error, "Mission: unable to write to storage"); } @@ -1361,7 +1361,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg) } } else { - _mavlink->send_statustext_critical("WPM: IGN CLEAR CMD: Busy\t"); + _mavlink.send_statustext_critical("WPM: IGN CLEAR CMD: Busy\t"); events::send(events::ID("mavlink_mission_ignore_clear"), events::Log::Error, "Ignoring mission clear command, busy"); @@ -1839,7 +1839,7 @@ void MavlinkMissionManager::copy_params_from_mavlink_to_mission_item(struct miss void MavlinkMissionManager::check_active_mission() { // do not send anything over high latency communication - if (_mavlink->get_mode() == Mavlink::MAVLINK_MODE_IRIDIUM) { + if (_mavlink.get_mode() == Mavlink::MAVLINK_MODE_IRIDIUM) { return; } diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h index 2251ef9e61da..0b5c6e25d815 100644 --- a/src/modules/mavlink/mavlink_mission.h +++ b/src/modules/mavlink/mavlink_mission.h @@ -77,7 +77,7 @@ class Mavlink; class MavlinkMissionManager { public: - explicit MavlinkMissionManager(Mavlink *mavlink); + explicit MavlinkMissionManager(Mavlink &mavlink); ~MavlinkMissionManager() = default; @@ -146,7 +146,7 @@ class MavlinkMissionManager MavlinkRateLimiter _slow_rate_limiter{1000 * 1000}; ///< Rate limit sending of the current WP sequence to 1 Hz - Mavlink *_mavlink; + Mavlink &_mavlink; static constexpr unsigned int FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT = 2; ///< Error count limit before stopping to report FS errors diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index c7332bff7bdc..cbac547c93b7 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -46,7 +46,7 @@ #include "mavlink_main.h" #include -MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : +MavlinkParametersManager::MavlinkParametersManager(Mavlink &mavlink) : _mavlink(mavlink) { } @@ -111,7 +111,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) /* Whatever the value is, we're being told to stop sending */ if (strncmp(name, "_HASH_CHECK", sizeof(name)) == 0) { - if (_mavlink->hash_check_enabled()) { + if (_mavlink.hash_check_enabled()) { _send_all_index = -1; } @@ -189,7 +189,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) strncpy(param_value.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); param_value.param_type = MAV_PARAM_TYPE_UINT32; memcpy(¶m_value.param_value, &hash, sizeof(hash)); - mavlink_msg_param_value_send_struct(_mavlink->get_channel(), ¶m_value); + mavlink_msg_param_value_send_struct(_mavlink.get_channel(), ¶m_value); } else { /* local name buffer to enforce null-terminated string */ @@ -249,7 +249,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) size_t i = map_rc.parameter_rc_channel_index; if (i >= sizeof(_rc_param_map.param_index) / sizeof(_rc_param_map.param_index[0])) { - mavlink_log_warning(_mavlink->get_mavlink_log_pub(), "parameter_rc_channel_index out of bounds\t"); + mavlink_log_warning(_mavlink.get_mavlink_log_pub(), "parameter_rc_channel_index out of bounds\t"); events::send(events::ID("mavlink_param_rc_chan_out_of_bounds"), events::Log::Warning, "parameter_rc_channel_index out of bounds"); break; @@ -319,7 +319,7 @@ MavlinkParametersManager::send() int max_num_to_send; - if (_mavlink->get_protocol() == Protocol::SERIAL && !_mavlink->is_usb_uart()) { + if (_mavlink.get_protocol() == Protocol::SERIAL && !_mavlink.is_usb_uart()) { max_num_to_send = 3; } else { @@ -330,7 +330,7 @@ MavlinkParametersManager::send() int i = 0; // Send while burst is not exceeded, we still have buffer space and still something to send - while ((i++ < max_num_to_send) && (_mavlink->get_free_tx_buf() >= get_size()) && !_mavlink->radio_status_critical() + while ((i++ < max_num_to_send) && (_mavlink.get_free_tx_buf() >= get_size()) && !_mavlink.radio_status_critical() && send_params()) {} } @@ -394,7 +394,7 @@ MavlinkParametersManager::send_untransmitted() break; } } - } while ((_mavlink->get_free_tx_buf() >= get_size()) && !_mavlink->radio_status_critical() + } while ((_mavlink.get_free_tx_buf() >= get_size()) && !_mavlink.radio_status_critical() && (_param_update_index < (int) param_count())); // Flag work as done once all params have been sent @@ -426,7 +426,7 @@ MavlinkParametersManager::send_one() strncpy(msg.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); msg.param_type = MAV_PARAM_TYPE_UINT32; memcpy(&msg.param_value, &hash, sizeof(hash)); - mavlink_msg_param_value_send_struct(_mavlink->get_channel(), &msg); + mavlink_msg_param_value_send_struct(_mavlink.get_channel(), &msg); /* after this we should start sending all params */ _send_all_index = 0; @@ -468,7 +468,7 @@ MavlinkParametersManager::send_param(param_t param, int component_id) } /* no free TX buf to send this param */ - if (_mavlink->get_free_tx_buf() < MAVLINK_MSG_ID_PARAM_VALUE_LEN) { + if (_mavlink.get_free_tx_buf() < MAVLINK_MSG_ID_PARAM_VALUE_LEN) { return 1; } @@ -535,13 +535,13 @@ MavlinkParametersManager::send_param(param_t param, int component_id) /* default component ID */ if (component_id < 0) { - mavlink_msg_param_value_send_struct(_mavlink->get_channel(), &msg); + mavlink_msg_param_value_send_struct(_mavlink.get_channel(), &msg); } else { // Re-pack the message with a different component ID mavlink_message_t mavlink_packet; - mavlink_msg_param_value_encode_chan(mavlink_system.sysid, component_id, _mavlink->get_channel(), &mavlink_packet, &msg); - _mavlink_resend_uart(_mavlink->get_channel(), &mavlink_packet); + mavlink_msg_param_value_encode_chan(mavlink_system.sysid, component_id, _mavlink.get_channel(), &mavlink_packet, &msg); + _mavlink_resend_uart(_mavlink.get_channel(), &mavlink_packet); } return 0; @@ -595,9 +595,9 @@ bool MavlinkParametersManager::send_uavcan() // Re-pack the message with the UAVCAN node ID mavlink_message_t mavlink_packet{}; - mavlink_msg_param_value_encode_chan(mavlink_system.sysid, value.node_id, _mavlink->get_channel(), &mavlink_packet, + mavlink_msg_param_value_encode_chan(mavlink_system.sysid, value.node_id, _mavlink.get_channel(), &mavlink_packet, &msg); - _mavlink_resend_uart(_mavlink->get_channel(), &mavlink_packet); + _mavlink_resend_uart(_mavlink.get_channel(), &mavlink_packet); return true; } diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h index bf8d48d78506..c1042d0e71b5 100644 --- a/src/modules/mavlink/mavlink_parameters.h +++ b/src/modules/mavlink/mavlink_parameters.h @@ -64,7 +64,7 @@ class Mavlink; class MavlinkParametersManager { public: - explicit MavlinkParametersManager(Mavlink *mavlink); + explicit MavlinkParametersManager(Mavlink &mavlink); ~MavlinkParametersManager() = default; /** @@ -159,7 +159,7 @@ class MavlinkParametersManager hrt_abstime _param_update_time{0}; int _param_update_index{0}; - Mavlink *_mavlink; + Mavlink &_mavlink; bool _first_send{false}; }; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index c98c36b3d668..35e2879c6db7 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -106,7 +106,7 @@ static constexpr vehicle_odometry_s vehicle_odometry_empty { .quality = 0 }; -MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : +MavlinkReceiver::MavlinkReceiver(Mavlink &parent) : ModuleParams(nullptr), _mavlink(parent), _mavlink_ftp(parent), @@ -344,7 +344,7 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) * Accept HIL GPS messages if use_hil_gps flag is true. * This allows to provide fake gps measurements to the system. */ - if (_mavlink->get_hil_enabled()) { + if (_mavlink.get_hil_enabled()) { switch (msg->msgid) { case MAVLINK_MSG_ID_HIL_SENSOR: handle_message_hil_sensor(msg); @@ -364,7 +364,7 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) } - if (_mavlink->get_hil_enabled() || (_mavlink->get_use_hil_gps() && msg->sysid == mavlink_system.sysid)) { + if (_mavlink.get_hil_enabled() || (_mavlink.get_use_hil_gps() && msg->sysid == mavlink_system.sysid)) { switch (msg->msgid) { case MAVLINK_MSG_ID_HIL_GPS: handle_message_hil_gps(msg); @@ -380,18 +380,18 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) _mission_manager.handle_message(msg); /* handle packet with parameter component */ - if (_mavlink->boot_complete()) { + if (_mavlink.boot_complete()) { // make sure mavlink app has booted before we start processing parameter sync _parameters_manager.handle_message(msg); } else { - if (hrt_elapsed_time(&_mavlink->get_first_start_time()) > 20_s) { + if (hrt_elapsed_time(&_mavlink.get_first_start_time()) > 20_s) { PX4_ERR("system boot did not complete in 20 seconds"); - _mavlink->set_boot_complete(); + _mavlink.set_boot_complete(); } } - if (_mavlink->ftp_enabled()) { + if (_mavlink.ftp_enabled()) { /* handle packet with ftp component */ _mavlink_ftp.handle_message(msg); } @@ -403,7 +403,7 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) _mavlink_timesync.handle_message(msg); /* handle packet with parent object */ - _mavlink->handle_message(msg); + _mavlink.handle_message(msg); } bool @@ -527,8 +527,8 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const if (!target_ok) { // Reject alien commands only if there is no forwarding or we've never seen target component before - if (!_mavlink->get_forwarding_on() - || !_mavlink->component_was_seen(cmd_mavlink.target_system, cmd_mavlink.target_component, _mavlink)) { + if (!_mavlink.get_forwarding_on() + || !_mavlink.component_was_seen(cmd_mavlink.target_system, cmd_mavlink.target_component, _mavlink)) { acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED); } @@ -568,7 +568,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const vehicle_command.param5, vehicle_command.param6, vehicle_command.param7); } else if (cmd_mavlink.command == MAV_CMD_INJECT_FAILURE) { - if (_mavlink->failure_injection_enabled()) { + if (_mavlink.failure_injection_enabled()) { _cmd_pub.publish(vehicle_command); send_ack = false; @@ -694,19 +694,19 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const // check that we have enough bandwidth available: this is given by the configured logger topics // and rates. The 5000 is somewhat arbitrary, but makes sure that we cannot enable log streaming // on a radio link - if (_mavlink->get_data_rate() < 5000) { + if (_mavlink.get_data_rate() < 5000) { send_ack = true; result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED; - _mavlink->send_statustext_critical("Not enough bandwidth to enable log streaming\t"); + _mavlink.send_statustext_critical("Not enough bandwidth to enable log streaming\t"); events::send(events::ID("mavlink_log_not_enough_bw"), events::Log::Error, - "Not enough bandwidth to enable log streaming ({1} \\< 5000)", _mavlink->get_data_rate()); + "Not enough bandwidth to enable log streaming ({1} \\< 5000)", _mavlink.get_data_rate()); } else { // we already instanciate the streaming object, because at this point we know on which // mavlink channel streaming was requested. But in fact it's possible that the logger is // not even running. The main mavlink thread takes care of this by waiting for an ack // from the logger. - _mavlink->try_start_ulog_streaming(msg->sysid, msg->compid); + _mavlink.try_start_ulog_streaming(msg->sysid, msg->compid); } } @@ -726,7 +726,7 @@ uint8_t MavlinkReceiver::handle_request_message_command(uint16_t message_id, flo bool stream_found = false; bool message_sent = false; - for (const auto &stream : _mavlink->get_streams()) { + for (const auto &stream : _mavlink.get_streams()) { if (stream->get_id() == message_id) { stream_found = true; message_sent = stream->request_message(param2, param3, param4, param5, param6, param7); @@ -739,10 +739,10 @@ uint8_t MavlinkReceiver::handle_request_message_command(uint16_t message_id, flo const char *stream_name = get_stream_name(message_id); if (stream_name != nullptr) { - _mavlink->configure_stream_threadsafe(stream_name, 0.0f); + _mavlink.configure_stream_threadsafe(stream_name, 0.0f); // Now we try again to send it. - for (const auto &stream : _mavlink->get_streams()) { + for (const auto &stream : _mavlink.get_streams()) { if (stream->get_id() == message_id) { message_sent = stream->request_message(param2, param3, param4, param5, param6, param7); break; @@ -762,7 +762,7 @@ MavlinkReceiver::handle_message_command_ack(mavlink_message_t *msg) mavlink_command_ack_t ack; mavlink_msg_command_ack_decode(msg, &ack); - MavlinkCommandSender::instance().handle_mavlink_command_ack(ack, msg->sysid, msg->compid, _mavlink->get_channel()); + MavlinkCommandSender::instance().handle_mavlink_command_ack(ack, msg->sysid, msg->compid, _mavlink.get_channel()); vehicle_command_ack_s command_ack{}; @@ -793,7 +793,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) device::Device::DeviceId device_id; device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK; - device_id.devid_s.bus = _mavlink->get_instance_id(); + device_id.devid_s.bus = _mavlink.get_instance_id(); device_id.devid_s.address = msg->sysid; device_id.devid_s.devtype = DRV_FLOW_DEVTYPE_MAVLINK; @@ -839,7 +839,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) device::Device::DeviceId device_id; device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK; - device_id.devid_s.bus = _mavlink->get_instance_id(); + device_id.devid_s.bus = _mavlink.get_instance_id(); device_id.devid_s.address = msg->sysid; device_id.devid_s.devtype = DRV_FLOW_DEVTYPE_SIM; @@ -916,7 +916,7 @@ MavlinkReceiver::handle_message_distance_sensor(mavlink_message_t *msg) device::Device::DeviceId device_id; device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK; - device_id.devid_s.bus = _mavlink->get_instance_id(); + device_id.devid_s.bus = _mavlink.get_instance_id(); device_id.devid_s.address = msg->sysid; device_id.devid_s.devtype = DRV_DIST_DEVTYPE_MAVLINK; @@ -988,7 +988,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t mavlink_msg_set_position_target_local_ned_decode(msg, &target_local_ned); /* Only accept messages which are intended for this system */ - if (_mavlink->get_forward_externalsp() && + if (_mavlink.get_forward_externalsp() && (mavlink_system.sysid == target_local_ned.target_system || target_local_ned.target_system == 0) && (mavlink_system.compid == target_local_ned.target_component || target_local_ned.target_component == 0)) { @@ -1108,7 +1108,7 @@ MavlinkReceiver::handle_message_set_position_target_global_int(mavlink_message_t mavlink_msg_set_position_target_global_int_decode(msg, &target_global_int); /* Only accept messages which are intended for this system */ - if (_mavlink->get_forward_externalsp() && + if (_mavlink.get_forward_externalsp() && (mavlink_system.sysid == target_global_int.target_system || target_global_int.target_system == 0) && (mavlink_system.compid == target_global_int.target_component || target_global_int.target_component == 0)) { @@ -1224,13 +1224,13 @@ MavlinkReceiver::handle_message_set_gps_global_origin(mavlink_message_t *msg) mavlink_set_gps_global_origin_t gps_global_origin; mavlink_msg_set_gps_global_origin_decode(msg, &gps_global_origin); - if (gps_global_origin.target_system == _mavlink->get_system_id()) { + if (gps_global_origin.target_system == _mavlink.get_system_id()) { vehicle_command_s vcmd{}; vcmd.param5 = (double)gps_global_origin.latitude * 1.e-7; vcmd.param6 = (double)gps_global_origin.longitude * 1.e-7; vcmd.param7 = (float)gps_global_origin.altitude * 1.e-3f; vcmd.command = vehicle_command_s::VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN; - vcmd.target_system = _mavlink->get_system_id(); + vcmd.target_system = _mavlink.get_system_id(); vcmd.target_component = MAV_COMP_ID_ALL; vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; @@ -1514,7 +1514,7 @@ void MavlinkReceiver::fill_thrust(float *thrust_body_array, uint8_t vehicle_type { // Fill correct field by checking frametype // TODO: add as needed - switch (_mavlink->get_system_type()) { + switch (_mavlink.get_system_type()) { case MAV_TYPE_GENERIC: break; @@ -1570,7 +1570,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) mavlink_msg_set_attitude_target_decode(msg, &attitude_target); /* Only accept messages which are intended for this system */ - if (_mavlink->get_forward_externalsp() && + if (_mavlink.get_forward_externalsp() && (mavlink_system.sysid == attitude_target.target_system || attitude_target.target_system == 0) && (mavlink_system.compid == attitude_target.target_component || attitude_target.target_component == 0)) { @@ -1659,7 +1659,7 @@ void MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) { /* telemetry status supported only on first ORB_MULTI_MAX_INSTANCES mavlink channels */ - if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { + if (_mavlink.get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { mavlink_radio_status_t rstatus; mavlink_msg_radio_status_decode(msg, &rstatus); @@ -1674,7 +1674,7 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) status.rxerrors = rstatus.rxerrors; status.fix = rstatus.fixed; - _mavlink->update_radio_status(status); + _mavlink.update_radio_status(status); _radio_status_pub.publish(status); } @@ -1691,7 +1691,7 @@ MavlinkReceiver::handle_message_ping(mavlink_message_t *msg) ping.target_system = msg->sysid; ping.target_component = msg->compid; - mavlink_msg_ping_send_struct(_mavlink->get_channel(), &ping); + mavlink_msg_ping_send_struct(_mavlink.get_channel(), &ping); } else if ((ping.target_system == mavlink_system.sysid) && (ping.target_component == @@ -1703,7 +1703,7 @@ MavlinkReceiver::handle_message_ping(mavlink_message_t *msg) float rtt_ms = (now - ping.time_usec) / 1000.0f; // Update ping statistics - struct Mavlink::ping_statistics_s &pstats = _mavlink->get_ping_statistics(); + struct Mavlink::ping_statistics_s &pstats = _mavlink.get_ping_statistics(); pstats.last_ping_time = now; @@ -1728,7 +1728,7 @@ MavlinkReceiver::handle_message_ping(mavlink_message_t *msg) pstats.min_rtt = pstats.min_rtt > 0.0f ? fminf(rtt_ms, pstats.min_rtt) : rtt_ms; /* Ping status is supported only on first ORB_MULTI_MAX_INSTANCES mavlink channels */ - if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { + if (_mavlink.get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { ping_s uorb_ping_msg{}; @@ -1814,7 +1814,7 @@ MavlinkReceiver::handle_message_serial_control(mavlink_message_t *msg) return; } - MavlinkShell *shell = _mavlink->get_shell(); + MavlinkShell *shell = _mavlink.get_shell(); if (shell) { // we ignore the timeout, EXCLUSIVE & BLOCKING flags of the SERIAL_CONTROL message @@ -1825,7 +1825,7 @@ MavlinkReceiver::handle_message_serial_control(mavlink_message_t *msg) // if no response requested, assume the shell is no longer used if ((serial_control_mavlink.flags & SERIAL_CONTROL_FLAG_RESPOND) == 0) { - _mavlink->close_shell(); + _mavlink.close_shell(); } } } @@ -1836,7 +1836,7 @@ MavlinkReceiver::handle_message_logging_ack(mavlink_message_t *msg) mavlink_logging_ack_t logging_ack; mavlink_msg_logging_ack_decode(msg, &logging_ack); - MavlinkULog *ulog_streaming = _mavlink->get_ulog_streaming(); + MavlinkULog *ulog_streaming = _mavlink.get_ulog_streaming(); if (ulog_streaming) { ulog_streaming->handle_ack(logging_ack); @@ -2013,7 +2013,7 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg) mavlink_msg_rc_channels_override_decode(msg, &man); // Check target - if (man.target_system != 0 && man.target_system != _mavlink->get_system_id()) { + if (man.target_system != 0 && man.target_system != _mavlink.get_system_id()) { return; } @@ -2100,7 +2100,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) mavlink_msg_manual_control_decode(msg, &mavlink_manual_control); // Check target - if (mavlink_manual_control.target != 0 && mavlink_manual_control.target != _mavlink->get_system_id()) { + if (mavlink_manual_control.target != 0 && mavlink_manual_control.target != _mavlink.get_system_id()) { return; } @@ -2112,7 +2112,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) manual_control_setpoint.yaw = mavlink_manual_control.r / 1000.f; // Pass along the button states manual_control_setpoint.buttons = mavlink_manual_control.buttons; - manual_control_setpoint.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink->get_instance_id(); + manual_control_setpoint.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink.get_instance_id(); manual_control_setpoint.timestamp = manual_control_setpoint.timestamp_sample = hrt_absolute_time(); manual_control_setpoint.valid = true; _manual_control_input_pub.publish(manual_control_setpoint); @@ -2122,7 +2122,7 @@ void MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) { /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */ - if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { + if (_mavlink.get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { const hrt_abstime now = hrt_absolute_time(); @@ -2166,13 +2166,13 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) case MAV_TYPE_PARACHUTE: _heartbeat_type_parachute = now; - _mavlink->telemetry_status().parachute_system_healthy = + _mavlink.telemetry_status().parachute_system_healthy = (hb.system_status == MAV_STATE_STANDBY) || (hb.system_status == MAV_STATE_ACTIVE); break; case MAV_TYPE_ODID: _heartbeat_type_open_drone_id = now; - _mavlink->telemetry_status().open_drone_id_system_healthy = + _mavlink.telemetry_status().open_drone_id_system_healthy = (hb.system_status == MAV_STATE_STANDBY) || (hb.system_status == MAV_STATE_ACTIVE); break; @@ -2197,7 +2197,7 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) case MAV_COMP_ID_OBSTACLE_AVOIDANCE: _heartbeat_component_obstacle_avoidance = now; - _mavlink->telemetry_status().avoidance_system_healthy = (hb.system_status == MAV_STATE_ACTIVE); + _mavlink.telemetry_status().avoidance_system_healthy = (hb.system_status == MAV_STATE_ACTIVE); break; case MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY: @@ -2234,7 +2234,7 @@ MavlinkReceiver::set_message_interval(int msgId, float interval, int data_rate) } if (data_rate > 0) { - _mavlink->set_data_rate(data_rate); + _mavlink.set_data_rate(data_rate); } // configure_stream wants a rate (msgs/second), so convert here. @@ -2256,7 +2256,7 @@ MavlinkReceiver::set_message_interval(int msgId, float interval, int data_rate) const char *stream_name = get_stream_name(msgId); if (stream_name != nullptr) { - _mavlink->configure_stream_threadsafe(stream_name, rate); + _mavlink.configure_stream_threadsafe(stream_name, rate); found_id = true; } } @@ -2269,7 +2269,7 @@ MavlinkReceiver::get_message_interval(int msgId) { unsigned interval = 0; - for (const auto &stream : _mavlink->get_streams()) { + for (const auto &stream : _mavlink.get_streams()) { if (stream->get_id() == msgId) { interval = stream->get_interval(); break; @@ -2277,7 +2277,7 @@ MavlinkReceiver::get_message_interval(int msgId) } // send back this value... - mavlink_msg_message_interval_send(_mavlink->get_channel(), msgId, interval); + mavlink_msg_message_interval_send(_mavlink.get_channel(), msgId, interval); } void @@ -2394,7 +2394,7 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg) device::Device::DeviceId device_id; device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK; - device_id.devid_s.bus = _mavlink->get_instance_id(); + device_id.devid_s.bus = _mavlink.get_instance_id(); device_id.devid_s.address = msg->sysid; device_id.devid_s.devtype = DRV_GPS_DEVTYPE_SIM; @@ -2908,7 +2908,7 @@ void MavlinkReceiver::CheckHeartbeats(const hrt_abstime &t, bool force) } if ((t >= _last_heartbeat_check + (TIMEOUT / 2)) || force) { - telemetry_status_s &tstatus = _mavlink->telemetry_status(); + telemetry_status_s &tstatus = _mavlink.telemetry_status(); tstatus.heartbeat_type_antenna_tracker = (t <= TIMEOUT + _heartbeat_type_antenna_tracker); tstatus.heartbeat_type_gcs = (t <= TIMEOUT + _heartbeat_type_gcs); @@ -2928,14 +2928,14 @@ void MavlinkReceiver::CheckHeartbeats(const hrt_abstime &t, bool force) tstatus.heartbeat_component_udp_bridge = (t <= TIMEOUT + _heartbeat_component_udp_bridge); tstatus.heartbeat_component_uart_bridge = (t <= TIMEOUT + _heartbeat_component_uart_bridge); - _mavlink->telemetry_status_updated(); + _mavlink.telemetry_status_updated(); _last_heartbeat_check = t; } } void MavlinkReceiver::handle_message_request_event(mavlink_message_t *msg) { - _mavlink->get_events_protocol().handle_request_event(*msg); + _mavlink.get_events_protocol().handle_request_event(*msg); } void @@ -3058,7 +3058,7 @@ MavlinkReceiver::run() /* set thread name */ { char thread_name[17]; - snprintf(thread_name, sizeof(thread_name), "mavlink_rcv_if%d", _mavlink->get_instance_id()); + snprintf(thread_name, sizeof(thread_name), "mavlink_rcv_if%d", _mavlink.get_instance_id()); px4_prctl(PR_SET_NAME, thread_name, px4_getpid()); } @@ -3079,8 +3079,8 @@ MavlinkReceiver::run() struct pollfd fds[1] = {}; - if (_mavlink->get_protocol() == Protocol::SERIAL) { - fds[0].fd = _mavlink->get_uart_fd(); + if (_mavlink.get_protocol() == Protocol::SERIAL) { + fds[0].fd = _mavlink.get_uart_fd(); fds[0].events = POLLIN; } @@ -3088,8 +3088,8 @@ MavlinkReceiver::run() struct sockaddr_in srcaddr = {}; socklen_t addrlen = sizeof(srcaddr); - if (_mavlink->get_protocol() == Protocol::UDP) { - fds[0].fd = _mavlink->get_socket_fd(); + if (_mavlink.get_protocol() == Protocol::UDP) { + fds[0].fd = _mavlink.get_socket_fd(); fds[0].events = POLLIN; } @@ -3098,7 +3098,7 @@ MavlinkReceiver::run() ssize_t nread = 0; hrt_abstime last_send_update = 0; - while (!_mavlink->should_exit()) { + while (!_mavlink.should_exit()) { // check for parameter updates if (_parameter_update_sub.updated()) { @@ -3113,7 +3113,7 @@ MavlinkReceiver::run() int ret = poll(&fds[0], 1, timeout); if (ret > 0) { - if (_mavlink->get_protocol() == Protocol::SERIAL) { + if (_mavlink.get_protocol() == Protocol::SERIAL) { /* non-blocking read. read may return negative values */ nread = ::read(fds[0].fd, buf, sizeof(buf)); @@ -3124,21 +3124,21 @@ MavlinkReceiver::run() #if defined(MAVLINK_UDP) - else if (_mavlink->get_protocol() == Protocol::UDP) { + else if (_mavlink.get_protocol() == Protocol::UDP) { if (fds[0].revents & POLLIN) { - nread = recvfrom(_mavlink->get_socket_fd(), buf, sizeof(buf), 0, (struct sockaddr *)&srcaddr, &addrlen); + nread = recvfrom(_mavlink.get_socket_fd(), buf, sizeof(buf), 0, (struct sockaddr *)&srcaddr, &addrlen); } - struct sockaddr_in &srcaddr_last = _mavlink->get_client_source_address(); + struct sockaddr_in &srcaddr_last = _mavlink.get_client_source_address(); int localhost = (127 << 24) + 1; - if (!_mavlink->get_client_source_initialized()) { + if (!_mavlink.get_client_source_initialized()) { // set the address either if localhost or if 3 seconds have passed // this ensures that a GCS running on localhost can get a hold of // the system within the first N seconds - hrt_abstime stime = _mavlink->get_start_time(); + hrt_abstime stime = _mavlink.get_start_time(); if ((stime != 0 && (hrt_elapsed_time(&stime) > 3_s)) || (srcaddr_last.sin_addr.s_addr == htonl(localhost))) { @@ -3146,7 +3146,7 @@ MavlinkReceiver::run() srcaddr_last.sin_addr.s_addr = srcaddr.sin_addr.s_addr; srcaddr_last.sin_port = srcaddr.sin_port; - _mavlink->set_client_source_initialized(); + _mavlink.set_client_source_initialized(); PX4_INFO("partner IP: %s", inet_ntoa(srcaddr.sin_addr)); } @@ -3154,21 +3154,21 @@ MavlinkReceiver::run() } // only start accepting messages on UDP once we're sure who we talk to - if (_mavlink->get_protocol() != Protocol::UDP || _mavlink->get_client_source_initialized()) { + if (_mavlink.get_protocol() != Protocol::UDP || _mavlink.get_client_source_initialized()) { #endif // MAVLINK_UDP /* if read failed, this loop won't execute */ for (ssize_t i = 0; i < nread; i++) { - if (mavlink_parse_char(_mavlink->get_channel(), buf[i], &msg, &_status)) { + if (mavlink_parse_char(_mavlink.get_channel(), buf[i], &msg, &_status)) { /* check if we received version 2 and request a switch. */ - if (!(_mavlink->get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) { + if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) { /* this will only switch to proto version 2 if allowed in settings */ - _mavlink->set_proto_version(2); + _mavlink.set_proto_version(2); } handle_message(&msg); - _mavlink->set_has_received_messages(true); // Received first message, unlock wait to transmit '-w' command-line flag + _mavlink.set_has_received_messages(true); // Received first message, unlock wait to transmit '-w' command-line flag update_rx_stats(msg); if (_message_statistics_enabled) { @@ -3179,9 +3179,9 @@ MavlinkReceiver::run() /* count received bytes (nread will be -1 on read error) */ if (nread > 0) { - _mavlink->count_rxbytes(nread); + _mavlink.count_rxbytes(nread); - telemetry_status_s &tstatus = _mavlink->telemetry_status(); + telemetry_status_s &tstatus = _mavlink.telemetry_status(); tstatus.rx_message_count = _total_received_counter; tstatus.rx_message_lost_count = _total_lost_counter; tstatus.rx_message_lost_rate = static_cast(_total_lost_counter) / static_cast(_total_received_counter); @@ -3219,11 +3219,11 @@ MavlinkReceiver::run() _mission_manager.check_active_mission(); _mission_manager.send(); - if (_mavlink->get_mode() != Mavlink::MAVLINK_MODE::MAVLINK_MODE_IRIDIUM) { + if (_mavlink.get_mode() != Mavlink::MAVLINK_MODE::MAVLINK_MODE_IRIDIUM) { _parameters_manager.send(); } - if (_mavlink->ftp_enabled()) { + if (_mavlink.ftp_enabled()) { _mavlink_ftp.send(); } diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index e5575b7efb5f..9f2882e84835 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -126,7 +126,7 @@ class Mavlink; class MavlinkReceiver : public ModuleParams { public: - MavlinkReceiver(Mavlink *parent); + MavlinkReceiver(Mavlink &parent); ~MavlinkReceiver() override; void start(); @@ -246,7 +246,7 @@ class MavlinkReceiver : public ModuleParams */ void updateParams() override; - Mavlink *_mavlink; + Mavlink &_mavlink; MavlinkFTP _mavlink_ftp; MavlinkLogHandler _mavlink_log_handler; diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp index 574a5164ad16..288023a6508d 100644 --- a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp +++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp @@ -77,7 +77,7 @@ MavlinkFtpTest::MavlinkFtpTest() : void MavlinkFtpTest::_init() { _expected_seq_number = 0; - _ftp_server = new MavlinkFTP(nullptr); + _ftp_server = new MavlinkFTP(_mavlink); _ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message_handler_generic, this); _create_test_files(); diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h index b32ebd628422..46da67c5f1f9 100644 --- a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h +++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h @@ -37,12 +37,9 @@ #pragma once #include -#ifndef MAVLINK_FTP_UNIT_TEST #include "../mavlink_bridge_header.h" -#else -#include -#endif #include "../mavlink_ftp.h" +#include "../mavlink_main.h" class MavlinkFtpTest : public UnitTest { @@ -130,6 +127,7 @@ class MavlinkFtpTest : public UnitTest bool _receive_message_handler_burst(const mavlink_file_transfer_protocol_t *ftp_req, BurstInfo *burst_info); MavlinkFTP *_ftp_server; + Mavlink _mavlink; uint16_t _expected_seq_number; mavlink_file_transfer_protocol_t _reply_msg; diff --git a/src/modules/mavlink/mavlink_timesync.cpp b/src/modules/mavlink/mavlink_timesync.cpp index 7bbe8f8dfacd..410dd84512a6 100644 --- a/src/modules/mavlink/mavlink_timesync.cpp +++ b/src/modules/mavlink/mavlink_timesync.cpp @@ -43,7 +43,7 @@ #include -MavlinkTimesync::MavlinkTimesync(Mavlink *mavlink) : +MavlinkTimesync::MavlinkTimesync(Mavlink &mavlink) : _mavlink(mavlink) { } @@ -66,7 +66,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg) rsync.tc1 = now * 1000ULL; rsync.ts1 = tsync.ts1; - mavlink_msg_timesync_send_struct(_mavlink->get_channel(), &rsync); + mavlink_msg_timesync_send_struct(_mavlink.get_channel(), &rsync); return; diff --git a/src/modules/mavlink/mavlink_timesync.h b/src/modules/mavlink/mavlink_timesync.h index a3e8295ae09e..0cb32a229cc3 100644 --- a/src/modules/mavlink/mavlink_timesync.h +++ b/src/modules/mavlink/mavlink_timesync.h @@ -49,7 +49,7 @@ class Mavlink; class MavlinkTimesync { public: - explicit MavlinkTimesync(Mavlink *mavlink); + explicit MavlinkTimesync(Mavlink &mavlink); ~MavlinkTimesync() = default; void handle_message(const mavlink_message_t *msg); @@ -61,6 +61,6 @@ class MavlinkTimesync uint64_t sync_stamp(uint64_t usec) { return _timesync.sync_stamp(usec); } private: - Mavlink *const _mavlink; + Mavlink &_mavlink; Timesync _timesync{}; }; From bc51eb37eb6449ce13eb1b9ea01d667839dbc3e2 Mon Sep 17 00:00:00 2001 From: Rowan Dempster Date: Thu, 30 May 2024 16:39:16 -0400 Subject: [PATCH 315/652] Only close server when errno is not EINTR --- platforms/posix/src/px4/common/px4_daemon/server.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/platforms/posix/src/px4/common/px4_daemon/server.cpp b/platforms/posix/src/px4/common/px4_daemon/server.cpp index c3b012bb8462..c26b364457f7 100644 --- a/platforms/posix/src/px4/common/px4_daemon/server.cpp +++ b/platforms/posix/src/px4/common/px4_daemon/server.cpp @@ -153,9 +153,8 @@ Server::_server_main() // Reboot command causes System Interrupt to stop poll(). This is not an error if (errno != EINTR) { PX4_ERR("poll() failed: %s", strerror(errno)); + break; } - - break; } _lock(); From bfe3c86aeb5a669ef1f9c27896701e3f5375a67f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 3 Jun 2024 11:01:20 -0400 Subject: [PATCH 316/652] ekf2: merge mag yaw angle observability into heading consistency - the additional hyteresis logic for "yaw angle observable" was needed when it controlled time dependent mag_3d --- .../scripts/itcm_functions_includes.ld | 1 - .../aid_sources/magnetometer/mag_control.cpp | 24 ++++--------------- src/modules/ekf2/EKF/ekf.h | 2 -- 3 files changed, 4 insertions(+), 23 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 60a76f97e1b9..477cc835bafb 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 @@ -683,7 +683,6 @@ *(.text._ZN18MavlinkStreamDebug8get_sizeEv) *(.text._ZN12GPSDriverUBX7receiveEj) *(.text._ZN13BatteryStatus21parameter_update_pollEb) -*(.text._ZN3Ekf26checkYawAngleObservabilityEv) *(.text._ZN3RTL18updateDatamanCacheEv) *(.text.__ieee754_sqrtf) *(.text._ZThn24_N18mag_bias_estimator16MagBiasEstimator3RunEv) 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 2e288adfbc21..d817c01ac87d 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -52,8 +52,6 @@ void Ekf::controlMagFusion() _control_status.flags.mag_aligned_in_flight = false; } - checkYawAngleObservability(); - if (_params.mag_fusion_type == MagFuseType::NONE) { stopMagFusion(); return; @@ -391,23 +389,6 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) } } -void Ekf::checkYawAngleObservability() -{ - if (_control_status.flags.gps) { - // Check if there has been enough change in horizontal velocity to make yaw observable - // Apply hysteresis to check to avoid rapid toggling - if (_yaw_angle_observable) { - _yaw_angle_observable = _accel_lpf_NE.norm() > _params.mag_acc_gate; - - } else { - _yaw_angle_observable = _accel_lpf_NE.norm() > _params.mag_acc_gate * 2.f; - } - - } else { - _yaw_angle_observable = false; - } -} - void Ekf::checkMagHeadingConsistency(const magSample &mag_sample) { // use mag bias if variance good @@ -437,7 +418,10 @@ void Ekf::checkMagHeadingConsistency(const magSample &mag_sample) } if (fabsf(_mag_heading_innov_lpf.getState()) < _params.mag_heading_noise) { - if (_yaw_angle_observable) { + // Check if there has been enough change in horizontal velocity to make yaw observable + const bool using_ne_aiding = _control_status.flags.gps || _control_status.flags.aux_gpos; + + if (using_ne_aiding && (_accel_lpf_NE.norm() > _params.mag_acc_gate)) { // yaw angle must be observable to consider consistency _control_status.flags.mag_heading_consistent = true; } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index c1542e8d046d..258ef6d7e865 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -703,7 +703,6 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // used by magnetometer fusion mode selection - bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable AlphaFilter _mag_heading_innov_lpf{0.1f}; uint32_t _min_mag_health_time_us{1'000'000}; ///< magnetometer is marked as healthy only after this amount of time @@ -1028,7 +1027,6 @@ class Ekf final : public EstimatorInterface void resetMagStates(const Vector3f &mag, bool reset_heading = true); bool haglYawResetReq(); - void checkYawAngleObservability(); void checkMagHeadingConsistency(const magSample &mag_sample); bool checkMagField(const Vector3f &mag); From fb659ae200a76942a0391d2d06852d222a5bfb36 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 4 Jun 2024 10:29:18 -0400 Subject: [PATCH 317/652] ekf2: stopMagFusion() reset yaw_align if mag heading was active - we also need to clear mag_aligned_in_flight --- .../ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) 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 d817c01ac87d..5bc5370f4859 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -275,6 +275,15 @@ void Ekf::stopMagFusion() if (_control_status.flags.mag) { ECL_INFO("stopping mag fusion"); + 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; + + if (!using_ne_aiding) { + _control_status.flags.yaw_align = false; + } + } + _control_status.flags.mag = false; _control_status.flags.mag_dec = false; @@ -289,6 +298,8 @@ void Ekf::stopMagFusion() _fault_status.flags.bad_hdg = false; } + _control_status.flags.mag_aligned_in_flight = false; + _fault_status.flags.bad_mag_x = false; _fault_status.flags.bad_mag_y = false; _fault_status.flags.bad_mag_z = false; From b1bf0ff8882a7675a27249e579ca2294f1734b85 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 5 Jun 2024 13:19:28 +0000 Subject: [PATCH 318/652] Remove argparse from the requirements.txt. The argparse module has been builtin to Python since Python 3.2, released in 2011 (see https://docs.python.org/3/whatsnew/3.2.html). Further, the argparse pip module has not been released or updated since 2015, and lacks some of the features of the modern, built-in argparse. Drop the pip installed version in favor of the built-in version. Signed-off-by: Chris Lalancette --- Tools/setup/requirements.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/Tools/setup/requirements.txt b/Tools/setup/requirements.txt index 2db827d34e3b..b130bd55a0f9 100644 --- a/Tools/setup/requirements.txt +++ b/Tools/setup/requirements.txt @@ -1,5 +1,4 @@ argcomplete -argparse>=1.2 cerberus coverage empy==3.3.4 From 71377806548632a93e12a81556784a42e5b1e321 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 6 Jun 2024 09:27:07 +1200 Subject: [PATCH 319/652] Makefile: add missing bootloader targets Quite a few were missing, and everything on one line was hard to diff. --- Makefile | 29 +++++++++++++++++++++++++++-- 1 file changed, 27 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 56c373663ffc..2d4116d73b0a 100644 --- a/Makefile +++ b/Makefile @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2015 - 2020 PX4 Development Team. All rights reserved. +# Copyright (c) 2015 - 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 @@ -323,7 +323,32 @@ px4io_update: cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin git status -bootloaders_update: ark_fmu-v6x_bootloader cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader holybro_kakuteh7_bootloader matek_h743_bootloader matek_h743-mini_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6c_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader +bootloaders_update: \ + ark_fmu-v6x_bootloader \ + ark_pi6x_bootloader \ + cuav_nora_bootloader \ + cuav_x7pro_bootloader \ + cubepilot_cubeorange_bootloader \ + cubepilot_cubeorangeplus_bootloader \ + hkust_nxt-dual_bootloader \ + hkust_nxt-v1_bootloader \ + holybro_durandal-v1_bootloader \ + holybro_kakuteh7_bootloader \ + holybro_kakuteh7mini_bootloader \ + holybro_kakuteh7v2_bootloader \ + matek_h743_bootloader \ + matek_h743-mini_bootloader \ + matek_h743-slim_bootloader \ + modalai_fc-v2_bootloader \ + mro_ctrl-zero-classic_bootloader \ + mro_ctrl-zero-h7_bootloader \ + mro_ctrl-zero-h7-oem_bootloader \ + mro_pixracerpro_bootloader \ + px4_fmu-v6c_bootloader \ + px4_fmu-v6u_bootloader \ + px4_fmu-v6x_bootloader \ + px4_fmu-v6xrt_bootloader \ + siyi_n7_bootloader git status .PHONY: coverity_scan From f6b65e68cc5d8216a9833e321f99dd13c4312e34 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 6 Jun 2024 10:11:57 +1200 Subject: [PATCH 320/652] boards: update all bootloaders --- .../fmu-v6x/extras/ark_fmu-v6x_bootloader.bin | Bin 46360 -> 46360 bytes .../ark/pi6x/extras/ark_pi6x_bootloader.bin | Bin 46152 -> 46304 bytes .../cuav/nora/extras/cuav_nora_bootloader.bin | Bin 43264 -> 43264 bytes .../x7pro/extras/cuav_x7pro_bootloader.bin | Bin 43264 -> 43264 bytes .../cubepilot_cubeorange_bootloader.bin | Bin 43200 -> 43200 bytes .../cubepilot_cubeorangeplus_bootloader.bin | Bin 43624 -> 43800 bytes .../extras/hkust_nxt-dual_bootloader.bin | Bin 43256 -> 43256 bytes .../nxt-v1/extras/hkust_nxt-v1_bootloader.bin | Bin 43248 -> 43280 bytes .../extras/holybro_durandal-v1_bootloader.bin | Bin 43284 -> 43284 bytes .../extras/holybro_kakuteh7_bootloader.bin | Bin 41876 -> 41876 bytes .../holybro_kakuteh7mini_bootloader.bin | Bin 41736 -> 41880 bytes .../extras/holybro_kakuteh7v2_bootloader.bin | Bin 41736 -> 41880 bytes .../extras/matek_h743-mini_bootloader.bin | Bin 42672 -> 42672 bytes .../extras/matek_h743-slim_bootloader.bin | Bin 43264 -> 43264 bytes .../h743/extras/matek_h743_bootloader.bin | Bin 42672 -> 42672 bytes .../fc-v2/extras/modalai_fc-v2_bootloader.bin | Bin 43284 -> 43284 bytes .../mro_ctrl-zero-classic_bootloader.bin | Bin 43244 -> 43244 bytes .../mro_ctrl-zero-h7-oem_bootloader.bin | Bin 43232 -> 43232 bytes .../extras/mro_ctrl-zero-h7_bootloader.bin | Bin 43212 -> 43212 bytes .../extras/mro_pixracerpro_bootloader.bin | Bin 43196 -> 43196 bytes .../fmu-v6c/extras/px4_fmu-v6c_bootloader.bin | Bin 46100 -> 46100 bytes .../fmu-v6u/extras/px4_fmu-v6u_bootloader.bin | Bin 43264 -> 43264 bytes .../fmu-v6x/extras/px4_fmu-v6x_bootloader.bin | Bin 46764 -> 46764 bytes .../extras/px4_fmu-v6xrt_bootloader.bin | Bin 82728 -> 82720 bytes boards/siyi/n7/extras/siyi_n7_bootloader.bin | Bin 45412 -> 45560 bytes 25 files changed, 0 insertions(+), 0 deletions(-) diff --git a/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin b/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin index 62ef9238b1061e35a5c6535077ed20491e59bab0..ea510ab36e38b5ae643a0a191aaf4fa584469f65 100755 GIT binary patch delta 25 hcmbR7ifP6xrVW4BbD0@hni(0J8X6gIX5S#l3IL132=xE} delta 25 hcmbR7ifP6xrVW4Ba~YW$nwlCW8K;_TX5S#l3IL902~Yq4 diff --git a/boards/ark/pi6x/extras/ark_pi6x_bootloader.bin b/boards/ark/pi6x/extras/ark_pi6x_bootloader.bin index ef4d19d36c9bd09307b24c6b50de52290a9c1753..fce9348a7408583edf739ddb2ddfe60891c98932 100755 GIT binary patch delta 4685 zcmb7Ie_Rt+w!e2~5=IdXpn&o#Aw+`#35W$(tr29vq7VGhid%m`wG|aKm8VkMU5JR- z`U|;O5%p6Qf8bLKF-=!$(f)GPx>{qql}cT8`)qWz?VyyIBqXzEg0I_uUp}8R_s%`v zbMBpU&pqedTzWv=eMq&{(Nv+;R!_gA#9M6-2kfQsVNw%x8FM6muomwm<%3fw^$Bux z@C!<7Gh$0mklw*@_$@MgNGqe!CZGag$O*L4ULDqV^{olL*Qbc~qs!K3hyx zF&xGJ*oU;*b*c_@KJf&(p{vJ>$g3k`gV0IDYJvU>XdBr%G8}Iv$48FBmu!xaXEDA+ zw&~LcTmmL*SMpYJRiD0mnvdagfUx*p*!H47@YBM9ByD;XMpzs zw1PgXl8@{oD-#ZYk%o+(i4T(E(Z{G^9@{`e2*#Uj(TUj0@EM|Q_*f}?V8toKs)JGd{8J<@Z#izT zZOhAM@Q38<{GafC@@YXUXn1|*Y>dmvg;|sE92-458{>Us+MEf43#^Eh2_d<))z3*~ z2JCwuu?;|twyT9S16%5tufq((2a3eKAZGXv66!V%n#UDzsD2MOFb-*15nrMCne zDhkJyZR8=}qhu1=9P(fm8o9r1%hL#$tl$PAqNd|rC)OOY*jTSNs|&G4(mQPx``G9m-w zmu^66NthxrbslxG89 zL0kJOV(mb`0~2M!J%iWto+xso9HWO0hV<7708a(n&H zr|?{u%R8fVdX5=K^Q97_QPwG2B;kQCF{#IK--&gy?hAh1Us&k9G*8pC!BokgvtVsL zj{+$*7}rSiAHs%3ONAWGkC7NI;;erh(fmgeY>lxwQ`1TBMe$iYLj&GK6WA8h#1}#< zLfa?jMOK8Gr#uOvDUGrPjXEVp7$u>_H_C~0pEwJ-1TL@}2huz%edSbx{t*&3R+{*k z7ADQ%Ooi1I`>n9nGK{Aw6TjMG7!Fgawq&9wr55|IRh8&TiRF&CuWcUpKbb=vmq22n z|9ci#;@dTO;3KIqB_oP-Jgv}8J()SoA=`ASE{w8^*(m%0@Zv0VJzsoPs0FaE|AjkZOD!SH>*yu-8S1FGVRnxq|r{EZkqD}#x zM7#-{>`^;pd{0&RDnGsy@GGvX<0efD*C|_k!e2ozeAX^Wc+-!sl!SGD0aQNs$0e|Y z=Rsh0*M-wDNd=wqlBUCZ-u3*R>t>q2=dI@Qdu~AQd++GHz1fo;33-i~6CHQN!)-Dm z`(J^9^T2)=z5V#h-oot3J$3Jc&xOi9*Y9zYz31-tAFCKIzt~zH737eeQrSXj`T@z_ zCF&t<9S`_?NvQ3R&q5>}X&B&0;ShZD9JnCx~S-o`AxGUb}9Mb4ZXujHIk z+w*(wr731~fp^{m2Sev&;cq}2qEY;}B&lR?kj9Pl3>SNANv2P*k-wL`9{IBiso4&s z&F|@2O--Y6DgNh=(D}z8b&nJ;JBUvcdihNJHhFRRI&2_Um*1nlcaydiFUi5SGzTvy z`K2p@{_MgKD5>w&%RIsua6*Mp5Ew%!XZ6>$N9t}^D_BrM3 zob-^-LEUPW;RbUi;AW9~E2m&Yw5zmOMRHbEPWB4lOE?Z`nC?X66~2AekAVJl3B_e_ zOm~zrnDYvk;myd&y)T|&VgPfFD9l=FP#YO-j=^PQnmHCPuq`tysNg?(n=1@fqy>4@ zY<3H?NagC8!EZ`hNLd2RNUHR}Q~b;nKWD^dsA*C6(0C1S^0$hC?e@lBik4GH6FVt;cT&L&B3=RZF2N_@OEtFC&o_E!ERUOqMv1T5PF~YV3R8Ie)5} z>l13+3a$k_VqzO&=Kv+P5o$wR7z}qGMzAxY9zd)66m7;1VEtjk2$=oF4f(?k0yYFn ziAHGm1EE}VPOGhb!x42f2QJA2I!gOS;dE;fp_Nur%!l} zoY)vWetw5&XSkXQJSpHtQAwW=>ycBpXcC3d=US0@UfdB&-#=Mf*{4(nD8>2=5> zeL^6?HIev55?zx-J@%04HM6MCJmf&lpQ&%WM7=2vn@QFt9d0GdHYMO(LN*ylagp`4&*81aT00ktr2(5Gu|hsgoh0Gy_waaf`Rxvvt@fQPJd#{_XDQxD#%@`L z^U3}#%c4iPm?Fp=X=+Z@Vf}SVC2Rk@MB$iMq5{)Y5bf3(cpiCu>+vujqy=-wffCk= z_(GSOL-8J=$489Ye4s9Qd-d2%AH!X;1$3tkEZ{_8wo4I1-%@iPVWjUL&YPk-g|t|t^%PNvgMz3}*l)YPeFesg$;`T$_z$GHE+sh6jkQQE7uL#YYOqTdxnGw8M3+swa2=5dG9Z9Mm9&psffVhs#s9%bciM@Wp^R_;Q`|0!nD^)ot zPpmIIk6eEPA>UBy$#+yQriG2|uu0;wSh)MsAO zMqa=s;vvZi^SwsXBKKwy*B!9p7C~r|FqDmgFjb1SW|bI&>w-6NbKlXrzj7kXY2*?m{C2X!(x{s{Gm37qbzmp_I!|8fBkqjOQrbNYA5sF9Uu7*x5kfu&BJg=Ke?x*HHDKgg0O|0 zdUpndV9&cc%Hbw)yG!v@vSW9WF3A_rgi}=+07+_$rbIWH-Z+c8<|YRk3-A%r-FOOzkoWdvE0UTJ>m?8O#8PEVWMGpy*xZMW z9$~h~a4IX_;}NFXwltl^lv^aZ`wD{)1cMB}i+F^&4-? z8vdh|ANf19ImgzxUrmQO+)!aI&Q^aRR;7u;m+q-*QMl+P*A7HX_}Hb)laqB18pc)tTkEDJiV?Xx5WJQRN z_#G$YBgFrWymv4*Y(S^R+J6s0{4^L%g&f=KAlDB*#_gozP%J)9ZXb#b-{G#}G5Ykh zGFMhD3Om~sxuUR zLJU<2Yo{DYBMIL@DC-sOdq~ug*C2ORAJO4A$nhhw>5`X;VY>8i2R|wa!coW|86B(m z5XSAyfDr$_q~Hpzut-2D{HP0(9^yegk&di^Jy>(}b;y^_qi^7`r1;oXyq+YtTmj9V zmL!~ROE@ku%;V4M7ufXgt8hd?VOr+&wJBp##*Hy9eJ*AEbE#v;rKFBUB%?Jx^~f^B z9tVQ^wf}eOS--p#v6IRX+rAvJ!&mn6ADR(6ql|2C4VxHU0aw3uh#j{cvC>+^Mgs)_ z{ROiBWuPlS77LulxB5kspdygbbu@9djb|g^Uj`752lc~jldQEA{(@Yv bY4Kh1&=xyb1Di7$*aZwiW2_|XgVcWm9f#Kw delta 4585 zcmY*73sh7`vfcOIfs1?`Kt<&@!+;I~aZprzYUHzA(a{AzF}i+$h%0`GqbBjQMi>cd z)?kG81E@(^WK|ts;h2S zb#-@DbyxM=d&FFO$h7QbnNM5nHSBypthGN1IK*NjsSN%K^CU0Cfaj78A*oEmX>u}T zhTpj3h!;mhFu@6WJ!#Kzuot(qqfn?bWXP5^byLR-e7@s3$ zrrG!{;xrA$*>;yHmIeluuTH+wF|VyGt$iPeZ8&<3%sY~+) zh%nFy(0HEwb!h`GCZh`~!9A@7t@spKU6?q`a0w@3ClV_zS*G!=NX(H{Ya;OqIae5g zGs)G$*ch9Pj6EHU8OQzN8XS(|qlTh*Z7V;su#gpRD}*Up6&@~+-Gq}g&O|{cI38L+ z!4^_hlw@GVPK6cEC<=WYa4W!OMJKT0FVH$3YBMT~_8$wuo7V6x_?}-eOTGRx~l6KJBoo zGNFAkx2+{HoDn^BT00*ikqrz99fUZ2d9FgE6?HVjcDl+q{hPTxF139I?bck;6_sEV zxN)pFQ{nWQy_!aa`YFjN-OdLtRrQZPb^1n_o)uY^P0A3DS+M~nFgmb}i4|+X-dHh$ zy~7kv;4k&{BUU`DfMrd`v!dIXLnuC5NrOxZz2=+dG71HZ-R7WBOn=-_IvvO&-U1MNLl|FUn1=hhL%Vda)tVzRQ zD(&tp^zu=>{=;>^0r=+tj6i#Oia$bWG+xs>lSmWDp7FkyuzCtwz&(3kFro8?L zg(-BN5Byn+jGsPDwgRrh^;p7zc+B5j9TL*2%V_bbt=+ds;*$1eWr#nQb7}2;Hk#R| zUTZ}OqlFjlp_GZvbx{*;XbvQhfy*ag4Vkt)p-j`LIjGQ4K6Pd-`}il-V#Pkq-p^g= zvKsK|&4^E90Rv11P!B*<1OV`KKo0_p3|u2e6#C4Ij2U8cx$2(>KqIlKoU3I;!S^o@ z_IRUR|C0WPDqSYl_KE+kPrL@ixBF*^d&+r;m)+&8xb63$-+R?1X0V5TQq_M1@>_1O zV$|>aulo4q?Cw7PN#L)#p=lbVV@0h`BXD|dF9#v?kvCCLL+OGl-Ce$+?6seYLEUB$ zpWAWuLQG12yQ+RCe4B6Nb>FbC;y=9=LSFYxpuYDS&4+TPI*sPqtjW$!>2QlGk@Mey zfeXQEUwHfF|I@o5XKMGE^AJGcY5?_z&la!yLH_|+=oM`nqJo`jfNAD7GWvdjRo-G< zV2k6Sn5WRs9BNocvXMyv&Qt-x9u9cbw$8gF>xUaRT`+X)|Eit^iHad#Kj<6%F1k!+ zuE-6ZaxvYZh3hyCd^DLHU14TIJ>-`aJH`e0RtZRNEMdh8w@Kh(MoWf|e%6-PeLqbz zs{=ysK7Ru8U0eARX^OhP>{M^~`i8 zml1!th%V2AQPauYl}E8i%2v(BUlQl4jd&%QzWP2hTqenD=Hp*T#hPijk$kgebFitr@+2s!$F1_ zER&ws^YMpd+8d>iqg&rN#fqcBbnzouX4?In-mx+7p13b^(`Q}Ile?a`pf5nRlEnk7VNr80& zUQLV1u@Bgm)*yj1Cbg@%Aj-(bk3fTG83ixBLY&+41_wX|utlu`05mGjwM>h!kE=L= z@lw+9R-$3QJWWbKmNq=)_@*OSnmg&B{4eraaR?f4?`7ch($~ny%IL^?ht$dmm7DMs z|C@y+y>yAJW?d;mq9vrDG8#`OZ&pTPLh340m{GmtTIC!D^^&L^+n6vPIlLndpC^}h zB;Y6H!Hz_{gACl6zG|=B6^S+Kxym3X-hLl%BsqU|fNpkoHdH6mcCWynk>=ei zaTOW%&dTToZmtm0eVR_tI&8mXmhr8hmuQ>|OSG`zkI4J)%)$rBlXseiOonp8;`pG1 zw;^$XTPGkm8eB!t#tjS>%aD4t68%0w^|D3?5-6=wNa5fiWKGSW(47j>SsW<&*vJ0v1`UUTP9mK2f=AMFv?MP@bPA^Wg!2_a!pON0Rr=z}v{i zeWMfWy{3!;&n^k?{lJDBDQ#CURC1JVSE6m%B}s)9C94blHdFc@`F7uQ{VmA0etI{Z z>&b-~1!bSKSc?p?iN}jW+tb0SBAK{9l9}is^Y_OLzfTaK4q=!xRJVz@oy|hdbO%mz zQ;kCQ>>n}drBA}zWZEMSy~lJ#um*8p;Gc5P(+lNCyLgRE56JT+{_rxNv#>@kfz#bX1q+U)y`ppWD-@EkAEPgb?0zCiLB4j*y<2(CClq$ znXWprquvsFz89NhS}k#c)`sh3y4~)7=n`hq-Q98`o0_*PDb z#EWh}vzoU%N)}`z@st~h-?{sr363^&S*?uJr^9XNceoMAAA`1^U)`oW9%#NLq4+Ej zGoJ%i={cnN=#-@Ko;(p3_RExrot~3x2t(T8Vz!rpcA)XXM@Ed1F6zzW{V=Uwgrg zbv^V5EHk;Zht|1AnGa`WIZ?dYTjL%9!IQkahgOl$h6$6F!_{8cw$vumcAv^$=?*rB z&PW!F!f=pz#f|mhxiX#QWAtHwr^C@uZ=Wzlrk|3EhH-wYz@=MT$bU4L$|koh23u+G zp?hlT#JN3mEZ9%|MsZlr8{Sg!1 zt}gGa#HIw8!Hy{Cay(>tq@OD#n1*F*%)>%qy+JkfP>9c0dBr#9ntxZ!+Z$msx1$I7%(18|m{=+f<12L4RF8}}l diff --git a/boards/cuav/nora/extras/cuav_nora_bootloader.bin b/boards/cuav/nora/extras/cuav_nora_bootloader.bin index dbfe7cc7b3e85daa97f337810b5e5d1041cff223..789124a7493510c9ad1978830d03114fa038424d 100755 GIT binary patch delta 25 gcmZp;#ME$!X+!BUE;B<*Gb3YDLnGtO^~)NW0DG7S-v9sr delta 25 gcmZp;#ME$!X+!BUE+bPzQ&Ynv<5ZK)^~)NW0De6QIsgCw diff --git a/boards/cuav/x7pro/extras/cuav_x7pro_bootloader.bin b/boards/cuav/x7pro/extras/cuav_x7pro_bootloader.bin index fd3b3369f403fa7e44023789712218e685c8d2be..1093b162f810ab2b7831bdf815fc3f012c63fd11 100755 GIT binary patch delta 25 gcmZp;#ME$!X+!BUE;B<*Gb3YDLnGtO^~)NW0DG7S-v9sr delta 25 gcmZp;#ME$!X+!BUE+bPzQ&Ynv<5ZK)^~)NW0De6QIsgCw diff --git a/boards/cubepilot/cubeorange/extras/cubepilot_cubeorange_bootloader.bin b/boards/cubepilot/cubeorange/extras/cubepilot_cubeorange_bootloader.bin index 8a41060950c183f114d261d669d300c8bc75382d..a2b7b74c1cc1e95ac1fc465f66776066454b1b22 100755 GIT binary patch delta 25 hcmX?bk?FuirVXmgxXcVK&5Vpq4ULR9>o1$g1OR|*2+aTh delta 25 hcmX?bk?FuirVXmgxQt8o1$g1OS5&2`B&n diff --git a/boards/cubepilot/cubeorangeplus/extras/cubepilot_cubeorangeplus_bootloader.bin b/boards/cubepilot/cubeorangeplus/extras/cubepilot_cubeorangeplus_bootloader.bin index fef54cd6d8a7f8e611b26e924b1b5305a6a32217..7715cf2d8433ba03ac104bcc83d2e4ba0e4133f6 100755 GIT binary patch delta 5506 zcma)Ad0Z4n_OI&h85+640|LSf!^j{igP>v*86dRCK!6w{#tXcFD9fl(!DM9+uLSQh zZp0%VsE}Wb;7B4-f@fmZn23o9(RIZ&37D9qQM8-6`uBQZv%mfCH=ob9ULD_8RsHH! z)vM|HmU{O)s^K<;=a4&8Dt?EA(Lr9zZHRa8MSQ9i@dYG}j+xSFN4yPcy6vbneGrOZ zF^XUS2%(69?<00m#@dFPB8u1am^G5GuplD$l{S6)PTk6~F#4_bCf%p;eWX>MsJ@m@S(A_-G0rtD73W<@Qn_`)5r zd&n5~3VhYlWwG8$A9y4ydN+hCJIOT66A>MjL#}UL9kX-NJ(RYIpyG4uG z*`bIHXhIQ^Fi%n#4bN7mEKs9eOgiEd?JACH@NGe@-TM$bqLv)+4pqM8jo68`{JC%NlG#>e;$*A=*$sHC+Z8~aMJ?s+< zl8n`jb>9SJwn@oXlNGv{VU;?$#PG>BhED<{+PsW`MS;zp&|PrR@@AxRgOf9Ej#^)_wvERGLMooaP28;(xnAj(O068?V4_c6^fD6y}A=xr$f;)}BBVm&w z@kKIu(sZo1yf-OKQIR6%2V*WJ-x+@Kb!r6)_q0(1L*nKv2wKQ=mnn9M<%Sn{UuKEv z+f#USl{m|=fUjWOhF6K{h9zaCPcXC`5i?8=+K?tB(xAP4>bw|Ha9-5=h3L(qN^KTB z)owQ0AII$!6O-MdWsS9vJ1BbRcD14K`7@@hP}v281L^47EnT8P65?CuW|}o~vyS9H zC`#oG^n-jF7)iaFVib+<;6$NKQ=H0UT2t_faav}0@l7{;3s11N(JG|13(>tt77tX( zTh+4rh2hvse+;qhUa*-#?jYCG3aQLvma*Im4CU)2Z)QBg0x340#CI$~nNu;oPD-*8 z@rUGpvMSyG$Uh{NaX_vut_(*j+M+lW*V1JI-7_R|*2wTx63wSd zlCT0~7Qj!E{cZ!KEnU6_hL1TzR?ZsBFgy}T!>ovk4~*Lykk*a6CpN4dYNFq17g+<% z|LnXco<8i;_;(SRpk-$^FOB`X$mYByq8zNE`KwZ7<82Y?;k4un*CLf9BumV822Rb# zcjWdDC1$UBLRfTHJ3jo9sNqrT_1WOrfY0Y3b_mFRRIm^GD>lwWY*IdAO8_STF$IYI z8l(i+1Nr0st@!T_{$J7vx)e-OAt4>&nYHv@+0$rJ&{2`yv)UvH51fk7^N+ zR@R}&6JnrV66&0hok)AWGmnenJi4(5%`b3%-6=c8N+;G&G4Q#SOnh7CXqa7r%L*$i z2k|sz;FncK2f>iO)hX!llFFv1<_h$pon&mU-}@=2sCnh+tQG6 zH!p0VP zKLpdk(e7=r9D;9tYL`>dz9HqojhmgI8TX&A{T)a{lWjk_w6}c=USR^SAY}#V-coZy zOD5c=kH8%^*O9LZGN^BQ$#e5IjJ@V~jYDc(5zXHf^&ATWn+#52U2}HN{dh&z9dOwD z;B=@}*4_-=y$Q~>wT^r@Z(mTI9qAY@?Dm2br*O*3_yuFc8;}zZJ$|Gr3ln8eq0Fq0im=?bO|L|$&J#3xRNY2?ZBf5z0?5#7G4(TKD!jLY2|SGlf-4;Q)%Uv!OKDSI2p8J z74@)}Y+aF|yymFyOfDz?T=6e_)^cHGB!%6`!?NEPyKo6Ek<1Snf-<)7HYfSL{_21rUOo(L(!mb z`4JeVCQpvhMYqcrLx_%!7={LA={ScFMH=789-IyOUjYn&GyqCBOTk<4Bb42CLSGZOog<7=i;T~1 zS4=(aCDwICL(lj2?HLv4+tTW0Rd1|{>w^36s>Q84en1W<3gvc1D1BQ6JK#&_KRdq{Rk5@s zBtM7yTvR3Z3h7pPT~jT|n-*j2PENd)OLesDd|U4ao~1!5%_`p(JieQNI&*1IAxQMh#mweHZ$i>=^1VYn4ma^5tUWL6LKE43n(sRfOAau-jOt$Bhh ztsbH_!mEY}S8>JM76_8Ih*-Zxq*R!Q!k2aiIxv#@>O!!&-{$d2qVR*naKD{8*hp1) z8mEe*eQiR6bNv&)O-QZcMg#kE=lyCGhj|*yCzU94w#u!gJcUdxkH}k_r&GL>{A;rg z7ZHywM!bkj-x3qGR@58jS~rP!`@u$BCkp4S7@|W_c+EPrF|{Z9@T6P&hJM0Ve` zG|zVC=Bp5d7&ycq6XQYJgn{Jitvjf1Y-HZHiGinWa#g+Ubjr>f_1!EL3zHXwKkVeA zZ3!XkY-*Q=Cm0jyl6s0x#&R-A5U$wCfbE$$k4)dLg>(0>+e@floaE8=5!!E@ZZ&wc zFNb%+F==JE{6@^-8nzDcqDa?7acrGUxIhwj81V`6){de006D&6Dt?{VcI09s$=Z1W zXA;}aH1|COvBiLDGKB;yesJZANs0ep2iDt!UXkH^8}S~S@QdBjMLv;V#Yf(m;e8G^ ze}c<U6JXy`;gMW>u<6lrQp|OjG}|@AbuVx-L1yCWXJAc zoJvmYjtbq~e4?B6EP2R$g?Qb6=}C_+?zHf`RdmHu2gHx_GgX&GbG#`0?#NV$!mn^i z%H_*qd%Q0^^pSzegLkkB@rQerM)_vGQe!|M z?Fy*7;4t$T$wOW^C37yFBN_V)aUa=7LBV1l32B2JtDXrbAeb0Y@=U0=M;Z5}q_m+3 zx%RMq82HzSh0lcjq-Ec@3G*S$%5R?2XcJzM@PFAKF0}YmuK>+jo9~xM4q%ERYD6yA9`D-C|@iFl!qZQ zVVkHnq?X`FQE|_NaU|(LA@$i=Qg;B|b4Og(gs zx^|AJ4v)aOmaN0oIQNhWo>=gFmL=UUl^CJ*P7{sp7BQ_W07&$)*v0sdYrzBt~U@l-OU^(EA)u6euPjhcspS;yCcR-sw z;;K@zwJs$#bq)MM1dyxZ`lWVxjCMJESmGwc{;&a_-T=8hY$IZA1lP~Rr^)R4B>3ZP kfBj_2Tu*+k52yCklL7CCdff#_O9E~VgU~Nz%=>Zw3)v^n8vpND{e)^$siLaGrFud*XP)P-leq1FzVEl!eyp`0Yp=8RTC@EJ z>i+lC@f#E#N7|@tyn#g1Vg7Smh{q1Z4{;*Cgyhgkqi?wp{}g&2xKVR%FBHpS6w3e* zLb0WX5j!n!`SGhFO4oK+wb>okv{gXY(|D z0qPo3!x+d9%ov}7W4Hzn8A*~9b0|i#?Nsci6^*`#T}yI&D{;E*lJ6Uof`<-dOYHt5 zW|aJ|5@7>ksPCO5As|_iUyImcGBrSzdRc|oWje$bL?Je$0mVwfG)ZA9?8ul_szDzz zxronnt2yd;P!no?eJ5hK*OE^IqLhmQ5L;JEt_I}cViFlR9Lm=NwUn*awmdLPiGQ+P z>NSYMI-4gnkfOe=wFQK~hVe8qOI3mglZ&bpTx@%$q7~HlwZy4@M<#D+UIt>jpxKYZ zlAU-5(keArt>pVTkrwYzYAC43+A6hwU_618>r_y#)e*dpMD~r=CG1CRAz(3}5x|&K zWwiNXd(c?=8PfWhEu&C#GMU;pj_TNNTi5qA21+>nK;I5vW*d}z0a>X}>N{UAw-}yw zF+2uHPJdIMvObO7VLDaWf<~nF;p?5`)A-(m*Rx@JPow7U42t~)7gaf7UsC6NqqpZ3AV_TAAM88h9LGDARb^C z+C{$x>Yv$#UO>|T^)GcH#ikqLOXKY%X;>V7pNtI##i$+OEX`Y;K)lM#`HQz1E=8g1SGYuR=9okvQfZK4U(1Nwv zspCwqVvQ2AGkPq@6;YPB^bPVsZ#pjR3coSJxkclniOhJ|JtpddU2v|aLUOq#eJ3y$ymjWh% z7mxuS0jMpnFqP?c?jT}M0nQ$@tr|-)xYo9Id>qDcq<%tlxa39c$=yr1A`Wf&i0c-E zw5*7~rTM2`@}CJW`&J)9>{lS0OGcC&z+Vu1$x6J0l)u)1G0{$pPtl&i@wf%?E6!L( zu?>jNaW&m%jfg*gMtYRd5Lm!)hKdm06X@G=!N=!1;zy8W6QglG*)>sx6G`L5IUymg zvxkV3kN`e^ zqmtb`xvL{-3S$2NsLY6+2sjK_0+5+QrXqGc@KLakRziBj+pDOWY#!4TnR2_ZW3fdN zu%w7O_oS^#<_YfPxn5Nk#puzKma1F#5l{OC1ouRY#+oY$k&-M;(YNfCjAmKxbGuwV zg>q>wZ;#OFIc5OO@AonqMYW<%5|mOxVn@q8yFB%8UU~UCSRV9D(*`5IuL^6Cj#7he zl4+jz(tL?m4?3UiWjOXsXFsC($6nBEa&1;*D^-JHvw4OFej`;$K&{4!c_9@cjgw8P ziV(|)Cp~CNqo_l1N5!7WlJJ#xlwHqZ*if$bnq9uk30|CR?guzll>$A|4SF0MHSu4?#;;LJsy1s-vlGU^2E09>;c?hm5wy`qH1b3Sn zRTgg6@w7rW@}F6~T4d$0^ccIW*vk)44@r2%3%9!+>CZh$r~>*C-hoBzhf{yBw}~i7 z-W1zuXMWy^B4en|GV%|tOnPgl#_~HC3#vl8B(DE$lsLF$e#D?FimkfQd1V*Kw^P!v zf=E+zF^W3HHc9B`l~)grMtMy}py-AdJtxqBz_WzJfB3f@3sH zH3K&EnJ1o;ZRv!}-Cykm-gKWYl!OaSvRSKWmBF_qg+p+J$8Nc7cdyF2 zd*!MfBvomDPhH?aT8eyguTy*zY9`FI+*hvmfTQ$(v zJDWoqeHqQ)6q7j?*0dPC!iC1djyvg!f;KR>J76-XS(g489OzOA&we>XroFK<>~}ZP zGhFnI(k!pQI~gRB!!%0;%%jG$6H+rtW)m+*R9 z5$6&JIa+pyigA+aS$(KMZgOPSu!v_4J$PY$b?qFiQFHH$cu&pj?W5#Xy15B6+d6EV zh+~k3X-`02q3A`u57hHS6qCU*?Gegg&MRa?E18pP!(Q-20Z)cVF3gU>J;}Y<(Re0N z%!$V1ZMr!MD)<$#w!%;k*54k1YAr4ypA0E4?y=CRg$G3W6CR?qB*TVPqHTA%7lVp+ z%`2obJ>>Dcxzs=xnPl06n~BG=8P6q~=6m2_-SAeLZ_AqymQ{eaCSSkxBh^@8+qVE@ z?~%O=-=*T5B>bH`rLXs}y`h54e&<*0uob);N8uc@aM2%(N5CSPv3Lglh+JMg0N)|> z5-n~eaZol9(~=dcrJhgilSZmJw=m14;Of94M%KZz3`i#rmS}rHZ~Ic@6h3k3foGgY zaXh&xooJS-;Mkc<3wwVIoKf(YR|EYA0OeXnovpL&Te=_PBV^Qj@e_x*M~OOQX~dbe z6}z$&H!@%zje8#78+E%q9!A_kxSO}*0S#I9YctIUEl4dk&ErFn%P!xKTQGhhHZa`E z3Y_V4)m-KlXb7m~_{Je@B;URliT@-I-cy056qSj%h@@4HrTR)_P33!3hJ&!y82mjk zSanp0gN(82@juBDtHCD_-VBFqHP%o}$R%r{FTA~apBrwWg1D@M{5OIZRX`BM8sW%f zc$EfUBvY#fQK$Bk9aZD-99w&p3M=JL=eIi2W5sSN(nU_JI7=lsh~@n(s+)tHe18Tm zBdV3Ns5B>8wXzI*$)77#coOkjRX}CB$!n|Xdi@G--xvCKxCT7AzbW?hD0Hx z5#k2OWGoE|t~;z}Bj?u}f{!|p+R}s)p5DYmWt}}Fp7o)cwUAUWF=}oWw*g|54I)n7 zAW~{fM4_990ok==zy~uyv%5YRoaGQgMTYz1#GZPpvb$-lm>T2~9(z|l4PJxbyG#Xc zg>+}Vn!`MeWhdnjbf@Iec|3(IO%ou~BHx8akn{~1RDX%Qxj~N)l5HDIct5$jAu0Zx zm~5QlTqEM@J@vRw6ueFhF`6jUIV0<{%M9ifWpm8RMWXN}8M1M7rUSIB)HvWJ$c3}a zb$%#L3PRfG_}bFo)(p_>RlSzE3gZfB_!*sCBUdPr7vM#Ke|hLeZ$+zf~G!#m23rEoHnAkZGNwK^Yf zC3mZJ;Anj}ms5I)RBTT050-p(;M5=vZ;_o~{pL_Ck*_zKq93|qv@|$wWL(o(Fo zvOBLBvqZaW)-K^^lD1_mK0#J*DaLEbPg{=Sb!0WkiT5Xny}1PFRA@QS4 zw3#-oFe9zpLd^xhvxGb&~;RCuDS* zl1mukCR?`->~*X0Xgk}z`~mZC6z|)H4B>5vFDG}lhG8>tZPnmH61h!}M*JR!5_0mzmbS79*@)i&|4uYHx^jS8u=?Zh^vQX_8R)NdAmCpEW!Lz-jnbn) z(=`#rX7QN12vn|*A<;FNh6raNkIh|ty-&+C>~X=a%!qe8{vLVWi1_1Vbxm{+pH{?2 zIMwxC*#Y7Wr^(rx`!8vlETi)M7=$yho^Hh&oGS{U|F4g2=+>%$KH6*LF_M=%e?sO_ zG?8C+8q-8~e`q{&Cqntejn&VEKOu}rD1R8j)stmNXZ z6h#1Bu$nk_rRb{9wt@zOZll|>!^XMKh1F+Kv)o28Si|J94bO%5Na5}<{rtcBsZPFG zFWQX0%Tz*I<((imsootC*X}~$Aj)X!!@2E7Q$EUQkc9J+f-9;Qgh~e!#kA=;NjNA80z4Dd zANTGt7djQ4otGp%e2zUNa_Zx^sdxwJzsG`ilaKc-!Zs4N_cC@8``&LU|0Z&BUjiO$ zyR&aSF5aw$ObIesnbI$)5+k$_+CI>hDf|V7769$`V%!(nGQZ!8cJ~+5U#7OE{aRdk zISH}TlMy=ts7|i;hY%nU{;vS|L;Vxz3j?YFl)S*+RKy0SA$Bz2JfH+H9RRbUVi-Fx z0I`Rly%$iN0iQ9n58IJQw!I4qal{&KZNDTF;j+{Oc<(~*9H5}$DVi0J-H1k_BeCDg7hP0SirlH5p_2? zNo?-^+-WO2FKbiuJ=Kf!VkBh|S?E-oa$Zh^ypBZ{(G1Ut|9S3lE*gA>I$|}zlX3#@ z;QlLvOPN}FN={3e0{^Dqe_jf88|9pm%_$|2mkAY6ibdQ%;}pasy%qagNgM_7y)Yz{ zvJH`(ur!OPgf7C;V3=u^9f$}H9EqHO174GdKUW2XU9lfpqGniNXRqqG^l?(_02cysd%OAms<&4R(r zAc*%vdZvPAH%D=d<1c899R)P(cI$kpPei!3LwDfoReob-22SOw4Y2 z^6mQ$;oW%RSPyDOW@?T+`ZW}7Hlv9Ytr|^XT+22i#Gx6QhKwnQ!}<$Q%PL~}G{hsy zPRXq9w5(xL%OF1`#$mRKnqZN>?6jOYh5(bfC%~s=8-v8PazMH>a6xW^Mo{HoLu~-} zBb5IL@db!4K->Z4&Y4#69cZlso_~Y<-ypsL@ePPYDCeL|g!C_v_Y1^5W3;E?Pt!E` zCdi4VKl;Z&Cqe-%bSSuohn5X1g-Okes-=6JPpz)Q*-_5u+NbKiszU}s)W6hk?2f8E zQO9tmFOYcuvFUYq!c7m#_`?OXyHZsO)SHJ5*F7lfnhV})B^Au+@R+`+E<$Euo-&bB zmAC6o%O=lS{#&}=~Z0PrhpQ+_s)EH0#nX@X@Hn*~z>Qx==`=d!9U8s88y zHHY~66;jHSY zgKZ#STuHeYFwM8qVkA8;k@n^pDsp$De3=Q|V)45Pgti3caCo`s%m$hs4$BGxH+&|J zDW$zOD}8&h)gm(q0zhlZkX};~%EjA|_?ZvsBT8rviFH0`MSo6CoMaFkR;$=y{R-0J zC<29R1$BfmDCMFWu^&N*X>c0w$5lMT2c&W#RXq|<6sD?&TL<4R zGwZyZHtCP;13I*rn6LJ-SAU>mUbxgW!z85whI0}_!;{x|rAX~i4T+;P>o z17-N#)kQF$qWT!(Al9)w7DJCSqM<2p0~cd)wlFp<*%6R-255s;Kfc89w22>IHopAy zbw#eyaCHMMw)T%L;rRP(wAk*?EyEw#`P};xZIr=SjYYNZ@^yr1@k%da$hGC#v9a*7 z$?in7*wdR)riC2F#udNoKqBkkXHP0_w=c9|adBS)ys_685C8FyuMp0M#W>#XPb>?q zLt>6U0b-Td=#LLRI|EpJvlol&{R;6lnK7t~jn$-{0!Dzu39>R6ACj>+y06cZYoCwm zVexBWZjM6e0IWuZBUS_H(-6Lga2P@hgo6-LV-Y*?dBnOy63HZ@lz=o>SQZ|q=-q|b zOyTA5WW|IC#NI2^g^$Fug^S?^Dk@SK2)~a+_eF4Y?Ld)G5wQ$62=0hv{13q!kskT6 zoW?5;S2uC|uXZFpEu=>-nfYcflXOozHKXI4sdz%V!#q>g9j3c#B2IWwQ2|7!ad znj{tQ?mP8w$tG?tPje$yQE)yyvI=Nx!qqJXv67ClGTs8}>IR@%82m;#@h}!2_64M~ z1H*vkXz>8hmEq}t+=?%{7DY1c zlz1p`7P{Z=nI>nVFfR^^x1Y4*dqT{GvL1Pa?5N=toA{l)ibp9!_!3^LuQt)JY>N38 z{>9HHPCb#yQ)BXYW!FZG#g}`Pe0k?a7Nr%qP!}7r-^;Q`cxF z7YJ8k@^P-9i%lOA(f|14gkF34ez7uUdV5M^K#CO>#>U}%;h9(izAd~JJ28Ayfa&1) z6uZ|$i7yMk#-`)@g~%b8X4~_MH=)oCXm+%`+d&o>rq@@ z6B0k|gX2p)&?kEG8WD7-b)ko)?; z3qZgqt<|mJDDhGsO55kc272WWo`7`5pT2qztnI(~m9RQ8U1odn5hR`yx`$e0?-|eo z@j}aiVEqvR=^ekYu41TQ8#WXl6`me8m1@umUk}T~06%OJJ|bjmhs2%hSL`Bf-EjT1 zMX@cv2QB|;Lq5FK2f{+_%<>od6}#K-p1dvnCTM+#e~*V8kBTx)L!vz(1*cPt?rr)_ zV-85?juV1l8>lkOB|vFu@8Gl3&Y37NLcnpOv0ccHn~cv0%j41`_x0bbe;(eJ;{nsn zcHyJA1iW836Q_%Lt{;zK$A)Hhx)G-!OK^i-=#3kW-w}qzj}O-a<(uj-aOIR3CCrac zHuW7(F(Gluab!?6P(0p>bz0c-zVYK-$e`3=PAQ)9BLm*0)KQRb@(UlwKbtt;#~6SW z;43#GG2b^hl)NStu=+l~U`|NHCxrzGSy(A-Nq7RU6nYb~7ianud~qG}+EkfOrSaOa z*?_Ch{D&-(+Xk~W+{f^9NU4GvIqd$CPjS3<41svx|2{yN0V3=!gjs<`YVIGolH)Z& zi0%J|@b?O@Bo4(Jg!dCCEPTXIxGBPnX+uy7*;>lRgGI0nR z+^6yzC-Bo?nm&~oeo5od6NtOzLB<|;D4daAS3vr`AEn)NU-L}h=fJ|cEKD9g*3r?g z;Gb_qnJyQ{hj=v@Uc*n8-LAmjJV-wX`S<>to(qkHlK>_s6bXoM6YE!ewgpDF9=Hh( zh*;}KyBU6vT&C5LmQ=9w-t;Z8t+em69kE}vz2lh%D45n8Tf*=yb)+?D#j_JEPqlcOPW|P!JlHk1#2`M zm?3lBfYcL6sfw*LtUX|%-2+lT>>+tgDfZi*z>R32-2}U}E(!*{&)3nYDJIlQiEkYj zlA?zS9ZAaYS9}ETu*6}!7liJlT1>hpPS00W>Xqa2!snR1SX0U9v*5F9FGDsQ|iL~!$}miaJ8A2u~bLd7bd`4*0; z;>+)ZReu5p;>$8+#;?=j`vVwu(GrUaU}pQSd6W>(ggx_T;5CYYB3fXtz6v2?A7ZCM zV9FBgwC$8vGn2lJ452pQy_!!8Zq8_}h0?6+Vv#}(xbLQi4G~#|Sv==_tZb${(uPJM z@p~ugF&jXTWslrOqk$=P9=UCX_z=X-(Pr@zVX`h2zbP!yEeL(m#q^kSA%F5x;RoGJ zmDSa7+q}#ojMS$`jc$8ik=06Dar#PIjO(f*N~qAs6}@BDbs`*TJuS1V&eanx6mf)U zpmcLRv~IR1oqxcCxOE<6*x|v3H#}78R~|aG#bfA1^grNa8iG9V&b7ix{lrxAE^GrM z#`zg>7=$7I@G`Ak+ZYCKpI~3vh&Yw_l%O*t<0V4AVc5_gWV{nL44~;T1K|XwPAUFV z7M?Wlu&NsjbE$vz3YwIh)=KuSEG*KlU3vLu6l9dZYxSlCLmjU?SKy%Z$xB+#LYX$lTGe zRo1q|-e2B1WmwZ(BQxy60Xj;Uo|!#PS-QcDI1sP2p+vCC>u5r1QZKiU)U&SJT-&bv zW;GURj9cN5Z4O8;H-iLtEOS=z3))YTA_F-?j*4++$Qf2?GV|jtP!{{ z4vXczKofOZI2ik-zYoCS0`gXM1GN4Ev@WP7MHbL&FDav1L#JGj*}QgDSnCCunWNwe zK^c)MV#R6b1&h5h#B=V{2N?;jx{35s-B7kp!H4nlRbdx|-%TmQ?E_t&tF_Vh&r6Cb z(66iWcY9~xGV9j4*3OgGP+@eoNda@C2^GFIB?;S2c@9OH67)qHBPb7y7Lfs=8yU&= zL>kv3)}}EiN@FS%Wl>e%C~+&E=yTItzf^sKl$*n8WEMH3C{>neDx#`3{TIZ-6N7CK zn7jtMis8d~Yn^pnyHeST);V!N`Z-{zN{DXEYYIp|1bShoA*b69{XIf{LY%OERP@m5 z2J1S8|CjRKR(joiCG+w8Im4MTtwMFqP$4l#Q=D5$ubYdhE^Ca|?o{=)Zkcnlo=m`& zXo=Q8Po&o~kQb0<1v$Vk2zdaRvxL+Ehh(X+W$-69DApyHKY_dE(ju~MJMwkytfVmo zNBwtt_;oQ>A}CrrPh0V*VfVAm*3N>JUDFHKG3yi}tyqk4*1ox{I~rbsog-9_&M2pT z6q|6$KRnZA&Wufow%Z;J>F;iz8sM01rhs%L!00R2F6vgrRIVE26u7!s8es7i= zBC1qCSPwUbt}_YWjGi$6z!#P4K8at}{Xz`Ns{BjH<*T&^EUF*1?%ZeERdj3RI;&`= zEB~Tf7gtt_&&}yd+*V)TwJ$Q{($G?DI46%`x0q>I=40~y<{8d+d2%;p@Y%q9#}x#( zIFn)M!M4hE^OPT5`0Or*w87B|k7UntED4zSZeX+z^>@OV6N!NJ2Ljy`7*mQka(bQv z)aOhwz-svlQUPh?K!;shN85FLyM0H|fFbk#ta6kJ;zLNen5e$G%J7uhuP8S0e*=+? zOcKO<@z{Vgd|-$Cj7jM|je=7rPNBK+iQ{S=kQtC7p>R^RD$4-bwUD~(9#Tdm5~Lea zOmwE@A_o0qVp=Guzhcv1O@S5_rRjSH7QvcIGwThT4L#MB29co+>nVd_ML-(YXNE07 zRUDA~aKwp40qFqnA%rSi;V8uv0X#e4peLdNrQ|h4Pi6T38U5E2Egq7_IuhLC7X zFM&lIX!nAINv4N|=^+gLpJZoQNAu^D_yS1OLV4~aM^xXSmJoI)sWl*b0JHhlwG2pt zBF!1i;(8~#z3r)GB9F;w_;^1_F_Ztgn17MzlpLT#R=JEFKU={1ZBk%EPLU%5e_OQ8|H&^u0K+T^`!P)(@@!!W$Mj zqAl_k%g&KAMbtce9Af_oAq&Fj@q_UX5J%+=hB%1FLueQ~7{&q|x0Y8ityBi(PEw-Q zVMh#WiDK5U%CNRwHMDiRyxNq;zXY4hyg5S4*x0hPz@GpC>8n0ucu#)V1XEK(i^()L zX1FM0mlY3Vkjcb_(QT9NJPAstwB&`RT(wo_fF=t#jZ&fp;Lc&fk7 z^XStbK7GeS2J>Mn%6Q*R+M|ra+-S6;r}7ZgL&~(tcOE{}($#_@l;xdHG^N>Q0(@6< zus}uyIsZ@kUk0hc(NlH^L#^UNG{2~ui7~7aJtNjus~or296}k6p4Ep2+m42|Crxk< zHa(&3|J?BR1Lr*RPvFtCn-?|85v#uQP@@g*@9INO2odA;_$wiMyv~sgZD$|qzII9J z=*c=Xty4)mdeRR$Mo+#o;!x#UqJE`}lY6*B`qH1C1NjG3!~>PqP8>sY%1LGV%`s+m zowaBEO2c}Grybe|J@msh-P&?!Re9)N@Jt_i7`RDCPvBDwSCxjClj|%!)C&FjpRa+9V1>`~=RW5b0|5yF5OVqR zhp)(o>)Yj6bGxkNz|N5i1i8{+jx`&^>y?I{4uhfRxs`-izmsD@WYLg&3)B^eQ7~{HW*=qw9l$!5cO8LBU`T#Lm%$?lavX zLr_+}>x$e`lQ=@@SHJK-@|fiaM25#}-jMHo_c*BN%;KV&|B+40*T6K2v<3z`ug08p zfLD2kqy5e0qB%6#=h))KuYqO5_kLF>to2`fZ@?O-^m+Va-RtQWAiXAdgsfSGcYY{8 ztbt>tKhZ$@)wN{1Tm~>?vz%6zXaOT!O+W(G$)M`s)ixDw)!3tK^I0xujt7n8r*^CI zTPEO zSp=Ou4>3u{hzwS^1JdWdrNGdsVwSGbic}=+q6`_Oqy??WMuxhU2H%@AQf{)P&F*In z`e5l_Sd|y6K6h(8(|LyhHt3IJ(kNF#-uYcvm82UuFMQv42I=4BPUMh3L{xO4kV`P2 zklSxQo71>UR+z}3HbdO(A*&hb(hBg_fK(%sGQ5M}hbZp|L_oUTd(d-Pg<1!3^2;@r z@X-!956C${&IF_ZX%NnZEArVIP(bKl&XR<4vL+ACTRYaz zmqV&4pZZpgh1#ZVhU0-wHV*>|r-eKhwR@p&)2&3^h)!C$pbYz|>0oZLV}mWbOb!A3 zqKx~47@lTyga?r`&;L5?>wls({NHHJSo<1qu2YJabr(h-SPPu77BCXAteXZ!Wi`(4 zjEDjrS(~xyz^Z#xR4Z#B&HI4~%!juQNTdClU{0PgqLtoV)=2Fp`D9ReV1OF~%Bm!X z-x&nKyNPO)^(M0OSuDKZo_lQ&_2+}b3-$lQLmK>R?^oCIHVxEHw2zC|7JO>i-#m&> z_PrqI2g~*+1f&;wCv2)M_)un@pIzfhXRM_}k7?Ybm|#*~d6;pZ_GZ6!yOfhMoW%^D3G! zM6d@=AnP5@;gy6pId2ChV5YUFW#)O?@n8Sfqh6SIFQ-l#z@YjHNUsPR?oG!dg-`Cy z8h)uC$OiHrmRbI~jYu@W{5KPNsBSO{(!HERrw1C%m!IOo`1BQh($W5>I32I&`=vs8 zcv%3fYJr?P^11CV!5MyxOa!a>F?}EYBdKl|X%ffH0uUu)Mio zgWgnZ9yuVr(py_RAZ-c$*Y>`6e?Zz4c(JU!r)LEMO<|wp9@tny@iY%?TbM<*C1BoS z8_<8Xih2s^!~9fiV(!C>e2MRccvWi!B~2(L{}b_^?vE#6f@ zh+&>>ZdH7#PITn!de&kH`8qLxL##+QuVP5)u8JD{F57_g(*TIvy-$HcNH+ILk9j2h8=kSP-1%L~It`GLME?{lWaSwz^@KR?C<7>;<|Q z&i@im-`@L|J}J9jcqo6&y*nENH#BAALGi8Nr_|w(V48aI4wQDG8I1ZI(d9AXL_bOk z1H%|2&hw!(n0BIp6$fPD`+RM(aJ;&Rm~ZnM6g+DWBl>jNlBnpSqG3B9a^MJUNyd2- zfS(%cQhA3dQpHHcAHAzV&XI5c}n05Pc-*~Cz1cVC#HcMxbFmr(f~B& zx;|+D7(nWZ&VRIpbf@w^bqCnS5oh7o@0b(uF2srh+`!EP|X*cV#}%x6L& zKiTm$SbC7SN>1nTE_y!_AL&(qn2yBFVAE6sV%dg%X(J$%tTh&tOfP-OHsv*7Jy>LP znb00Zh<7Y9FkTZ{QhEA%VJ;Hyl^O3^bXs;!14B2Y&qDh9X-&W7nUOf^7_sJLn);== zpqD)@&_$yw;S3KD^nTuV)k7p#Vw&0s>)Y3^X`;oBX26M#ED@|{O}NHt3rO_?{~6IJ z7*RFUV#L473jV5nhb0<>4_0Y{R{j#8lT?=iQljuykpZt3P8JQb?17dQ@HWJ5A~)fQ zhV_~ztV2}+sqafNws2lo6~s?JHqoxDcAR_FMpPI-_tSR9D7s{ikXW4N*iekvH4rAw zLaZezO2!i@8Ba#WUa-K^yryAWT}S~7DsgPu3W{)~=lJ+)b%#dAQ)n5NA<)8^<8dBL zI1hOfk~3+sxJaWax|0!o+M(eZsMX(Jf# zG)=<1lKb+DVR^PxRTm{UzQ)HLBK*S8S8(#JRC6Gbu&^O2+2h_NkqdpbULw5W?1CO=!8i3tzoDZ*q?iJcVcI+eBFnVG zzlJ&IIeHs88qXj1J{y?<16vh268;~H)VWi7oQoar)fe<|i(5R$y%~{_?heIVnVCqn z8al7828D(3!)7w#WPYKgK&)jx0jN=tmjDWR7i@rTSG@;0k4LKA`xM2^FwDiINzx)( z^;amdLy7I*C1@2XaW38rCDoBsa|-nPo+Aic>-pHb1m5?Ri^si{Fa`T-Lc}ZdOyJwU zsrin7t8Bi^>}~|Su+2Mpf`wu}wmBb8&pkftR(0M_mPVH5x zBh%Ua>7pt$tvOP6;szCp#IgRj=Ni&@!yUjZ6PAQ_j@UIN@59=D^2G|#|v zEia7$Mtpf$So2nX2me7At5$chN-a=wRpY%p$~23|*56lfk*6|upT1TuW~smOl#51n zvnQ;MoA6D&(N4Pg)pM%;vdrzlf~^eiO0*;h?kO>jOjo>@i5%6wtuXTvp%wDJR6E|i zt1#_S2n-DG-q*#l1`y9^;j`w9&d!wz1I{G_ML^QWARgvoy_kwAIAJ;39Ee9FV?}jj zqI)6_g8t6pq?7gdwZFlEMSBBz?Jz3Dwt0S57B}PEYaV!g2hRvwix_Y}%djKk9l$~| z|NqB=0kpP_Jkz1}1}2z-7&F=l41q4^Y49MNaR~xlb(dm$&_XhW zvCW0LCAu9&WSW@v?BEbDDzjR@^`ek0-QXmfbjQ8w$kZPPpBNZ+h}VSodhjknQKf~o z&1!ERMMQ+{%_iMr1rCsJdTX1b<(R}BMSt^jfT9bJ``Sagr+@%YdW^br9-RHLHzeen zdbj60SS6SZ_i}1jLla+?Ig?%$*$TwSOeqX^^94t);mLoJby4AaT`J|Bwm&>y#K|5q zpg15{kkUv0=E9S&!LnT($vAqrN(wfRs>s#uBe%I_m2R@sV411E<1fmLWFJ_It-NHml)zI(S3XXLfycq(Rk{e~X!o>EOe66tCwnl&pohbEY%i1WOFeC%(s7j@`hjc2K$P^$R`ux0FGpPopj_CS3D>+lwKSx zH|jVYw7XE-oTcl8!H}LDWV_f=^u4DtDdOWaeui(utsi06j0WjoN6|Nbj`-dkMfd$` z;v<7jRaw_%YfKM%CXrY2k$hsa0S+m$aEE}`(=V${;G?GJt-wz`-K)+x%1;bJsed%( zyjQ4@v2kS=OWy!?7-WVGWGe%NkI(UXX6O6?CjPIs343O6k4Cw5ojUpJW?!nmGEqIn?{R#z*~=oY6NuhktKb^Uh7{(xbogYl8Wg$qD|G z=bf8o$oo17yP(xv!Wtq|G55~Rdxh+o6QWFIbl2Cka1*UD{jLgq=VpemW@dt84|uxm zIXwM_CX^BV@-ooLZ{pF`_5|X-Z3VZiZI@^8^LezR1l|+8UcIKUxx|43eCI;+$iT|@ zJ4QSsujjY$*E}(IdwlJtW)1hdY7LAfI6kHw`RKmGzZZorDZmri2}fX8z2V;H2?PR3 z5dLr=@G`!=G|Y;e9pj%lm2cI4fY@oUow|exvy!o1m^(|CYXDWJcnRzsU|j?UngUJ3 zW=jlDyAoI99F!@$wegxJGGR`bs-e84aX<e&7^6vR(02bv8z`&_&{dJL%kgyqRp7oEBySx zJ$RBZ{K16D0jVJ9e@dleHxesO;9z|6M0L@i$0`vekQg`-xRKWo304o|>KL&fIHa#s zs#YXAgr^=%PWl7nxjXIP(4_y}b0!izIb#ucys=YkHb%s~Lj8j|i&g@+jz2}Ii@AW* z4qUye9gkJYIF!k{?FQ$3&R_!pG-!xb-%t4Z+|`tk3~0JPcQrOD+{7T+^jkFy<=6?L z)gawy8lt8cfaf3XT4awb6S&z!`OsblycPn|QvpW&NoK_NL1bdYcwoPY5W$G;jT*4j zQfwfA*~4&mK+^yoAX8?^22Ni`{_#Bp@Gm%L$A;|b%`xn=0eG|U=Ilhr!LnBmqf`|S zitF{mtLfL-VvZ3P^^U9q7f#StA@R}m z2wpxvz-(oJm$(H|FC$udnccdH$;RK>@ZK3Rs4$wJn*;s{5T2fk*uTyGcW|&f?`Djj zhuA+L44;qK1rV-4a6mW&q2wXN&i-F3{&yq)&$J&preKf?m?3apUQh2Px)@rh=x~(x zJX;-*t_~=YT5icT1gIM%7bM=Qu_rNU=+^HwSAK&_8le$Uv53(v0u5MTfK;dGD;`F- zu=q~!zZ?D^E*3qBsUZE2WyFVMMyK4W+#isB8_3M+asTSUsif^Q!M0D=(7S2S*U(0@ zL;SJ^8-TA1r8q#Yi4i}5=?$0X!1N}8BbW9>Fds3X6@sZT?X&3GfMrXulHCLxUuglR z#e8pR%<7oN$z=(vW2*CSMbnf{xgU-EMAm|IynkS%2Z1xq96p^7_2N)klmq{O^}>iD zGB!EP;`AD3jN6j~qpJvF;V(5qz-QJhuBb7_L6@2>7If?J8qh#E&@Fq-75UA>bNP=g zvF@`_OKxS3vde!z}auyYB7rx46n^Yke3$hY-9~e9nG6N$Vyoa zn;9YZqY#ckAPe;S7?k3I_%xKGtO@SriQ`?$H(o9&wSU$45+B2}94+FA`Rtc)Zm3+s zlzBrOIa7ce1AB(U;|9Fxi7^E&%KZb< zu>q*CU-3F9sYwNZe>w<{R?fagcE0-nerEfb`lPIBZDdGO;JM6I-s7sKMfbo4(5an+ z)b|4!WxER}yVJ{dSnhRSk>5K^APPGjp`qZbEq*>QSfO!XPT}O9t)BuR#}GmuB;(2b zU;a9{R+IY0x|NCHZbInF{giI7e02X}F34Jx2c#F9$ofj46O3wiHjm()Hw}>gmj+(2 zTy>oT&L%qdKP^WO=|=`yc=gvo&g6Tb8ynD-u=Sz%+&#YV63#}82Yq2>s7_1Hx}4Cd zR-M+KVWUJFoSTaFG#h6pilqTbcRa6Yig5X%1UOfFAJQ4dLpe=OJrhx@smnN<);<9C z7pxEWsxSv9rA?T$KMYxHkgaN6k|1nUKrNQ-;g+3F{ z0_#-``w5gn&IX1B-HT ztZ-$~*c1oMz#X>&)Hc(g{2*Lth;Q#&O@kVG%Mp@uz4y8&==gbm<=KSQz3&1hh>n)H zdmt~zlDiD%V8hvqb0W%7)<0#mHS-e5DifA3j-zB*cxmw{_IU3^`@SwUEqt}OxMDyG zlZksW^z&waC(39n3ak#K_i4HdjFE2^PpB(vQiGp%`9N4$o2$!&+X|xY6$?OdbI&f7t z5nU$I#hb8r6&fbxSo~K2LyCjc#b7EEQWpY@Hwj@KVJEQoLvwY*22gZARK<9;pvA;u zWxxQFt-J`j%4+hw9Q+G`U(xMb%JDiO+dgxYwJHYARLT`n@R|iU9AG6kfJ%b79J-n| z(yn+2INR$9fqWGN;i!Eao+)(M*Wg!$N2>~xe(oo7sM3|s?*V#=gF_%7DFeaFB{k$m zR#l>Kr^*bj(c>R8gzx+kyvKA-dqCR$r7U1@<#Ilzq$2x;+Q%M>t`52Z YU$J*Jt zekl=L;j8u3Jp;ntYBLo#ApBCD$Mj3@`vh+J)|~tL^6e zaDoO!p2fviW9}awoc^2}o=n*IjJr+VW7=V%KvlKFvciortKFntcR!SCNXi6c@R_G3 zeQ~e`GTQ#TMwI12s4~k93Zv?Co-aTZyX~oX#}11XfF9;loDrCXWAY+ymve`_nA^4d zMUO6htXnlImo&m{wTyOK>*DQa0d`mIet_HkOs%}w)F#`3?L6i}+>W9KsF8TLORbv` zX@->6%5%)1EOlY-CX|QWEoUKynpwu(E{gjJ5YC}T;s0T@7>?o48uPLe`>ERRoU}cm zN(+}9$QHox(iR-;1-2^w>dQE{xqf%O0Cr*^0=@2)H|o{(TP#|){*`FRRk{IAgF!uy zClKq$&^ki=kNZBiB(zQA`yEnm@1Wn}zQ9?}=ayeCUVB+1Q!O~BV(GYgEGt{$>T&K* z&+o1$&1?yF@`J~?DXCyo4Gazjde~*)snWB$VpzDTeII#l0-5E(0)ME=d`q3X6MQCa zIHP|w-%SEpUJCYbWtb-)XUpa@F0gam;fq6Sa!xI+pcJv*7|dU23D#Z-X)g ziiX#V*TDOF?^2}W9Q?M&wiXRi#!8uJ$TmSE zUpKxbGbVCTbWoe|!ApA|8&|(=fo0a-myY(1u;HBO`Zp|lH&Q=>ghB7yh_k=;Fy5C? zpLCvVb#O(_%;S4tyW_C_fULBACu^#=$PBrc$3<6dEkbE;xqk5E*R?E-x4g9BrRe&E z`dt?60yeN2?s&pJOYjA*ts&4TzEj^PIRZl1lZlSm&DBlSMX-d*Up<_nSHUT&*pGC* z(gXf-kzyH;cW7{u#A@rUIouDj#;Fv3xXym`!}XBOebSfx44>Bs*U=Qpx-qu2yZR#Q zttm!we!Z!f$M;Iv{&24*Y@H zJb(CkduXXf_qsgW#6Wc{n)>XZ3^@SK*}+O+q4Y@y`qJR(-hKsGI!V3ihA^H8Cos>h|>DGx@e>RTobMIjxtp`=eja4!yzZLoOGKWh7+ z8gX*dGI1F4dk8brC*5h1;qZHYHJ+q8XS4T7*I@|~8^2Fl(0B+{kEpb_%{3Kh?n7dd zZ>U!T=7>r?Wc5j{{$GPK1mvI|5fr&HM zP?HC@Z9#7XvX1IfpY(7avNLJ7T`#3|yUZ4p26rY6OKgUkE>A5m_eAM*Vj!fL-h>5d zO=QF`P>WcAS@3zd_X{C*Ef`IOv1`ZUDZ&$LXH(OC!q;opvR&yj&yRVNp$dVU2?orN5%Psc}_Eq6m~mDCjHX;pZBl3oewwRPuUgj zxpoauKy;tb;hciIg{+$NxU~L*_DcH!TTI=qO*m&4_}%6A6O?Qdmeo`wRDkBsFP#NW zuDWRtaAHWD1LTHM{L+^~SIru{M|gC-0W-pu^+m?|fZY~e{PlH8fyB>Y+ocbSO<|m0 zx<5ek)9Ub6l%lZhx9_llF;eJXuXAkTW5JTQpgp>gTv>)IR-?3+@kd0r*h21}f&p%a z-3*%uRuHaok_#E&dah|gM+rde>eqmr5~hGlp`$*ukGnht`UwL!h_gpj-b|1akobPD zB8i6ktA0rw_?PFOvNoGOl4zR-p4{4eAcS7njr*kWKDgFOlgq@9*eWXwi{6t9ww}JO zG=v#8f|mp7Hr9nwp<6SEYDDM#;@{-h{2x72QW(E-m1)csm>*Vg2>wGA2R()0tuDfj zLH5ewaDN)E()gLA=yv*JyfY65ozur8soRO>=h7y<=pf(tfDemYXO>(7tarfDQUJz? zYYDh8Kt+&B;XRguq!^IgP?`s23}6z}K|%cN+k|uXLCsVCG$>Q>ez-hG>h6TPAy79U z&4Ui#ZGOxy0Hgqrp9WhY;>6jyz)uTAkM@R{${Me3YFCEB<(apHk2WR%JAY=Q z0qcb88xyFk0YUlvG!^qDSxAox3!a}GwXYu=KrITF;goP?wO86LeDZv@<6r<8z+3fc z@ElLQ?I9OO#fF%vh>Mv*jmWUmBMtV1MuV-=CN@Re>+1wr(-O7zr9%1QbUV1ywVb++ zbQ2meH`6xsX`?Oq>3F^pROX?!nYN^-WzS4|;9qbP4%$2hfr2|=JM5Vza{Ywlky~>H zVZjSVkTy5H;DCSii(^3$p8R5ESSk2s!w2q;2uR}8S6~h3=__oUrX^DbYQte1VdR0kfMI^Vk zLYA_7Rfb5;VW=Qtx+LxYGB87h@Joc7XZS)bx0t!Hdig|jqaVEgwH=gq7;O+EL+2HuTlLO&y{y77{oVJV z%)a?uVOSe;ZXT$R%{+2|j(Q9v{NSb?Jkwu&P-eiBO&y{WF(zoOioc{PwohqBBOj2} z)u&V{(2dM$X6>NFDwtom{QNP?0mxy`?Xb)^x33F@(tK{?e0~gX=y=ECKi8gcf_Go1 zEZc2ib>G^5w(YRI-$g6T7enml;>!v`Y!0I>%ubwi9=Abf2u^pTwSEgJGNgSzg_mXK z^XKbAx>V@Wbt?KbTNKzT!nkj38TNN9@dX(+<3)e`N7@6^GVGaN~Ikas$VI_ zexdP|gt2q1#WtcsA%v0FURkAY zRpqN$;pP1*aHP<{LE@L-QwXmP1FKlWt7Y6&pFU`@L*})OLpo6E4UZ3)71=|W5x;aF zs6@8TpkjT(s;$#tyE?P=6a1{O^0h+s)Yrf;17V_Y^0frT%fZx7uRRg<0(@h_2VZhw zcugJN>6hjS3%5N7N5JK6>8fXsu?>EyQV17x36C5@dh@LzQDBKXCN{iifBrBrh7Gl& z(GLhE!f2c+JR?khD0tc53@q8PiQqQ-57&J7|K5c^Hs1=H&Vlm?eAlAA367jx=lA6B zMBjKKjy~O>`UHRUfXpmKuMbEM!}+Cbhf7~P-T_MOyDXhwnkWnU?Tdy#4JNcJKEicL z(*0kc=KSZ$(joh}Uz#txyM6qSpBg{$vSCkLXa0`T)$Pa_-;Ts(!p-e*c#)ubU5BR& z>8~eXt5EoQdeR&Jffdu_%QDk(`8s8Qi>JTgvoZ?Z0g(xg~)O1gp=jp>xy8^owWH) z&(~f~b;PXqsrsgL(qWuW)q{P??nG-Z!B`1`be+E!oRP^;)P8Mn2&_K>hCun0w?c!% zV7-BRoMNrB7EtlLbHA5jD+&e&(<`b62a}Kd5d*KlU>s!JfV?q}pL?b7v5Qn*MS;1K zHSh6L+u!Yq!0%el@*nUIo}cMjP0PBG-431Fv)bAnM|?H zM|Zzw#@0V^c4QC><3hu%ok}Zoedlcp8(E4 zXeyIA@TDCiOK$&EI(?5bm;*xx=W+76GV<{*WP_c=2WkfJFC_!WJWjg)3{()L zB>KNf!j6Ns>p1ytmIJOXgjW|uq-}35?*a2R;K7;{ZX|54x=jaqIdbqK(FzqZ!6W&O z8{Xav&D{oA@%JkIQO1~Z~ff4RhF+l0yLj!8}O|T#;+sYRJ0ih9v)`OP3=1krM1m}k;w#J8H|M;|@ zbW_tGUZyF{1WJ#GW}ofHy69rRWay`KQ4l8+DHP<)-}?R18~rla`)bGF5hp=IgUo1- zAns1n61IPil}tG&I?Qt_$lSC6bqc08hc0=ri6k{0sDr37aPb{!DiAq&MtZDcirI!c zQb9kdjP$!Iz@il_qwd0v|2HfZtULPdGm|!W)Wo!rH~3mO@MgRb2LCzmdwEU7Na**p z!6zTd5HXnC;7dAgqzgzFL4cN|5Lpo4%!s4-o%R}wx((k(Q8gCDMMZIq{WbVVrB=v& z%Ygqb%zi5syM^c8N*><~@*5MBmQq~pT*x1PdPLdo09F)y5W`x%h*$G-Ce$V2p=_u=w!hfY!Emcz0r_^Mgv*60`15Ye@0s((O;K(lrp(9J*3#YWx=8UmS`Ahbw?6IRvkB-ZpFfJ!|Y<3RZ zS6Tf*N_O}{xO@y@uns~)?xvrqKy11lu?aR9Y2{#f>k=51@WThgN*;I|%-Bm2JN-$- zmO;GyF~n9t2!${lLNbKiV5N#%K3KB|>;j~Rn!E8NC?n4XA?w53>_1k6gAN3ebLDQF rx^i^tN_d^?>)~=v4Ps9@2g|>M^oPQ0AI=9+@8*Y-;i5>^{_p-j9A~GZ delta 21883 zcma*P30zZ09ymVp-b?a0B;k^92suE3fCkWtS~Vo_IHJX~_2?0=?xWTft8KNlCU|T; zdZ^E~3bnP;!=4h9uIN&1wcTEJ6DzwYy3*Pj1#Mph%_9Nw`%bXC`@cS)e?Fhd%zJZv z=Q}gs`CjuRHzm2Lh6@xf6FMk^J)r_=6Rd(+`{QtHLPbLP4s+U%NR;&>wT0jY>~PjNg-XE91g z2&MPFhgb&EJAX%=4_G%gB=Ndlhh1mxb>t`6=2YO_xE5ujo;nAvLk3gND~=fzGs~gV z-s&ZKQAt}w7CMiB=guV-(L_i5k?wUYiLepis-cVt$_W2S3$`Mwxgv8??c$<}q$Nca zwM(emC_ibbsp7)oB;G6@nq^P2CGop)e_Il-g8zIN*Qeq*c&i1>r%CpPJ zAWX9@y=ZoX-8PC8>@_`M?nO@|*(gYNngJ)XsG)QSKNK{e6XCt+n3ZG;C*@CaWK!{xy%5==Oh;Kq>bSQHHzrdyp zz1P6IsL;Els-#713u+~!Vr$S$0^py1AM8RXh;ty_4&fq%P6*c^h!B2(P+c0lVLU3R zQij{fdX2XZuSn*jx6-|iC)YZ0UbG`->yysoPNXNfzcg;{iQf95lhGLehD7VJawnc} z(}S{qcUgKJtK}83HmvXRpj?kj56=`l|LigTt-2Jz0{pQIO8>nldLz<1w7>VLHa+oa z4YanYN3~U64l|wrRU&Li%UBZ~KQ?ZHtf21$s3@G3e>zoeMSwHtfrnL55c{9KMcSSL z`z7us>Kxw`K0T5%@Da@^T$T;*L}HJW#pAt5oFbf3Xf>qv!Q20QLNA&uUq~P2k+!M< zfuxPG(1yUUN9`l5m1591qFmLK%+s)|7NpSLLj9tGI#dK3c859OPOv7FtEVN}Dn&(3QS(AAZgg=iOp7pVoE<<8rUk)^o38C{X#D4o{oXs||E-E|RmDGGr$F4+T zns75L?T9KolbY;;wmTuPO;~&`fB{fO!Wy;-iAW;2V zhQ%lPlVONG{v`NMf%h_@epswsJ(yyRa3XPRAQ@tXnAe{adfphs;sIG9*NP1 zl^Lo@JsCiN#0io-6d#tbIJv*yQ@}4ojULph2D~4IAOZS{A`z>C^l1p+Lui0-62eCi z=Eov-;TFWo!c)iuq4c0{fiN{HQ5Ic?*ka+Ks5DvCFvQLgYNAHrH--13^i)xl@I%xT z5=ALBv}^DYAy2sypAz0urs3E!s7~IqwO^h>rnA0VIuRTu@y27WpeIdAwaT5$+vy`$Ei;ww(zOM!oVBOK;mwk**_jJ(r!(bUl zli|IL$6@2go>)Grd?6YaYeTvS9w0|__m8U^yO$`L4odtw_%(FD$1_9HA)Ft<)862e zQ+!kxO_xY|bX6FL9%0|g?d234N{{D?IJK_YNQ+$o6ZgEd)kKSz0$j@U6FD3;wvdx| zZ^l^M*C*#HyEccR%wiYn4hw(Z%Z44{n8_z4bif2)o(?dav$%-EV`sqAzQCN~^Cih{ zq^XdY$m9H3{(jpK@TOZhajpa$LtLiIMT_qTu<_aD^5Qql!_VTe(}a&>64GA{I5@md z!?9k>(&F+!ak0y@Qe1%A;6DPL^*ntLu|iaen#Q6{pkpm@-}htVR`c&}tdTqz)&?yq z`h*3sDRU1>WX-FZ)LI4>SwPY_>-i3zwjqtGg|rp$R5!t}dS9xh#5;oww-ff?k$^0f zxd2N^yfm1}RktwSbad1v7mETK4rS2dMd7>Hsl&AJM2qcY$%!8c32|xc*5lWpFW41R z;>^RAOBx_@9|cMFD&fVr5!ftz7*~Yzgqv|$@sR_MKTg&+8u-P+nCLy}%|Ty`V2Dq| z3x$$+J?;^z;wKHO4>Fw^E}i#!DDgeP8J~rDp(8#IJB4Ax6BhOdHO+XeCdcOnia%Dv z6}A*MF&y$vlVw7mbAmIP8Sk7>`o3UcGnC0ceLY%J*n-64{cz}sf9)4NLp4;PQj>z2 z&1z_e67Lc0!?pM`;jQ7h@$Us~P6Myut}I*5>mNn>`lU#$7Oo7R8P+kVX`WL?iT@HN zCm0lO4Q_#@enRj*nlQmscBhdN4-ftY-k{7jw@O2axB5|Ly$kE<)n`0G->E>>+5gm+=1Yx&2 z2j37{)sx4Z8NhY4jjCI+SrOVCGdS69O1v>3t0isUaQ(DHw!5eot@>$G5sdAmU`U)@ zd0;?R*KzlZJ~?27-n4-O9>Pn=tg5CIKIr?qpTH2)*K$o|3i@2f$ueS_C@a<^L+;ML zp=SrLF;Zfta3*mKb_fHBQ}JbCa#EI|W#DEb!3UWY)arocntNTe{Dp_5IK5J&!Zi0B z;I=dv0iG{}T}j%!*9P!dc3ebG7wi`q8O0`2N7Zy{2g4=H;?GTNcJP@_%QM(OxpSb$ zx8cscylxPjS z10_sQBK>X&lMIbg-8X8rhEs(~eDa?XvHvMSjbi_&#C}pjcyh$JMUDVr<_Pbh4oB&L z-^zII{))8BEe&TS)Sv*m-yyLFnDZ;ecof3v%SFu-xEV03%@V^cYaV_AX>NItq1PP& z$F|oM^xYglnK#{6JrlTjuy-#CVX5Qnmj`6rmS&XWa%s45uL{HNfQ=vY?F;_hgLFeB z&kWr3+-QaqW`{#ZP8z}*{&B*LgdI`<^Yn;+M-Sna9JEi|}osKIT(Ya;IqO2f_P;>Mo2PU$J}S3gxt z*X=R)x`!4tRN6!dxDIMB5P@O9k(r!> zzN^9XsyL^9{fB1SJ?Q%#h*x1tI)B>}yb%N2BAK^1qhUBse`m9*jBE@_{O~woy<-(+ zzrc=v-A`r&s0fUpQ+O|}fO^m`T#Ps3cZ6Y@^29Pf(%5W&tS>c}%wP9_Tq5QRD>Zq# z0>9tGz@nE~DZ8p^wv?}80Ol!vq}M+kVlWR1UuYK0+~CI=y203@go zt3Q^I@kNO;;a6z!<{$7 zVT;y)4+u_eeD05q$E>rZQ8qLhiDw+B*Q7_Hl09-8jX`3g=qS)1R+qBXmbm+3|#`bq)quXc;&RT7Yb6t_ev@v2N zQ`xnZR%#e;LoqEz(&r>LZm&tOYGRQjbt4m4dH1h?K}^yz2B3?&G8`3 za~`CB&4cx?c&LoeJ#ui+=3jFyPXY zop2WR3A%I+s6kcwe5%YZoKDXVTN7xx#+opkhQaiB{C6Qf14Pk5VOGXy2Iy{|usP!% zMlMd0gwHbWp=#{Hos0vJF|JRj9eEGTfP3VquyeXZPGcMNxdl9G3~ms7dAzXc z%jNR&Z0;3!JLqG8sHmGsdcb!&w7P%F0#4%7Y>iNzor-q~FK5R`R|W}l5GzJ0e|JUc zV;A2L+OpH)vj#i=44iR5voh#=AYfa`I)lF1LYQF!o+elfGbaxW3~`6u%WMA}X{|Lg z?tD(8jVK%NeLryU&qRAM3`8~3#)VKD|AIEu&X#KuoGxy`ZHUc1H;D9M(^I&)Ac0MA zKAd7K;JFv2FyP9*?k@nYip}x58Q`f;!aRO2MCUvmJ@!Z}w-m=!{yKj&6Mya#I!4%+ zlRJqmr@bl)>mzx=q_;%a#1<{5=l%(6A4RYxB=rPSSk~0pv{O=_jJ>b2Yg$6fd;^nk z?n7E7$a3@UkyUImAx$(NVF7qsP#CFG&`;`E*M+b9X05r4)>$?XCbmP4+k(E+twG;Q zt-|BEbIP7q53c{lDbLci!$I%I-aM1ri8DUpBK@+SMDrV*$~CepO8!gZ;2J_GQuNC$ zI;X8bT`acbao0Wc?cJ+^eH*9971+_7UCp2D8Ab%QRu=lE*DvZRqUkk6gaZ=i_9 z3gFr&IQ1e0cs><6+eujqJl}z_GtdUxWD+$|HtaxB;fh4sc9 z9T72Q&A@hQuowokTbZsJa=bFwUGB8^NS1OoeHDYaI zlWc>gas}?5Pm9QcvI|^aZJm=kw)kk^PA|71)w>H}ewY3U|!(TwaLG z&mM!j9Sn6*Y{BV2c+z=nOtJL>232GwKp;>^O;J?}E|Pn=Iby>YVN3o5%Gn~E%#SM? z?k-r@p`hEAY#^$-B~NKLsI3+F?7Z%j-Hnai^-A_ad;??7*+!GTivoS-N^u38_(5OyUG5M8 zH%=O}2Yv4asSUB^;hI@^_B?$r0tL%X%j_8gzG%OGLsSK&U5F#f_RTnWyXXm`^>HkT zwdpp{JOwNS)@=_pPusq_i!BzgMYb#1?kw5zIu!^8(VWc)2g2Zz^^9(Dk0N%-njzK} zeWt2_?4a*a03loxUQR%;hz<)Vs$vNUu0DAM()`ganOGJkmK@2X1A->=2AVr7$LD~y z2@&Ha+h6G)QnbNJ_q7EjkE)5PVmMv1Wy9j0jkJZ-)dqd%14}lngy$tsEmYh-r{$;+ zO98axGuJSbJ{I}}o~|^OFPJu@mJa&pflglSql?wuvY-K*~%Tw;dU zq|z@ev{uwaAj%Uk=^a7`MY0#Gk7$evsqccXKbTy>oAoN0-Oj+*r zo>Fvs_md2_Qsgi>)QfK&_A1I>o>|=j5j{C>`Z~;&iV~|q?FD*Qo_km8y0Q&dBe0W#i*h# zTDwOYzSGmRe%@ z2jWu@5+T2U{2hj{M^c?k5gDZn^mep+xad$KSK1N%dZH-SuhFmXPz-O|Bds-Na=V41 zdlD;O8~h_L=-UNy%G=Vz#vy%(5t(E=%UGhQS{r&HI{`B;FPm3PSdKJL-h6`oC z?k4S1qldfE7<+H!;h|Qh-l;fD+S!XDkzpvhs+k5qgXLm)>_TIF^_AyiM zq#Rzdo@jk3!_?m4hxKqGl0|Ciij0l5X{@^Kv8KO)iVB0ed*f>T#tohxXn{K1d{w)? z651U2M1*JmC-Xo{WbeK63C_0n_I&ceRo(iTko(&wq`&S@X4^v@dOrDMU3K=MOndK@ zPjuVW04Zywf!M{hT6(F~M60gf*miY@iUa#;3W&j=4+2rm?I?f28p$W~J1Xcd2Bny& zE(A6fQ2IGC=%}{mtZ@^K@| zHHl$0q|o|`x<;@si9b6~j_Sg?3ani>J(kbphN#GZ@1K3wc#V_dXH|tev$&n5T3LA8 zs`9TxlqI=}cJ2ig@e1JEzUcc|{$Sg3>j+*3{QohpTsilmtXGUZVh@P|Yifo>f#)E0 zj45+}*%Ka*a*JILTT@2L1MEHfxPMAxS0NA*Dr#Pp?tSYxAl@XJYW^u1S3L`pB+@DX zvarUKYv2^#5$I5>NuTE56hOj!*!m3tRCg^Y==(bGDr|B}_ZSe$zd-8Q_3ugchZ_h1 ze|8ONL<1UuLa6Y`K#HCYuzUAHAwpHRLOjKqVn$*~P0%-L0D;s*REO;f+@|8AZ3|gV z{sIpgd09H?xGc3F07}~MyJCD>Wfzw?Ut+64A8Jf9Ns8n)tRF50QMtq#>!fI-!A;wt zTbn`Y9tFhhr~W$VC{|>!!VRR`Pl_x8;C4XVtf1N`J*hZR5z$6+{s5SW*Y^*wp}ZBW z+>7O(yAwP^3-^kf3<=VQBm1dmbAhO-T1H-2O{&-+=BJCJhGuG-5_04 zGqR%q2UY$Dtb(*o69YJr!?Vmk+qwXlS4GT%HHquD%46CtOVd7I*;5i-yZ$05Z7ES1 zwX%l>?QbnWY&sb}oBWuK^^g@bo`DSdAcEWHYvu!dhqy@h8b zX}o0~(1_OOR(sp%IrqDWB zV^2rgG|*ZGedW@Vnw%&4eZB!Lr{kUk*}xTG9L)hk6jdpj zBF&O58FOaapzez`)RRaT6`z%;Di&3OXNm?67j|l)y{epG@y#I0 zq%RDKrxRM2Ssl7%(~@klsoT4$1-A11Q&Ojf{QnaAzZUwx5&9QH z|Gk<)-^}2kZ%J@Mh^-51Q*2^^MY=J~B7G0xTF%%Ci}cGh!DxzC!LvF=FpKUSu!06P z24Su#&7NMKQ5Fu2U@$)&L_><#TXmw{tm}n^-n-tc6N6N&rA9~FQmv6?#11?RN`Xpk zFzCD0_ata=BvZfd9in0ZQ*y*dEQ*8>{z(|R_ie56FvT(AF+a+LRY4T2BI=`I zjr3gfc{E&?hiI565P2h-8PO}$m=hF8CF`bQHXV7>oQ5Y(1UBg&m%^JM%Mg{a!)9YU zQ9R`an{GRl1!u`7{&P^?jZ~Yfm?JvAp8vp{{o~KPV5{eaJC>1^V}nb0b}U(k#lWSL zs(R4#NG%y4G#I%Yc(w*lcw#i)ds4VFp4cY5E9iS8NCb3Hk%PvY12rMlKtyz6H}(is z#cdH=iH%ovptRrT6v|89(bBvgbQ@U2z?#RS>Qd#=v?lq7vq5cxchLeP^1?7~1a21$ zTo(RLn9EIyJ}Et3)$jbR>Zn=aCT5?132$-9X&k7Vhh2C@;*3OW+yXJ2_k#?-)J)18 z7dp79_V2)qgv7N{7Kdx;LtvZglYyQAi7$bHH4N0CY|{XoIApH|eJ>6o-ehLM41{%H z2-4<2dpHOSb{x_(UL#tziuI# z_E9Ufm)L?Hl9&LIsr>mJOw3Sb`!<1)Sl57nE zh`xl`1c!&s$GsU!)`bfwLC?>G3B%*gb9+m3ei9^npf-i%QoFq_G%8#-g*(O_^G;P- z+mCw<%E_)ch&9SduH#<4a*FE%uaWL(3^P==tHGr!rj-gP#+Qi>mI}!4QFI>n<|?!7 zP}HdGa+isirRo3;A5sDVzrYcz@5 z9XPM7*HQLOBhu~YEE6fVOk~&#o-&bT{{{al_MGR~ZDc?G<8kjZ%3SDcjWQelA5*5g zGkYC;n%}-vD(ltopL>pbvz010>0qJ6Orl)+t}9P}3U;3NS_#Cd+{5NFaVz^VlpC#V z50x{CYc@gWYwO|NJ^*f$Qo@(l11Ku>#j! zPFDK2_82U#p9l@%9&-qMBZ1EBE(bhXjXrx*UQzp9$xVTQduPpWR zM!f4=53YM8_1_*e>Y_(2s+8(hT;TB#JTSt}Ql<`1(!s%X2k?=~{onCHa2M%rD%{V};N|13YJoyUdMwK1@`*R(tA84wX^iNH#k-1{xF3!zyK}S3r#e8^7Pj| zws#Oa55j{G(8*vBnpA1HysXq#GUIwtMZZX5sDZ}l`N@~4ai9tdC++MleV_!Gw+paa z9)U@io?A)d~0ir6q`aQ#@^Duhb9TT@whKN1ON(Zo%9&AZV%4; z&}$Em_@>e2InUuy!+_Ah)|&L9q%o3tig!0~vQE|;EQD@Dke8PDe*Db*ZnuIS+X{|( z+$orf!d9e@FHS9n70rH8g58sg_g*DnCc)~4(U0zR;VHLZlP^`Wy_zKy?4>H@)9xd; zH7ggnVO!e6$e!%GMq!i*WMknfXwo36BIFlLW-B}|>Mp`*{vCm2*yoHZt$9WlrhylB z0I+Ph-VCSKq`m{)EDHjsM9Q3z7zYxY90ox5v63{vfa8|aQG8291sWr|C`tt?HG>!( zPI8i9;=#r2BS+K+=HeJBF~^u~68Af@drwwmi>kXtSWrJSIFdvR`nV%z$E`ySUs6wF zX>onGECQ_4fxVsQfe0Zx!JHaAeXgvkCDd`{Yc6=ZGO|_OIIr>Zgq<1_&7K$R?-(5!?MfU!wjYEm#@*{jFBAt5;$%==^(<(gmr+Fi(N?jlZSNS zzuSeQ@nmDKCsQ0A5e~YLAzaa}1cEDSw2NSBxreGtUVFbG+)dSyW6i=R@rvCTrU^8C zYx}?Y)e0z226SK-Al<6cUm998@N^QS3TAbihsbAG^!(UnbH=bi$vB$z) z;O4{s1D>Q_Mmxcc76> zXDK(&bHvu-7Gp*@-=YIvSLCRN4asGp?Czh z_}3)ZOfoMe)AMny^R#P2b$=n9(@8)hFT0X}w9C9WlyA^#w9xJ&>egIsm&ZQT6(J{k zOTYKPYA=ZTK*P=QZ@Tq}f0Lx=V?d@Mo9Hg=Q-KfoHIq|@v_hyg_qtRW+l$sIxUJl9 zE~Qo9i&n!<4@==LB@}{xn2s|5>-JP%SoU%56nKqo<-#r+^FJ(+1HZ$z9xS<$eAWn7 zSLtQq1BYGX^Sz!2@_z?@>xEPD3nZ+{P!eW=Y`&gzvJSo7x1Da&`=R6VQtO#!)IJ?j+)W*MUMt#tQSv~UwW zYy3?S@#al~FkyD`u(v_`^>)L|8>$FKyd^A}9XsshOS8Cz9NJqBWByjCnVm4@Gif8Y zgS+a9zuP{vy@~qVI}PiF=sDWTqY}y#FMu5iOqJlUQ><#*ZjR-!Tb-n8Nm&chTFxD}!oyCDgC=T4lT1Fm?alp0odx5r$S z?`#OcN3~(?ppQt4Fw!jSMq>5}9E!J}s4gYa*0hlS0204GQP`xM&T!dlW5fYvnEMNb zq78}VLhk)(;1V$X{$%QRNqFr3{ClgL!luc<&queG$|ent3Fy~igUn65LtCy@gE;f* z38LuvQb}9@W2WgrAV_r)A9UFyVetOpkB0X#Vml~fzyc`#EHUD{AZ;;XBKY(X8G{l3 z*&H%+Aqrf-DYgObI7C(;y{ajWnBUL4fo~i z>ustQVeJDc_RErL(~Au#N>~ zjD6gQY7EUR=o{rE+E`>jqG2P_fa`Qnwo?Y|#Vru98F6BttWG;gWw_Rk4+20UYOR`w zSUUs{gx?QFk^#_4T# z@X2KaK&uJE`H|cV8r<6CwXxMjw_<2Yt2l&4eJrJbynJeq1LY_NkkryySk{b~DPf~Y zoLj?;J?F^>p!N)su|HE24{9ir_*9J{5js=tFr!=5HK3%hqg#*HTn0bW`P>KQIQQ33 zV;2kqPUl56>CNVl?kN>6NMwk#ETi}%bG)0NhoxtF2x`Hl3oN5c24Q|dwQ}-SX^m_z zy^pHJKoN2NKRs}40(S;(r=ZlJ#f~6IIEI~OlPCx9+Cw;77{ZyM24#%lMt7pz3GP)X z<6VmISJNwI@}D>F;UWb4g7lQUX>iIr0bGw82Cr3t#EbKuH8EKojkAQ-1@U&pA;oJ! zU&bJTPDOWLB|fz;1Qk0^dB`?64LfQrkh7zZJ_h0YI0&&2;62%GE_haa2(m}S2yUr{ z5`w;;LD_Ng*4GYT+asvD6TsFJDlfVfbyO(-8ssDKn1iZQLr;tB!TFqGC($~}Qvx(qt1yW#J6Hp{^@4*myZt|{HV=@2nP~e}vd}(&8qc_BF*Eqb zGPJ)RD&U}3h6>a|fyZ2m_v19Qm=ct6j8?u=4y*Omfh>-!+TElyD6;2WT?);ufYP%& zzHCg*ozYI3e-@stuF76lH7#}zZUT4Xvyi$vIMP~IGSxlOy4QTK`?9pBfs`oeiinuc zfsMsII8@=s!FeT9dtd$pR%$F+sYB~@!N8?ohxX$10nxcSWtf|+WW^y$JCt8BKmd7f zU|8sQCmSf4PBw%AX#_)%SU*Vq-yQsm`HJf-a2GKJ|7|&U0JKFy4{7m3!qkW2hc)+M-7v2LYv9QFi?HY+t^I@MwXl*>t<_CK{cLTZ!3{pS zTn;@x1^%XmN7Us6>}tR92rVXoSB(Xf`jnW~N2kVi#7wW^3;@$>;N+;~cuwDYY_&x+ z(v$$+WCM?ZIxG|J!@TG>ax9>v8sK`Yxw7}Cv9jqMu=9Qz+nxeP^-^%HS`W*5Jpi%+ zVo?1|)9_gQN*M95mP+UoOb_Sdd|~y&6Oz7zea3KU7nYg_eRY0@;9#t}lNLt=g|8mg z40|f@lgA3~zG|p_N9cKYe5`KBcSv8^+wlZdPJv4zFHC-<9@hvzJyMD13wbsReolDO z_BsBiFn-ZY{IReNMB_6;+oDB=$NDgkd+MU5iV|P-A2wfe(+y$^;R-hKQCvLtU=`y{ zWleyLB4N>D12~btxLB*T`ODxbg$H1XprpQ1|cN&TP zrMiV^`H(gVe5+*=0VxFxb4bFF(jd4v5G1J_NZknnsu9)_1_6t|w^lc80);r405zyG zvA88jco6w{P)=5pXCVj-5BR&(FV}EdVJ<)0sA{rQ#ljR&E~FRCz_)<6;btD?Fqgi6 zkj|l9Nf2;>*AouPbA<+U(EsG`!Lx*6RnOv=gl$zNDL)MmnL+L<;ts&-ng~Y$SQ&#M zM~NEYMpa5Q(nr*oR+jUpwtnXTBUzPNP&`(IrwHYb>4)w7j9h_o@Il{>&m`eYaw7ZH zpI-oV@Av&e?PCwxiOUVcfrH)u%VinlT@Pz4;LG*zksbneWSMJ^v~UK>UF2rGd&161 zd%$IOn(GN3X$!Wg_(pKPRu>=b%h!C+O^0835f>0iwXRVx9|A#J_tJ}vF_1R6^)Dqu zEO$dm6}Ia@s+xerQkV_5H^4>x*z=oy2*Im*+N8 zlI&zsBQE%POI;)BZm5GFJRg*Fw844 zo9Z7FK3bisyD>;|GK0UtHNqQi3-B#uBg_ZZ;_~2TK-bS6;oq4_f^D_RE(`wQCgqSG zQV}j+gzHLM8i)tCVE~$DaIa29Yn9KH5dci@~L$<43 zVr)hpYHz2B_xF||@9!h~M~-(>!RJ%$?`od*R??Qyb4dWS(>Ig`<5Vt8soz<7?)FoAJfBrSt}z z_mzk7z5u&2FR(|NtI6ZaI6QGPq_EEC_)1ba@>jve*ThuqEJd07U1#9d%`k2=&*Cbf zI$^j_{iK{3@OAlxXP!)%`ABPZOOf;Ba`OwDUKk=;*cJ56X{|0TguV7)mFZSk!9MV7 z=yJqdG~H5!((gK)x6Qy~opun9@O|bSm-BXweV%KjsFpn|RIZAjs7g5aD9Ts?I({Vn z>X;)vJT=xwZ{~+_4oaeyXnuvDcR)_SY4N9S<}to@2Qrt_r|| ztAT!D`-;){6QOxUjs2ItzlOxLs=*^3uv^I*Jfs>qLzLWZi8(oQ-K*=Sb>STMIu|$r z?3U=ATo)d>b8YlmQ&-sNc4_U5Xwk+f{VxsL-LpaM{Zg-dk_S?MPAej0#$ z6-lK5x&72rleHvN0~sFq-x{+^=0cU(V5m;12If9zrhC>}%|tqTIw+|qF^Jn7*v3XK7H^d!YKWYf5zbx_<8I>lt%Df;4$1@f+7@ zRM~5`q*lBDDdL64>Q76y11jxiX{oWYclhef5`BQ_X2X~Kg}J?bwH>xg1J5m4V!qS4 zhWtYSC`>26;Ju|pD zkUH;Ia0h@BI|tlXKZIW(7@M{s`OaDgI6{0LD3vl$bu*q^zjnV_cA*fU zeJ`+59FD>}AAp>G-+_Q&T9-0+Z;J$5dCOWnS#j3J_xrZNQA8XF{Jvk09Y)n7m+M^x}wTUQs#lJpl=<)!4){sHBbZp?+DIyx%h42^19jh z8KK~r=;y98EyeTg4+ou z-&Bq$q?$n@Qe5cw(fx>LGQr@R+2b;q3&G&~xXn;QcP4EEOK5&l4bk3g1!kP6hyFSk zt}UatVM8PsVCfoQxC<;cBz8hm#3sywd&R{Q!i{G&z?lwPKOQd?O4dI>{oW_Mv3?`= z3fkvhgICSZ>9Iw)^xQ)@OPI7lOV#^@hc~Q;8AH{BCLL-Cg8gb!1eifsn>jifF@;&~WDzukAK4{pfP zj1l2`h{&eaAz~amnu$O zw=>HwfQRERutj8msY19L5cD-eMUX*Z1j|7)L>l_ze(VfTTz(M3OZ_%nP!Bc#9w4q` zGA;lY;Yi&&s2dJ-gK#T^NqwvJFed1fg;sAJ2jcGgTOXM6 z4a~~T#sf~u9tn5t@>K!fy94CDECR7HA29Ne^p+hY0k~sCWOd0G-9mC#iWGwD*aw9v z+h*C%`_szt*gxB%_%EeMM{08>EYe{EIh{sm0O@z}3)Q$Sn$K&lH^*I!=ChiANs2AM z0Xp$;PV{W$>EfYOR7Dmnk~w}=C!y^zoxAu~&Gp@we!H7y-s)!XF56AFteh;Qd;K5T zhQx)?bv!}2T?Pv1C{QX}owa-hheqOwwcyPb>#PH#F}hUULLmC3Uk~@?YWW&Iytvk8 z;W^t$Fr{|G2`5b3elNaH*tR_@neh{;81J3H)pxVhPV@HGlSxQpDn{aU;mr2D=q~sK zN$|!*D>zMC+L79iR62uKi5ftnwpsk zYk*&FldqF}$NI_V2*BZnD1|l^@bycHv8KRvUSf<$n_33jm<32WPpU6VYfmOu6m?%& zh4eQ9Q5cCofOw6$gbKoBU4Ua(ZrAn!fiVFHfA8BPJ*YzZw5sb;3Iv z%KgeUM|u!ISOOrN^vGd)`+W6*tFYt4<-fx}Ex!?3>Ql{1WP%X31I*Ch)=nY>e^f|g zLOik93Z;g%vgPnG65Rru}QKHsX~ZK3joczX>{O(myoCRYWe%78E9L`-wQ_myAWN!|55 z`v6qBM;&j0ixN<7{{s^H(cF^AcIGTxRs!(`+|;FeArAP~gUcAS@$v%_lOpd9kI;%3 zcK}9LC0$Th`Dw%hgS}r0cXTLNF#gYJWqHtI*^56kKk=if{_WYr4nar!cJ)?lPTVXK{DS}F% zv4Bqp%A$ZT!T&e&UNGRY)C5>XK40SCF3+Ko;b-50by>n4_GE*P(MRx!k??MsS{-ut z%(tz!{Q*iW0mXR2b1!$oV+Oq*29HRK?W~8i+|{QIVe1LFf{8Mx4)1;R@C1%@lit$8VVoW+7PR=C+l7DshcF{ryJ9`4mxe@$S^t^}wO zMTJHU7^X|QF|5)Hej|L^p;~aiG#~C|8eY!L7&o8*XGawrCjs9MpgJ}u23I=v5PZ-| zqHD7__E5m57oL0BO8wd=eEV_=_0K-x+RL-3k3cZnIRkGJUflUHs7@yBDhb=N3$b${ zY!bHZN|t>YO1-~pMf7s`f`uOx6AY(v;(Y<%RAJQa=kSZdJG-+KYr!in;42r}c59QD z9z#0Qt@vmpK5|TKdY<3XKs?rl^JvU$AzB!NvxOpI<~$@8NS8g6s*u6$S_uC?xbO$2 zTahz~6&Yoo?P!7Xrocfi`m*RdPt?(;n-m}8_ulur!W)5l>r%&A;%{CxJNsp@_+J&a;r;cnU{21z`>zNh<+t2>81a+ zDvtc0($%HHyjRNXFL30-#wN#ha{^a-zR|z&mf86QDBjZjNZe(5&1CArk$X&)T?u9S z$iD@oJ8Ays2id^z&n;cpA`e7)_nE`a2h?(J(C82oYxbEDV5M?#*mY8l)_8O}2-eOai-1K&L6oW>NaGoB~ zB@cEs+`MiM{+j@WvS+xzO9n9R0{|pE@8nnX^9yxdYs+t?PYAN~k?6GbtstV3{TzJ{Ta%Vj@?nO@x*X((ed(va%Dm))~ zsmKY%v33tx9qDjn6Mjhn=4(}xQNvD?e0lvqd6uMU^l&5@`lo6nUnbmIqbu}qQvkTV zRtJ2ajC{8YZry9(+W~!Y@IZN{x`Ur*LE@WzNc;zUT?AaY#inM|+HhCOIRo#T`Vf?_ zg@2L{YOQVHdmTycr~*kPw*h9sWz#VDt{?dt8(Xe}&)n&HRiW>T{rCH91X%JhHS!^~ zKR%+yHUYpOI2iq)LkJz6V1++U&f3PnP>$+9>;LhU%V!)L5WW8}kL%FI2jmAzn# z1}s=oqYQ)>R%ndBQG z)YPVd{PtFDnz}FGfOGZpMmbzUh5Hx2+s9>4;h1(y~I!b^Q@QZ&mRQW0N|8Mw8#U0-cxOFv_zvFv;Alv%7xyX&u$y>+3 zC^%ck+U|f|Fr$oo7)-{cLo5&I!4eqd&VZW)I{1P>nENJJ5asQai(t{9Q6-j-%!REv zoDr7UD^O)#^8?O+uW^7h`M^MoH3!yr0W>;u0Bd8*0=~%ulr{$92?Ild=I;XmU)_KN z*1oM{@u)96TVXn9n9w{2U`9AsmuaU#3Ycf1ts2p8A~W6&E0SD~oJpwOC7u z43%hOw0C@&EhL|CTEv8d%kKEnV8xSXq{CXejBUE(8$LjVK6?i@>*2kcv~{;^*ni4W zp}M#Q#f2&}nM21>Y&#j(>%z;gCmCQ+F9IuA*h1V&0-pBw5K92ZV1I)z^0-5Hi9xcy z<9j72oO?Yxv6kOx4sVAKLB?z}%g@UycJVdl7r=0-5)$_7;UgcD_GjRFVbT6H<>w&a zF(Fa!UAP+J5?ps3eFnyJ~6Zid{Y$Yk6a;JRN4YMeJM zL{>#Q;pkh(W?ffS%KpcKIKMbBp`G~vEk$2-^q4>yW z2Z!Uwva%7|0%1RV8>0ro=b4C&hG2lO48rH|ZWYAqAT-?#U>jo>)-=;5J(C7Zk(}tOvY*yyb-+#TB<>8w__;32h#r#cD=U{ RK3sD1y{Ygis@y~0{U5gs*@yrD diff --git a/boards/hkust/nxt-v1/extras/hkust_nxt-v1_bootloader.bin b/boards/hkust/nxt-v1/extras/hkust_nxt-v1_bootloader.bin index 1456ce1ab847b66f9330a5df2b0e1dfecfef3e6d..a940993d6c7791a3109bf0a1009b5d11123cd59c 100755 GIT binary patch delta 22104 zcmagG30xD$9ymU;yGfSIghLI7u*re~0S(}RwQ5LUxwLq-^{5&}`+~MlthTk)nxM8t z?O|Qpr_#e}4_j>&lvcC|R(rSaB`WWs=#$pgC|J7@G)n^H|D9mpd%yqj`RDVQ%hMJhFA>`)gFUe{vFKvLsl=!_y+l*H%+*auk90_St2eeZ?*EZ9 zq!>wS{YX;xAgS1gq`&kub(Ou^)V1Q(GO3+ECvO|2moRl2;&bwjd+8mc{)9o&@m?fh zDED12YRVssl36=O$qWR9P;&Tw#4an@aQLi@M)Tbc-qP*J`4ZBPmSPdtAOq@ZbdcE8 z^|`}ZdQR3R>$@u#>m@a1mRM+1n|w}AfOqYS&5{Y86aM?$?N~hU3}vKBfG7C`-p>8c z3odzT$!R$?c?$d+ga5h7)E$(4S~evY!@CS9fRfG9{u!qsCh2Y1-$LR@i0_9kq2%p| zya`V=OG;=WJQcc`YVJ0fp}Ams8{==u0!SwHHAtPa%iYOk(&0R_L;-krvI`n90}4+C z8`Gw42cV1+y)M#vPS!wIRnT`DAT`MxRH8|yq+Cjy-s3ta&w`PgW|+GXbZ!=OZZ>&- z0-m2Z4e4|8G=dqkx!VEx)Bb$c+u=p_zzZlK0f0mRNP%F5QBXk?sgOEcSx6?PhMs(9 z(ji=fCya5UCS;;!%cEXHQ6>|bK+&pE6vowT6G9xCp{Y-sf;g-{52Y*;rq4i}QhHiu zb!TJ^lUxe#lcVh>i=+u==}OPY8KVg>nR^0!Mz%6YdR7j2@AjXUTcHwEK2T9Bz+Hm; zOAw!j_&mhzknfmjk=}vY+Tr;+yuS|dO^9zoEI}+m{42!2Lfj2;_vkoHWwG3zc0!a@Xn_i2@|L#WVe>j1HSE)*XhI280!;LbpIbm$8sNkD+xABY0LSzyj zP$qDyViy3B%u^5}9a9?XI9In3sttHQ04$3yC_kG(mKf5*WWnN!$%Ki4iHphnb8%G` zj;jxy8ZH=YVGRjFniX$D(j7U?hIb-qi?~*$;|7-KXjqnn97jVf)lf?%P*Zg#8M63= z>ZqNqCtzH0nG`V2v(b{8o|`~>a`{C$H7HMJ!nT_IE&`z~hM62zCONWzvWLOqg1`-% ziK9zskJUooSz`JONU} z3&qBUPc_-7`lQk zjkET+LsvvvOIFB0)}+0_%`dmle@^igiH|ggq*8iKC}KGXY(17f_hT3YBV&%OM-r0B z|3<%9RJ1YG6jXIbo8Omah17O7TZFA?JYvE5#csu@vIFd;?)x zy4u6=Io2E-HWXYo+8l_MY74 z3h{J!w0&=1LTOknlCu5r5UZp{e_Zg{5x~-$Jy_b{S4gkR3?EWts3heS&;ulmmzBZz zkc_2Ky}j-n+dNbUxYGjejzZ{u7qO8Mh}A&)41^yc9EQ*g;UI*R7{pqhN31I}flMkO z+&f2H7!j+0EuJ-r&qX9D#t%a5H1XYt5%@vzy9l0&RExJFCXs05Adar?pC?Wqv;xp3N&15xU3<1LJqU3L-ru@-U^y~)oLRv)g`!J6EMQS!0 z%g7X{`_1}2)JWiQ&E2}UWFt36pt<3zDL5h?T@8dZ{_0jlYHHp2!fW(Yb=Ma}&nW%RNe=tYZ_4QuCdtlMUVP zVc8=BGqG7ldy1gLi~NjmIKNoHqo={sSpTg2R`H!kZJhQ&8CZ!_r<0ZhKQ^viuFQYi zJmf4MoiDl~hbHIvs|37@6GA*Vgoc$dCEw{@AxN*tavyuGl{ULr7H7xCyen!{^>*$DIk;q&G zl90aZPZcT~8Ba1gYE?=<`8WZk(9&1pA5oJdK7l7%Iz>oF+9^(mPGTn=zYcW*buW%K zM=X>%*x(KZNcMcOHhLJ&7yl8RhjYZpn6$xz`W}0X&}nz?uNKBc??`S4cw@w}m{?pO zR>bi5j`(uSgou{|Ogkqe+dOVcdQEJJNy9V5Kui{XOUxQPn4zR=0kLFo!o*2|X$_2L zmLe6J$_?Z;z}BCA=0+r!+lZu3d*LLL4)jXy+obT-0d?$NsZVv76L&)A{pO#rC{zwDRYTc`&Sx#WL;8vMqgznznnVaC4s#Y9H+1 z<0eO?qEu6#U<-J^BU36x^)z1Bm;&Cj#|cre^;9Y5;vu)BXW-dk`@@H$Z! zI~ji`E{aW4f7thX-SaS7P5@LltrK^}#^ZxxeXK6Jst=E5$Ao2cxDclx3v%N+@kZ=0 zyiZicjf)r#)NicCz^7BvV6ikV$%sxQ8K?zS5lx?N##K6;!1@2x(R z`n&6zd%Q3k7T0BQ)UYx3_CAI1d;`jGIyoWKqror?KUsRa1K+rjegN|CeZRZUHxP~j z7@jaBBEnT{c;d6I(7O%5Rd7JW34T<=2m|CYt(MfJf{obYTWVcp+h;vuyJ~&MJq=JW zt0$(I5t?gBZBUDO^FTG5p&I0wMsY&S=$~#No|4Y{(C*OU9cEn9?HZ^y$kK>VsCuAG zHKbVKlsF-ALjFX5vh6l3(g{>kSL{!k zTd~TAIr^}%Q4Iwj_nB_v=nA3iZg}M zeu2}a2q@w_G~}bBI!p5>NfEp+OkLPpixMwbsV{4g7^@`j!`D*6LFL-1-~gi zsGA@5S0~eL%7OQjmy3+H{#a25x>)o`8V8D%9n0BrPn*O;|el1q%ZCA16QgH?ZF* zw?1@AicKjk5~n9mp!|K}E6F37e(!R>*ql6;QAjNT(U&}yI<-~IPT2z)?LP6JDPwV~ z7%_ZA2xmR7j}`j8e-kGTABFAW+Y;3+d_h_)S|Do=4kV!#x&uEo4&Js6|hG+DuXyBQ?Q?tS+=<=f(Sj(F1>D1R~}8T zCPEPGUmHLq;|4@B2UJBwGPcMmGr4)SyhPE>kQ$JC3A_c~+#%zKdWiT`+5ij}ho!O} znEP5SoPT}Z@B85l0gzh%BQHra?od zB6Y)IXv#Y|49ZKoM;_gy0D5u_2f81I{}C{=>4NMit%fx#>>AZjB6WCll}MXXiB zD@vjlDM}+NzEk2BJi+Ipxjyf*6Qq4p1dU7*hZH5sQq7{sip~E6G3Nx-A!d#oHsqH8 zUlHGs+Zgcv6zGAigB({s^@-Mz8AB@TE$bQK-^%-2==GC|=izy?hcTmDwr?IH#$;=X za!Tm+b1>CuiPqX2s@|5ZvwyE6NZvY)TkpUDuNdIg8;Y?W$S`+ z-v|(91tzAE@Ok!OQ(FL!mTt7_D~L%tUgdAmuMg#h7T>L#foIOTQuizc5${;uQ1)%|;WtPx0V2P{; zwiN!Pdd2#rvd3}f99lw_?MJ?@o|QN{|ET|Nx3E6iLIgfb#~BMAIrIUx$YJmN<8Ux-V z0Y+cGZgH0?x_tEj*LU(H(nrD!+-j2R2UVzmdKNT}v85&W?Cj2j?R9mX`_!Qqhm>IctUQ|C zYNBB+kIwzZJxu6y=WI?FvVfD0%@24V6sH^cAqQK_*UwdcbpEq@7}5rND=x^IYhM~L z3SGc7AL{FX^Fxh*j|URm92i}KIC2u61=MFx;bBR938{d0M1Q+YTT9z?LYr-8VLzYo zKxP?A0a+llOiBp3x|)A7#IGna3g3VTMkWd3y?9K(JFI`F{ESiQIfH^zCrzQbaS3Cq z?eH?-RYT^)ELA2Cud5+-*)_P7h!;pVxQJ*(%Onii#e~!_P;14c!m0rsDN5CM_b-N3 zlWNlQTlntEa$aI+egnnxPXxSUdrh$JRYd`>AI>YOFyK8v_F$k2X9P+%4g&rgaL_$y z5lYUjkDAH||6fEJUQ9?7bcPln;b=ml5j_MJaiFye5+<1*7N&g1jvO*$tS@v#eu4vXf}eV3IaC(4Fm1u8;&wj<(18NQ&`TQNa6X z-wr^?imuc2CWv2urtVCcmNlxoF9%RyY~YU|2jLR`|!aAC-qz z9+hM5nxk?&r}n+rze66<%+?L5`@$2h9^R_H&9bxQ3<))*j797f2xB0O8#fTQKpdMp z5OfevhR`@>AWQ@}Zk?cFTBvl&m8e85Lyz$5h}xB3&97@y4QbgSuQ8?yFTv(AclJV} z9-cdm^q$~qQ*hE#1Ai6>c)#pL{Cn~OBTQ8lEhW*|knW@m;Z9^Y??P#3UCmu6y1C1Q z-hJBCVL{fX2e)I%PAd&xwVv)gO{>NDvAms(`E*~c`!7#_`1D;j>D-4cDE)mGsgE)Y zb)ixA?(#!W4k=S7-(7I1xw9D!QkHc%(3B>t5%6Eh!GakX`CYoO@xreW-RN3#WJ%rNj-D?gF)ExzNPaN+WsCst!Tsfy4jfH%$BCu-EzzcsT1)qaRs06KyAA3HJM_~v-MTWU zRe9*&@Jt_C0Gy(|JMbxn{`Y=*@|u3#bjbC7N?Po;e>%{l^y!~O)Zc?r?cFy&)olsX zsY*gkNwwx~>IwaZU#@{g;0fU1@9lejDG=~N0KzVN{_qv~a9x`mV``JN99T7SfIwIA zrWg}1-6-d~+j+kGxmARCe~@E99zEblq17z_YqPh(cAjV&8*Y*gI^acaK)16bJ{)X0 z(p!#4>8O@Bz?z|*4fdPV!KRPv@OG4Lk}|5`9YAg?si`B7QB^1->f+WCtb1uH*}YPQ zKXwi}HQrgo|FTFj+o9fh%TWSWD?%B4DJJFAtj zIter>6H11{mR>AV#^vkGu!JPqYKV5V$fI?0PrMF|EQZFOhnS?JB?c>80q^I&<-oM-Z>;J7&hojgYL^J)G~mRU$3!*W3$8gK+XknMj#DHdT>r$k-x11 z^=8Nw`OLffL1%$$T2+s?EH5eRD2_iXYjWZIwPF1{Ikb}Uh1||IQ`@yoa9q$yrlCOL zw3zFpY8Lu7-%ijC@1T|QOR=At4rUb_=B-(!awy;zr9TkF@HB%xB8Z&1{?}oL{1dGa z|3Pc|y4QeRol>--t03yYI$(#jfRRBfx@b^DR^q&lL6N{1YtvUBSbd+0YGHX&y9hW*!Kr?NVQXE2cW+Md^Y1{;xqZL62#jfUFg>#&}1Ov_iler@?WN-w+jG4?y> zJ_##dPWXoU;J~Fw@fAJoB9O_;3IBV?MV&Y)ZRT zC(t1G?krS*P=NTW)>Ke+JjwNXwfz{hTLJGY;@bPu@Cfn!`!k1~?*rk_#8op6K;{+V>=<6ZAqKyc<>;03%u;`)(cBzCs{` zfwdUoREUcpE`rzwu?^yCh^ryq5AlA8zlHeQu(EE46}TMWePSSthL8Y3n;P(TfSI#Z zUcS!01ZI8tY9f^U*)uZgS4-sjvvPPYFQHXHgsZ-UGfSU_9%hq@-n63T#FIQ7fB7L}@ib=>> zuq1XVBhr)7aiutNQm(zcm|$^t0Hx9w2L#^HO$(@#r4WP&kB)~4#4k5JnFlo%aQ824tnV!~G*3Z&vg|hCwKo`S=U*qUId!Op{X7-7*@wspp%(lFt!!9V1QfqttM)doj{nA4-L3CrVbSU#4xy z&~?e{=7bJ6F`!bQY6@#$BvHJaH&jJM!L~m5z!86563!hDeAO7I$}?1vBB>RJ%%fU~ zb}BPaf5)NDK15i3l-t;#M?t>K+)oN7 zgZ@WuOaalwC}hC%l)xA6DDEeBg79~DbUitE-w6}H!CVCmc)@>8J4|i9_|_&pDpMF8`#s`V9|)U z__{0r!%V?RE5MQUT|Z-6VkRX&6DJCj?O%iK2T7~tGy(6X_ao`i9tFtwV8#dQW(dpy zTi@q(0Pe}MWI+%0(n+>4w;t=kK%>im`Y1x@V-U}HjA&{3nHvQ;NV;EUJnPUI*)a`C zVk$s7=Y8Pw;zBWxG zEwwiR_H<-5VLfZaRTgW&Ti5^J9*u+^RYEC7`kSl}u7Z*z3d9#yX@pvy3ebtFive$f z_7#9oL2}A&F{UWhzO@Lk8zER`A=aE2DdP#0j3*;Q4_N1EK~ulI zHZ-3Fl{q$U14TK~b3$BYNV`VHQ)n5NB2eF%;&3hyivaH?AcNm^*G&s?0?vtCgVKC1 zOrVr1T89(99Up)*KoyTYbi$b;>5q-aJt=C|iE}8?U<=x_$NnJfEKK=X zl<}V32_%==?r{Pi#D?k%g?wRh#+26M9)o(4Ga6z}eZSp#+{3FUJ3saq>9)EMLs@IP z;(;d0&*tV!4uFa`UoLZvJ8Ob`pctNKBB zt8|{s)HDEI*rr_q!9tM`)079Nav%#9X0Joo`SWqlqiTEi`a_`t)R%8p>q0!L5Oo^6 zKTT4Fr8cQ`CvH+F z-1zV63^vltZ|>7|mt}4b7OkatcY-aEyEe-Vbmkrwijev zB$Pu&Pqo=`&F+HKi=og@T(hr}WqA+=Y4NkB^p1{I3LfW>ej}jpV-OE@vK~xD=btbi zZ3@Jp5iwGTI>9wT0JXxdqQp~m__c4~T%bCzMNZ~;-+#oRRA)df^V-SG`8|eT6FB53+PMmQOI`+)B9z=iK8A37O zxkzA{UAxWWn%Dznl94^96=j8ERl?>18Wv^3#b1GwZ}0>r)2@-h8tJ#cF9>tJC8rq2 z7`Rru5|YUvG-!Zi%A_n7k2Tl`gTJ#d&rM>*_ML^KxMH`;btHjQq1a9;28MVy&Zgf! z2_wy7ueu+3AF;C_%!YuP0|972lPYATB{q@zd2qvf8Ddh7VA5clc$pdt`Z;^ZK(D?n zFxYe#W4h5oGNUm~1-hlWorPqcn6|877cVF?TfX<8&`jOHoEvq=Jt69pO9M{~bUV~z z#CzR%HzBZ+g6gIaPcB6Sk{wM(-LiZTrh2NIqU7j=orT}H+d<2Q$A0a$ljbR)$5U>D z?yMVUee4Mh{jSdC{s9&ZW+OaY2rQ`yFUy=!uTr-FX);p^B3wfLk!yJJpHyC0@Ls1% zdAIcs_ZP9Un{+4^$QN`1qpmygt4WqTEH+U7B4|h5R5~ zkQvQ9VEAEEn1j;NBu$9&qRCtgPm4P9a1!)97S^)TNl-_-rgdN%NnbkHgQ2`0w&^iF zO#H8P1Oo2>Cpbr%ghTTSl3*Wn+&=2azpbHQ2kZ*zpg^#qU1?He2-N6{gDFRn{Zj`6 zXj+yZCC6qMK`rvOBfY!1Bwf;kk_zHrX@YUm5eM?U(s{z{xP8XqkE1&o)?c@;QyD^# zy0iTUVV?r96js*JzVfZ}ixo93yyC$oQ&)2qgh*6ps@v`+V;(jz=KmeCJuF#Lh8*|I zR+CW{z&WsjzE~HMUf3F9C}_QMot7R*$%o(I{QR-+DndL=*ah$t!YxSmiyQX0MOU19 z#jGYrU31+Xcd|5u3FVV~n}XO<1hGXCY*86b_TVx%RTIDFAw#H(0@jrhEw(tDYP%i7 zYz4eqd(Zw>3}}x9q+ll?zF5Owa$g1eNO5;_aalLBswFtDDLO(c17{sj@^38vojYGJ zyLsVz;bHiH&>h$9D8nw`k=v=9wz`GxyxU4Du7grf?w)(73+f;{0ongTI+bwXov@ql zwEelAkQvd#7CEr;NktkL9(zi7w;=7({!Rw%DL4j5r74m=-hAUg|x zbeAU%`Z!gX;oEro5^SqcAeQVb{O->l-@mhP(r-pV9dzHyydhhnyU{ZVf>KZm2~9j4 zOt4x)27_1CuWO9p`=%Exz@0ta6Ow*Zm=J^txn#_KuRtMV!>Ue}z6oqN2rC;KB7vf@ zb6mE^{c!dl;6Cu>c5&wn?k|xpUB}N)D2zrOIjH^KOT8%NL@d%9g}E#5Updh_;E-|j zmMP40OXH*dMb7Zw-G^^AuYKot%krbQgtfuz(YrLfjd*}D`wMTD#6NF{j>TWS>@fZiZS9uid6?qSM+U+?! z{iY_2k^J%supDd_(6+XC;zDi#XRz&;X9)8Iw6hpS4?edZWB456GO~S_5UNK!E8`y+ z=_`4IuvNI`jvnYo8u!}onzh_56*T*Gu-i-<^3lDAZxx0u&Bqhi@ke0$z3JNL7B#c9 zA;u37YlA)Zx|lU93G2n_vvgB=(6&k!!2|wwVGYhk8L~?Ye#m6b z957o$1am{bH$Zs!(IGr-<%082C+8b$RLb-H-rM4-SwnTcJ|^+{#oKNTtc@c*#5d^y zu$V+#B&CQ<^sU%4D+|9P8XnX|e-1g_7k`3va34q^l{QNHTwM5I((osJT@|JIU5jo7 zIea6ux+OqbggT6xMoUFkEm+`s#P=S|2z{id9Rxctm-mPlAG~kgMDU9vP+B1OPPe%t zyY_Ife^d+B1-$t|msctcyO6Z#1P;chPE-~SILQ*31xbMuft$JYYB10k)^}Y!r7YnB-Zl^mRBd>SQpRCS<{cL}i*mdb z#NVI^IOG8$804&>45aDl{+u<~pl}fbY2)=uX!O_#qEq=wjlgp+ataSZ!!YM!o4Rzj zIrf6Ow8lnzP&s&x+;AjIOWgcReLU2QP5yIyXrayw%h5xsL z|69rbUz&!p6m(JnQwuKD8|WIMLZZb*?PcB1RtCKGtNn_^=G$@=0qO!F6G^wLY>7-N zx_zta%5@Ne!UjdgAV#+s6nBAsQkpoLO*U+G5qJd*SS%vvByM)3h4v=ePqz`}!BIMaX1&QEd zracjSj~Gy9!PFS{nRTte0w!C?t^*#rvnzEkoK zng_cGo>+Q{n;;n+&Y}WdV?R&{D0`Z3TdE-5g?D3EW!RqmPj{P)G(-b%95gMo)EEF> z!m!P3k|^k3tD7J%HQ3mQDwHxxFtw83I0oTIpz0r^QSzS@k21%*Rwj&d zD&KgyxWx8l!%G5)1RO2lLG##?aOkL<8>PoB8@t7lxoUg%6yWi|CS!NI0DF2OjN|OJ zCMLbDZo14HH+Bpi(d}Z!kXblj{;?G%c)#**0dIF78K#Cle~tL=J`zxFI}I*Yiv0=^ zyfwiY5QH)Z>HQfp}P(0FnA1h!2Ah4*JC)#HJv`Mu+mF7(hXMKp`+X#Wn@d zsMwb#DD9AVl@tKI_=;eG$DqJ+C#RoSJTyhQzu$YT9}4VOybjuTQUKte4#J~V4__l2 z=Oloi+4fakV&=3~(xoZzT8pZ5RZAE*^{z>_r*rC%HrvGLx?L&KrrUb{pA0p{uj(woo9hNipu$K%~AF~aJLa({cV7| z`4OmV4N%vgS2PeXC2*FMs;8h-wn+;e-Q$ZW=B%`I&=+2cYPIA<%MP1r(P?ezR!XwM zX{=~VwQ@G1|LXVZj^{R7!9(j;pwJyqZ#%?mg8Ml$g|lHv9}sUp!tvvv7)=gXBT*lQ zlyX+Btsm@7SRdh0VGfQ}t2k!9&c3OE6izIytRLu3^=q4;sq4e;%!v3L-7Utw6I)WHe+X>!2fVKnxnZ;7In0p7}ZoeAr_aWaDtL zaKZRk@RLhrgrtj0%>CXLA45riWQ5X{5MsaSo0V|Fw9G-VSqe*QEf>(ljV@5Uy&(wRNtcK?A?_2zhg(M;uw+ zj@O9lC9ya~Ok0wjR)#YFC8KQ_7fp~~+C$h}>BW7^G1!VWfl{ny+0H`JzATHImW*VN z_e`+u>kOgA<4cOl`@P{Zal2+b8Q_8lJV-FDg*1{8SaTUqf-(|JMLpoWXaogaAGqNT zz$Aj3;;jJEd)T5fX`ZGBhkwuU7Qh1SD|W>kEMSHFr+w0T?nQ!Aay>#coGrT5v~PG zKQ&d>Zv_4RBNdEC3mRE0l?QlWl#~}h%UVgESAy##FiN_8%Q-T&2s#qxa@ZQ$Ks)0g;4F_j6yB>KhzD(B@l5fmZ7qIPTv$<%_)8y=ize|-sb z)9OCavFwqk%Akw$?AqzItc|Vh^CtMkrz-W-ef{F@N)r{^FJ7w5W%|7D`$X-^ZP}B0 z^K2;1?If1deEdXqV&pQ!_N+qeyeGk-1}0#zz=A%wLO|dyJyO^Ed5~pZ)_=qemITFNHz`IOgw#Uh8YkFOBPDD2tm;;I&9rUR|Eyl?nz=?f zL193*e{>MBn*Kg-e0j+^U}lq@w87xSz>qXKGHghi(<`Q~HrrQ%DZvdYa;YlKwrvfP zy8L(DD9t3j;`q7F1Q?zkxaD@h^9v48>d3RWxJu0Z!;RCPbHS4l8=i5s%6p7E%@iol zcAB4Xp^QowDc98p`5KZk0wH|nu1Z@HEP)Kx|1I&L`5`DW%LOW|%Cqh-Kvz87HDe8T zADuoG)B=@-jm#l%+%~g# z|C0%i9&;jYXJI{LCEP2nbukjnw8}PPwLIGd%3LSreuw<IRi+iiw$s%=IKWO^p@r)kFbRc>K(2?_k!M{K0gP0w@MelX)qWT@OWa$8B$A#|1sa^=J?iWLZ98+(=*_}xi9do`*ZWJ z7p}dmk*Q{!y=eK^IxH)jW9x9v&(GJ?k!rRE8~Mp?*qoR@vI;r}9X;&i1*+s*T@ftY zl-`frcYw%pVSztVVY(fXvkN>%ZaShanQp6s>HUt{J7%~Q__c$0-0w0+jC9uCsj|;? zu8_2f=fstN9Xu&2cJHGoWd&SeM3UQa9-OzLtw-g>M$xfDUSbqiN^rFmNf+U1Hsss@ z8s8+(0mEjlDd1iHh1mSphv-B8dNFo|4!(wVUz0gnGT_$UX*F z{Y(PB5B4$+>kr6E>kqP~a;wac>xEoY#kN9}`j+!2cV2Dta`Q_YUy6zd9;4U^{9zO9 z(3c)hw)cAN13O|4*%67yL48lCk#87~mSMkas%)$*955{<>s4@}QL!KCdc4#9WfH|Q ze3?XpZzvA2+@8(-Bx@W>@uwT?M?c*N-O}ql*~bXE4REVYp{yMZ9vK6So8|Tt139SP zRLm86?A}a&ghvy;Nq)HUi|cBn{%YX=&FeJ!l20so9^y^%LL$dW8^WFCHO)|ah>L%vSyjA-aN0y$sF=#Y%$24=JJZ-~ic?x)z&N5FB z!b`9;vzIVb{oaxQxu6H|`h z4U{Vfz|A}e0Y+4x_ru;)c)Gt&0mj&y09{!hE-HM}w!P!s$P(2Z8=K zR=D*D&T&;z**nccD&DAy&IFoot}CzPDwXXt&v2!cAv{~Twes7_%0|W1 z%WmN5^ze6qoFC{8bZsVd>njLF5T-&vMU{n1j#NBdgTp=qwFI$K`n}sk^)tha@ARky zTkZR69N?j$>n)U1P-O$2xNpr{X2r!^=)J0Ug){_(wm%Fxyvj=(8>unKhpBbz=+gAms z`cVAonN0kF=znG=oTFvWE+0I*Pbo;XC^M;T2^!?&mRWfM#_N8Szw9p7vt8ZV$cY$O|$oS?O+B+(v3bcFWEi6g7OOd zLj!P)7kJoS?=!svJS@QmlIDVG8^i+XQolkd2QxI|;x~i!HHWXtg-gPq5dtwtb+OmG zpcmPg)H}|XQoEccGfIUkpZroQU)AZZ1{Rtqu1@ra7SWsWFhe-ls%h{X3*=a=Nct5j zAa-gN+&b?6LJVIArd=^}-8gI&m#%x5n(h-%uG@fbhy7FW@3)(=B--uq_^)D(T?e;P8trM+13vM( zUBG$bD2I-U^@%eaCae}k#|ZqZc)}4+MfHlUjw!fHOsPu4sbX2xP`q9IOVy(IMW7_~ zd%p$VtFmzqa85{?4HSct{oa$})vC34kGOCHj~Q{}hC)MKz-Emo`uYZ?K+@;1o6?7+ z#&FK>eIP&!(`xZHl&rAsx9x=C?-%cE(AhT&F<=>--xk$Cu1>>suaVlz_#>i*Y$kVM z+i=ZJn+bLUtRQ^gL?`0m=CE;mdoe)l?$gw+kir#kNp<9hwy~F|Ks({!uJP>=l_vwZ zdL+Hyqe!GLa?pFJ|KIL^$=WRXNP=}5c%p0bU}k$bJCO4@A6&Dg$u;Lkt>ugO#qY`a z+s@oj^5Og@@UbAx#yC+5G;0D;i|EK-{6>z+yX2md%=ne7jiav+%2OPI|1iZtcL8|Y z6B;C&-Y~ew9q^v>Gl@}c^v8HtE_6D(mq`q1Bf6f8oAr_yzG;xX9hQm$@RVDx0D#W{ z97Ig${c@1+0$vy7=0Y9=_ye_15G(sO04W0Gr@>kX+y5=p@;o@=_}h;5gd0m6uCklklwokM=PmKwP4U2XH*VswPW*XO zJeAom_HUY|Vos9v@E7sH=O;(L(}#J`n?9{+RKlg%9=M8{dGr znbsjs8>~rB#|h=2LJzafv?e|+yJy-0|3*!u&ST=l7c6kUv+4yq{NoqL;JxCw7t6y1 z@Dzs|Crf&~VFB@j7gL8k)c@awTnUH?7i8~YKe>7$`d*B|AB*bh5xN)PS}Oz0RfX^} zXg^;Dr5W5E=sW|KWv%+^!a<;o?6Nt4tM{uHGVJE zAH3HB=Rr2$;ve$QTY*`FYf?nImc1JrN$v`XLLd^sT|=?GIze2$d9;19KdBgx{;PG6 z?JGIlk=T$51X|IT(QXuS1f<_(o1w)mv9_#+z2=xpv9`2^_u`_9Z@RTYm>{{UZB+h1 zYEVfU5J{0w(@ysIsP%i9mf>#G8R+-=i zBwY9eJ+`HGw+*G>`*vG-TXby=h-TzZEoqdmM|5t{;w$2fEm@H>;KUEy9ABDwqpMH_y7cX$VQZ{i371ZKyw`h-Cc+Bi zZF_3*e%Wj5Bixkijp`d#Yq1%u8*R(2%4cNn$Ued>gM=GgW*|NG}^s3_WMQU#EBH5eSqvF+^onJ&mXRmkf z$-oR13VDfe*o;u1<<_vZ2hGTp+lWW^c&`TTx~bAo(t8lnsAI=KO+}RJ#@T(HD2x_z8s-V31-|_qv;S;c{0YHzgEH^1hSz>?`^CD`{C+2` zFkJ|>osBEa54GA2)^Ho~>v_xyjUnP1r?q?!Dbl5VK81&6<_YI&LpxRI;teY5HESf; zAHuost?9OR%yIeYR>K8<+(+62)6#7v)P*lJ3sQUR2EQ_ z*IV4bmAGew9R%ZMNGCmwS`O}}m`=AYCmk>nMNl;9fbo>u5>yMtSUMj z#@742<)T8=#Xous=}or>M}qC`m{k9wjc`&C!Vnu8^`HoB1I`dviqjtnepSE(4Aij+ z;Jo_}=RElT(TP7c-4375fo}e^!7Ayizb^KH02qZa$9t}i_t=HQZR zxR2`1>!1hiFqL&A6zRfG`sKSxzL&hLf5=sMZ&CVHo?Yh93kjVxt@H$p4k@W>m)UeX zp^BPRoHgZosg9WRK2`6O z4mzCksk*UG*_B}FAs8!0kgoOjfRi-oN{C+@>;mf_1YMwf%G+VVZm^!feGaMGQ4Oeg z-m%|9v5WEtI@2SC40I+B`3LpC0-dpwegpDGKX&$&f@K$|+(r4O4%W2CPwjZOa}a*l z{H^eT@X)!L&iS=RI$3HFyu&_~R}UTWn361jt(9o_0A68|=~fe&Vx5ofdd-9_f8y-O z02aoEg?chuRp&6&`Ad45g&W|(E~U6p@G4$wrN(m$wc z>pcVmP2>(ayVV?Xfts`^|GPM$0|~kAk;Eg*trV_a(+cvn(t?l9Hgr<#lFsl!ICr00 z0N-d%*a170%k31_x~U0^^0VDWA;e9H#BO$j>a&TcP&M^xE@X=A-PH@bPI(dsj=Q5} z@Alr|oa}uSI3@CY2EK^~JYDc3Z16n*4oP41D8b|Z*~&KCYzvY;f{*lFfKQVUb9++* ze2?dzB=awL-_(Nu{yq2~$QQx!TWyC+SmgV50Eb;0O8P~9DX zl@6TPs8YE8`+OC?{sCQr0N>k!?;{Y*A`Nc2U{jw`e85N#XJ==EDJnUJ6 z^PSwyC(Q~M=E74Hev~uYHtgBF+cdq~%sI`sF~o@wljj6yUhtW1nwzpXF-*u8N9``q z0p(0XcV5*vWl#u^MpLmsIjL0I2|gc1vez!YwwrvCp>}tYc3!Uo4$)I}O8E8$3ryz2 zClmlNtyjFho3jHd^kn>%aO0zT;^?WC?n<~AQ#~=eGzY#z=g6h+*rVw?>u1(bqE+^q z{Uf31(DoPba;Z3X#!$)oyD%Q&A?s`iaNuH)1wG*ofF1qW@ z1NtY=NRM?)5nF%Po7+cfL;Br|z)BU&qwc{P{sT*u1Pk-`UNETxhf#DZ8Qt+-Ix_?~ zL4?AalEILKbTj1?W2{9{8VjR60Ni43BQXN{-4YA{iLN)J87~-s#OrUS$5O&BTa`Ja z72iRTRc6HnMNyUQHTbBeRy4fD!(Gs_w^Hy|;*)PBjcWkejtNS69|Zcn-}VyuaD^1b z_&^E-Ne?W*v*9x?9{?1QBf&cX-0}OpN5voBdJ>n5d2g@8Ch^GI&*0z1%y)i*?~?f6 zc^|G*x9b$8E;&4tg0Emk!)GMICz9_2_5<=6T1AxWv8pShvGQdRV*|W7MrX;tX zgNwA&Z3^2ibDYz)Y%4eiU_LduxoZOo)iHiL8T)B^hne2tPqs z3SlJ#s20tKyjmk-kHGUM5a#EAI}1FI8FS=;_o6TZ_T>3TtnX{EcG~RG<|$8Qjm#P| z()gFLS>wlM=Zwk9hWj;@A0*ocFNEeHkSfV<*u8YsBIu?KvAh+ry7Gbi%S)jviwDx9 zmMnd0)aupGqg!q|dh^>GS4Iu@>2nhSY+@xDMP`(UQ z{Low!+B}dz1&~QPU=UM2%*pz{_PqkQSO`yO~Cy{jSL*88zAzR zf$a5@JC{eZ&UyR4o^kTW<%*M5a7-3jA;j?lI9dfXK?Nu#I@xiBHgFO(cZD+Jl*toU W$n#zSCVhLLYyhx3@Nn|p6~+Lasq};Z delta 22218 zcma&O33yXg`Z#>fy*J72LX&PZU1+nk&=t}JDIk(2?d=kucHBp(tV z8ffdQe6_7_<*QK@(Y#*7bhLGD@H*G}M-CFLgGjsuHU2zkmYBp2_Z*1{gS)T}cX2FA zWid)c2&LZm0I>|*@BAHgKV;d|n854$?KYjM-=3FXomYW(<9d{d`Wo!G0c9EcUbD}t zm|YH?_SaPDMI~((S?D|rp1Z5eqLB{!Z_>RC@*1|v7&Qn0&fyOoMTI{Ch)uQ;Q0hz1^;<4%6(|?{A9SAML9G!$pQuY zjiz8ZX7GGLc__aVuK92^i4+xT%?sXPxPz7;XM#niOR$cIdOA@-nM9f*bt$osQfK;H z8ReN}WDv%==6*Cc%w`=&3icbHGWDaU608*5cbfnwbEuK~Abu!lKqta`(LN`^8cNDX zLHQ`sCENr4sK%Po1b!Di{q~Y$xE@cL??%Pcd}+ciq=st}q;yD8MkAU^(TWKa#&v8P z3NN!!^VMb4d^K!8%uBv(1pA76dcxbIsyAkf{o0 zF60+l>-l;p#6Te?yOZyJn+)h0_Q}Fz=+wj+#QUC{V#xf}N_rAzYNN?Bv-ly99 z)L&|$watC1I(a#nW&7%|Xe-h(mU#OQO`9Pr;5`f#h41BmnJ%{=z!UVq1101~|9d@= zwr9Z_iTMq6PihXG8O~+#VJ%5qh86EbVxN@3Tb-V>f#uY>cH+3>e0gtC|yq&)7IyoF%SYJtN*)DcW=6muRi~mdwSm6|~1{ zrf)AZn_vYCCci5Zpo=UI(bC!cx>y(MEDR$PX~<$`Qfij5Z0Fs)bXCY9@-HE@$GlPb?% zm*va#S2ok4X?S9}hP%&7i++E;1%JeI`S&MTDScKA7UO)Et|Lr~Lj#OH-mw$Ma;8O(b)IQUl(F!t{uESx5t7 z?-d@7NRcfVh1eNFZNxZyK=>#^Pvu4k-$&d>E)hx%?Hqnc$W^YyXM_XF6#Sd;nKDE9 zm6XoO8*5rM+^;+m*9im4<#XR2V3MbF!F!RGBe4^n!nN5!%>Z`*Tff5 zTW%C$bFO&Xw=L$5v2qe8y3`0}8aZWUUvJI!O}|>d zffh;mpLg78dP_2>V2L#7#3~AlG#YvAAzQ&Q5?x4BAu-{n_;dV&){#LNZ{hd{B-s69(w$CP zJnF}W^(*AXZ<|J+!v!;hqfv3G^?o~t_h~rRgIQW!=`SvJx>t$|(Rug}L+9Kp4F9s7@hRML5UE%s#&dNfV%vW#&L-6;%O_= zs9H%|es@hX46FZ@8cOsHGu%#Cc*p&+WTq2nNc?FyovUeOJgMk}RW6qJH5^K##ctu7 z=;@=<;E5J55?T`*g}9g$cKfMo&=)L+`(jL^R!AD)XCDVh_S3@4F=IfqIucWabA{hx zGGfDro_K-~HX8cH%oyoCsVxC-l#mr0j~^9EV)eLBsE(aF>Vp8&t>IF6kDC&Y2#(kc z{DjaIn`>(Z)>;^fQVoy_n`InM)dt6mBuxu0&}4gEz}yQoTw!ZrGs7Xz3|TrrF+VV? zh4IV_-p>gXwm_M@v)3avg{??DH3-|A_&}yI@w&q%On>yVcoP6x!6&Cb))h18t=msj2>hN zu4)SsXZl6}FKkt4ktiP&!jqElcS1%|4o(#wN_rC8gfEhEZDl?gSLQ$-t0Md9bWS}n z7e?}<|Cq_^vcfb^_A%Uik}IRe#oa&dX$_|?ASKTD--8lHD3N}*gi(gZsqP=QTEnS= zC7S+SBJSTMsB!Fnl{i332v3ihxMYi;NNhyrP{X1C{8q+t4_2h4Z*4p$p+*I8|1OE$ z&sc|7`-; zi2OGe7Q`f&r$>D|`iPWd*IkzC8u9MM4$_*28@GlM75?Sc)%+prasG<+P4_Io4?n&-|wRu7;dCgn-EBzT5R#B^0#39j{-@|=ot214Ww4bIP@Eim}u9q_jllA zg{`UlZFk^C6fBEG-t35k;WYcYTU2FaVNl|+Q$)UwR+RnHM2Y)-WJZ92zzBX3K1j)@ ztUlpltO0){jM9|H&+s9Q)%pj0skub{x*HS@@g8BNCRaDf=W`EHj$HdXUnDNn@! z%qAbw>z^f)Ja|C(T(fZYCLh+&jfPewRNUZ$jU~F8tGp9lb5ufxmnF)GU!z6OFa~a3 zZc;#*$9-4ba=1PQ>-lHc3(J63oUpd~ASE9Hc~p2(8;5@swraERUcsS_E&Rd$xMi+1 z&Wgq(@jE-}H|mk7WRKrQ6Oh3;TBfYlWKeqh(ZvQG82? z*F7Az(#iB2^P$-ECxlwvTt%_7`L=PTS?JPb*bE)-$;O|j%{XJVHO6^G7ImHx!um%c-M}eT8=zx84 zK+vUfc(YKQx`3MD6V9gQg{<|rUSo|IcFI6%EdEA_O`A$7hJ`t4;~8MX1HzWHdlT=Fd?q7<3fJa#d8|#u-7HvaT9QhkULIKy*BpvgX6*} zSqKvn-Y-;Ttbj^dNjR5L97c&_r0(VE0NEu$n;C!4R{^BkBUw=-M~HRU8-A*=`HL0u z@=WeEcsuN6fXAp?$o&w^AR%^F21pry$mkXZ02zHp99_ne$C2&_d&mPCF=-y=Llh0ld(l8$(oD(!oIA;$=?he{4=pgi~?1R zl>gsg`5&RY+R=JVf{o?-(-P1&Dnmx1vD%u$%6Sl4eiVMoijV$kFdrlc85=h&VI`7cewYY2Zx(yuV<9M*hwvDli+U3b&BcdrH!ZlWSbP>tto zYQDX16w%h&Sm>MHu%xeurq>Yt4LF+}6l~r9$zT;A!B2MRMGA0yCb*@OvSxU`17l~P z4Yt`RYLMI_uTWd#`E39_p5k-Snj!DvL8M_@RfshjN6|>7W1Hnk7NU#C^I!j0vGQOs z)TR<<8^*+a8_-uLf@l=*b_E7t`H|hgHry|aN{ScWHbm)&k|}Ee`BQ_%5a8o#hZ=Th zEV>3^mun5&sA(3QiE*|Ko$`qDp|F0s6rtxs?w4r__+qe(q>7lyw_>qbD!9ukVK_h{ z1Q}#7a*Lt@%sd{e>6~yJRD?Q6|!|WfwH)(fMQ|}=q+ZkJd^(uac zk%sYn?HoBu8DAXm{z=g0>qmdmQMGZQ{K$_d0SW?v8d3o(oSHC2*gqjj zUIVgmI47h}NTo7{g!?BX;BcXOfstaJr5HR-xyIrX&2$JvVF4--Y$BI7_K++Q8_R_9>#P){F?a=u=e%WCy&D z0SKX*&~gHTS+twMCKXLU_42cgw2|h{$?=Z?Z>JDFahmP5 z!4aDp(7gA2Kys^^scMGPwU{?9?b}3~NnO}EFZioAu7u~RXBH`L|ET4tpkM*4*Dv84(oF&FH2|bXe=l!IgX_C$ku**I6fN#3dNMYf}0)4Yzp0mFXSITTJLeDMQ>g5wQ#ILF_wlb=wy zjNu2KozY_s-y)4^kL{*K8!gW|({ZNv3>_*Qy+;r0ZROy9)&cC}gCDv7^y~-Eif+vY z6#)FU6J@^XA{|iUN4wAjTYu%TkyfVPsW?X3*^9#DGuo^Mn6MfRuqb6vHP8)jb))gN z{=#Dz>P$RFb4&Y}X#JW$+MVA2)G?H4EAL-*_7JtzUm^ZchYl z>rXjmn=t)O(y^)yH26=btm*xukLh98B$R9J36GApYAm|#(Z;`mO$&p$d(&$Drj71C zXn{J`a#g#b651U4M1*JGC-cFqWb4243C^_j_kD8ss&2z<$i4Xq>96;bxwc@3?oa+8 zw(bFxZtK7DiEg_ZAZ0ByaKM;0b3e5j*cWtj{^|%92T|1M7Xtw=Bx1YUQT~!8oKNI; zRM0&PN-|PC2>dEw6||?(5$9jDyjU@YkK$vEIpId}BRgp1+AS4{;V8>y6dUYSwDSB$ zi|uZaqfIEsD2CLMLK`X?n!u+d{%l9ts?K#4Si5d!G@s6mu$Ce3xq)lE#zFCOszV(a z+|E+1EcE=U@~?vICb61!>;)V0lVwBRPX~UMFFwD*GKQCdYH-pcS3Yo2)-OgMw*|F? zHMJvJ!t-#oPbhPJ(H9zva*CagSdzxd{p>yaxPM9os}Sf96}7KR_Z~O}h&PJH+J8!h zRqJ7rL|O$v7Skw(JR*RLUsXuw!d2o*jVO48GQcJE#&L|APdT<^0anUGjg8}N=BLZDC)Q)7n$ zpI7mb)f}-9FH18%TiI6< zS-;^TSa~T?8L_gD25WH*GWJBMzJ+)3YwFib0qn7)JA+@YIBzOLy!$MeB&dr&F@4xJo=fq)AQeI0YTt*60q;w`$=m9RKaf~^*HxWm(Osgo+4|3a zk^-y+PzA!t_g52VvRauZ76rWXeXk9~8cbT0ZgR| zQWV)%gZd84`N+HrnbR~O)?o|=u7G#1Fn3x8-X%OgEoV&9Fw&C2@)FWqvl7jO$l0WU zn&x!jZ__lkRHRKQy90W2x%9Lq`>8?i?IA6vwNh&hvWSoirF>S?5l@KZ5K`HwD(U(R^e%3$v`7K42;u-0|iahcxw$ss8;$1}G47P)J5hm0o zo{%bGKz3`A_0aA1ss#Sft&6L5{q1wkNEgTb0ExKQ$vqf^z?n+j-c2pEmgk+3x;5ng zm*D@k;Qx)_zZm@Q*9?1S2Zp^>fyqHBFQ84biuq>g#tgIcEu?GN1r=uLml(0hnjUcjpy_A!gXA%%Vt zf(qURM<-B&8m^-XVZQ`M2EIMxAIdAdGJ?DH&qfq6LN47vHe@AqLn2&}utx?G;f|`p zaI~or=|jqqfa*7y@DCKk4PXJ+Z#U5wP(98=yKlK6ejpF;ChFeN)fk0xn4`;xPj!w& zfq#>D;%5m(MHBEUVO7zy>d4~C{)11cxtiv06OeWcN8dj947mRNyG;f6Hnaq8s4SDf zurA|fIPgbE{CEJI*XcjDAmFUrj*#C zi0gyp!-1k>B~y~D7pY{uRMh6rUdnb4NGhT>`-hVTtJlGf!y^Xki9$gLDY_Tn1Rp9_FS- zwo6Y`4?1pEpD-z0#D(;~!bexN;X!Uze(t5htAltZAXQe5_*)xYi6T@#ydf zzhRBAb$!aV65KH2O-aUG0jF&gs5GqH0Ihr%ppzBQe%vt4Gg-HtFJ<*P7n!nJu>Myo z7D~&Mi~k|%x8tk`7a0kQ^qWXOSFE(?h5lv0(TIs17bgJqxKSK6A+#sRP3VA89Lt75;`;V{xDFev+d0Q7uM^o zAQ{#^ATd)h9xCawk30m6ncEo-E}w zXAE35%Bjv%9=-BD=V6b5?rI9js_alhv{+OdU*v{`xo#ueb7cAPUaplm5FuiQ7AWF*%2&f6xVEq z&etA-cTXt8;2pB5+W=I4q-oMJTDu2w`CzVnR~TO9d%DguVe(d2MnkRD7Ij++_g=3eG_+SCi<59-wXtOqN0h3+ zZ<<*A4M#P!Uab^!LeID>#jMbF_ep3DJ2jKPZi0@Wn=9@!O_wB1BNmoeaJ{;RRwf9a z&4{*TI1@dLGOJ4{$>=-{b;zixF5J*ilG+*O!3x}PIZ^4W>qA+z@Rzo%p5E0mJ;>VM=moU3^d}=4XFJPwk z;>os?rj9lxM_^Mp*CokZ+bpQA$As|d5}e8aY`v>j@M>w?V*5OT0gPYI?s{K^L?^z#n%8rlPP7>0^tNi-CmM&r7gtTJc`n zRRU)M&@+sFe7_UlcMF#FG9}xusiI)@R4bo#9lxzvxx_^lB3Xn3*C>qAfln-21x;p& zsxWz{(PV+=CA~#B#ka$s2n(BWrnJoJ!8AzPb^w+Q)tg{nn>w(+mt{ebl}MTIB*qT$ zYR&d6K=;X#6u^M}mcw3rOGWvc!g?r51qQqY$}eD;hY{-h{rU(&9tCvM_Ln`}cNV0Iq{<1aoSLG`g~? z-bVQ0$~Td?gtl2fM>cy0a-Hv%DiDtF+_t zHCmiCmV;j$$4w#~gn5{dF3_H_6KQ{PlOB9`d$2dPH}$*I#nEA*U}M?gk0ywqopA(N z)OaUB)e7OeS#dU^KCT`7@>dHWI1$EmzLd)nI5N ztXBpb-*KDib{87UbeD4T-N#J>op%z*1n7W2j_?7}oC?VF6z43-==z|SMJG$X0`Xc_ zOc>ud7jDQZ9>XpDH33$R%tOiad`#PX?b;w|{z5vZ6MzL?b|wJlmU(b6KTE68Lc5Qu z+j6wF9)O8-MVQCl(r?{B+xZcPHQXHE=39^YHcNUw3e+L8V(!8|9k%&j(>Z0(wuIVp zu1l5C{b-$ntK&vKLmND_A`t`MTpbX*n)ch3xjWS-*AK#W=)7jn^%ccerP z@(}CY-XqB7 zW<};%=-w}B;WxD2a8nWX&Tm;l(cDDayI@0mw{i9jRTv}Qk^oA28;5pwC4$D)V1_Wb zS1--s7IA2AIbh)L67m?r7mz@e-TSyu2q2cl(FFS7>g^0ouQ< zAkZ>h$VU%0-sHlT7vrhy?T>;$(MI8q^ss94p!-4xAXmpVb!nzR;_!|XdQ$qf@~ zwsT6DOjFCS_Z8vEdGV8L10i~vXuk#O?zz=dTZqzF!$XkD5R-hZ^Ojo$i>P#f#9Q4D zeT?cPC5fiBSZJGdD`ew$m#F=&Rxt+;k3cp?+a-Uq>MHA`l>C(eM@czwFd+A z8UIIb234!My3Y~tUXz5!AIJ_BrEWJ_uQw!N{{vHSw$SxJ;i?~?G;gL$@^=8zdO2tCrRr7}r36a4zMI7{XtVXLjzYCuJL{WLK% zk?N}Es2O@tDUzL$VAzpOtvAJAP+A%wfD={Gw^4q*De@d6h7K@d2iS(dKPmn!G2;86 z(lKH@1R)Z&g%SVR5_G~L3S!Wy$!sH>un4a}dR21_H%HQ|v<~u*C!5HBJ_FHCa!cac z{FXz!zJ=0&+C7k`KV((43igMRY?md~=9e2$+Nt{$++~S9R0n~j%xfoj22@D0IW%%g z2heBDabhjG=kF3bYachJ217Fo2gW&wT^MB{F>4djKwNh~wo?WI$t}?28F9*htU)_f zm36HH9|V9z)V5?kVxNU{8It>90c31X42lnB}fGoNFmbaFa(FV(SYWZX)9o_n^_VP8T5f%{{ zgBWcs*s9|Lq_&NsFS{A-`m#Il|9n{={BI}|-AQR+m6*tgPfLteu~YG3z)JX%!!$aYv;j(8|vYb6}>$ z0Fqid2ZYXu=@K>=#RqDcf*;*^0MwpgGWO?cW5FzD6rZWhiigfrJ51b^&+T6yy2|YV3kxD3G|MHnqhh{Inq2Mi9c%v)u%l5NQUk+NxogQLx&y-zu$@ z?WOlo^%(dl&ikhuwpNhfXt4tfCbZZU0JSG;r^zVF0icc`mKFuElvRt;CUE1sQO;!7 zs-#Iy#p|gRv-!_j_HbbwtD!|4v55T?*t^2HS$Jb%j4gKt2nG&-*X@GQYgM2|2Tae0iZ=q@v|$3gitfEi!h&B4D0ZH4lXYwyT8n4nvjaAf7rs@CRXj6wJ5ND}(v{((j6h( zg+rHq9a)?+heXHfq){$H+KLY;?MQyb5CPK^s`+7W%K+Am@+hzdwy_t4 z>W8(Zhg;SH@g!Snno&C2rsnDzX$Uh+ESJOhpMk*G!sF_40%(oTaGVwsAOy$^js{9h z8K9G+yP{@Rb6Eh}8-nZM=pxt9<6vq_=V|d}pMhgx+%*8<<1Ll_KNZMkcERfV304ql zBk-;P(%k?(KLb~=A9147v&c{op4|H$O{zrj*txRlOireSY`kGZ=W z)8ZK6yGOL6p7Hf zkK-4X%P8BofkSJv9K`sTgbu;kp|gQIO~k`f(@JcCNSgp5-7<*)l>|;dBw@JIAUM1L zVWk96n5qEdNk&*p_Ixb<-d5AR8Eol`s~L|POrTiY8X$6p`~sLTYsj+@08s}5Y!0o^ za9ZJEey%~)Y_5)m4U%#qyY$q(#24Zwhp@UWK&k*l zDbk148dsL{XX?JO(|lsJT2MY-gzpn(Kdukk`6=XU?R>zyL$E!rrM?{$4nDrvMrN4d zAl~oA|2y6fc{Z>{&JVuKJ<`JtD!vIq zz}3Yk2J$qAd+E?CFXMcoyEZfl;L}8U-77CQMZtZROaDqDT;(n(slqlLs9uwixI&6` zkWmf~9xh4lC<9uUJ(vr|jevIoaMQ2dzrGARQajFFx+15El4R`(O*sGOtqo12yO9pQ zcONe4?MUGM0g-HDiYL~t6cc3tq9Mzn=j0V%X^k*d=Z8lQ8xa9fd=UcDWZ}QLCq04K z!sabJTOEuui&+!HUI_-5EDZ>TH3{sG!y-hm&2AIwR%aFs4rBcmX^{aCfeKsUPBXE^ z48jOGVYC3`g&V^J=Jdc#IKOzq_1`&{hoSVWpM{yLvuv`!AMsjt>0uR-??pI6wY8B1 zl-tKr0=gU7P6(GowmYSoon)`1UvH7*25VMfn^lj6AElS62 z{#jOBOlNpI=#1M%V9CHDB~!&6d<>;M3GM_W{%W5mJu*GodZTa z<{Q8h4$>gZIrtF^0la^-3WrxcNGA{dk3c`A&3xa9veaFBfF$Y_Q9u4S8Ek<=4oI)z z-jx;tx%?FZC!ZQmEgup#KIM$637!s^@0jgidDb!Hjg|z}3LW*NUnp2%q-OYqXI2z4 zgWfj-Leq+!1(ODfc$DFGlDO!H0zuqOCAj++DC)!lu!SGR**WcU3vblEY2{(zCl3m1 zp2)`Qg#%B_q`Lir_(VGOjbBK3axC?RB$%GeOa8qYu|KUq?4>6`=m&lo%dy}IsRoGQ z45Uxk{p5K3iSXHzwYFad{wJvRRSzF`L*Tot(M_rmJypr=mYDY0>t0_sqX%cZ);S?? zVYfu@3e0^=9&w3^;i1kQ)OA`)^~PdQKG*wPgy>r z#X~8_I$J!nG8_Ie7`Q&QXY)vWdjJXV{JF^X7ueI>#7Dk41Kv&^@VXHk33$c+sP7ez z5muoQR-ql1r1W=#;;l>#oT<~PTS!-P#(tg96B@{5@H%nHzQ1(g}srSnG0_Bq#95SvW1$J3AQ&&%&z&;BNG&wEI4z0 zQergq_Pvr^Q@^Utt<9L|QjE_hZD{tCOmLYU3H(>mBbxfU52dA=hIMt)GDC;N1EXzm zBF)~?zd((oyFIF15h5Kya_gk|-6-orC)WH1`Qdl-S-3(?Th^OSO7jy;i3aiT{|H(h zJZeQ4%&U#5I&xG;2IBpYmm465qZoZ9C}+gvYrZvK^PQyHDHp!G&Yt@2dT7I-_pu>{ zD{O&-d0MzGS{NBORQuX(nLO`hig%RRrUC6C(c}s`>PqO^ME4*FSLfdfEdY zUsIw_A(89b*JxDPZ!#xWyaab7qL9^}m8|01@ zZd%W1EHxo|wq{4oS2Z=QAv1q*hs^vLQn&l&VsOq$I0?dUs3$Iyb%S7^Xv+uJ-g}VJ zA>}|qWi_S6#~*mM0f!w0+k>i=g*|wz;9on&@WFtB;~npqGw9v#7s}QpJ+QY`f~CB5EuN-0XXOXI+hBJi(GNcFPbZI| znz2=U#{xsK>OLfDe4{-o@NkefgWjk8zY@z+Zz!%uS$j2jGx0h}47L#K94fn&1G5i%)_UAa)HaEeyAi zAH(egw{$W`3|uXsPANJEz4RdBnRIYUr}sIHrb2K^KVi+PrMnZhfiE^Mp_W*K>OfQ? zMyUT84i$b_A05#Rb%|S=gyuV=+_6Qlzzab-< z!4tw4&!=Fs@ayvr;|#&PQA-{236E{ufE~h>jgvw@^vU<~jzMpuB&6C*V_uQmFwHWC z9I%aLes&YL`U{Ptz>tT;XN1i*Eu3C?&z3>m91xr~4o?^2>{_a2K$v1T;!(nS`?%yS z1OLH+<93maZ9c=xTnl&=%yz&pwA*LkZedhyM*P^JkNGP8h&9?#zYXWrL%3nlP%!>L zsH|O*_%K)k{Sa}kffKj;VRJ#^JRmKU>IZw^H?`~W+d}CkJxt4rO{H0<0=#up*_YQT z8ALIF35;$OTf;SekZovgmILoZsWR(_{9Y>(-xV%x(!xRK7%qid&=u8!#Dk!MK?v_9 z{1LG=eoD^zfn7)I~_V0Am<@+7z%!dd0}N_3k!oS zY#P_=7Mr&Q4>XS9@NNjE_cO^+UG!nRk3@IgBmBNO(e?{09~q#81jq!uEl>h9UI29k z*qlg>KTZbE0wd|+AOa3;!}*6`LjLAYhl5Wt&JX7RN!QlGU<8DA_taa^eu!$28EhD5@xl)xuz(-$ss^cdF+OdOQZ`A@IOeX{mgZgHmwC~=2}NTtGA{+ zo4{3ptvt&**P8sSr-_`hA`+(L9o0&5SBey>X(gv41!rB7uxwj_?Yu9g92flA8o_@dh1-)`(t#RB z4P|#5pc$m!#V=Ch^O1aR%OO+D#YjG*<(Gu$@*7}(59LI69ZwgJ+(lGm0Flh|sk#Z@ zkLupVziv9zi|KcJY34vLgLhefbIHmHA>Hfy*gB%81dksU)f(X-WleJgSg zpYYf1YJ6QdzdhG>6+WsGxG}{7Vc=#t1mNuAl86#f_kU}G3h=WHcsC3b8o`0-#XB1v z_(RDn4q{NzByas-j)MXdI5QonfL~#iuan>?1^G$?gba~Yw>h6bw2U~D@|_nX#(=cR zWw2sxEa(B zbdwSpA=&T_*lhn^Kb7nUUogC^f8wEr-vr=oVTfZ<7QE!E{PZ0>tOAMz8m& zPXlulChqJ0UhLvSTrJ%TGqj+L-dS_izV0=M0ig*ax^AfQqwPlDl- zY^b%sFqNFv)3ZnC+d*SN$Zh%NQ;;DN`Vv^*&pSm3-Lp_ZEFVm^YScsOHZ`8AF$yW*!x6crjZV3;oH#Xz;4J_CIDqDHvz z$^tw?$bU6w)WjhL1a_)mEAfNX<;hp$!0Wg5Rg31=0bS5{hm0FqV!Kh=4Yv;j7RgOS z5x@7J1A_SK9O~l%p?K#kIOzM@&ZBsWVBS>{^87Bu&V;mH*tIKB)*8HX?0PbC1$^bh z2bL0sQ#tTHzjwMYVfXX+W#Q=V48>ZA_Vatog-g4&iOWtRo$*#|BoZGzDK@{zZ*3%T zccXbUVXhD_Ou(5!xiEV^67!|Y?y1!%%jH}I|KB_DVdJgv*(4?erJw6+g^eiRP7XY? z=o@#$iD#P?NAX7xxV8elHVj8}nPhnvp;Nq(i)h!B%34A*TxcUX$?jo=LG6T8?_y@F%Y`-=mC>E|itfg}~tW*`9c8 z6}t9laiuV{ClL&w@vmhhyz-y2;#ldD#B^T*N+f}vg7vjB+e;idj5f5hM{az#H-bT9$2fj8BK;TFkvSI@Fq|=O3H*xyg)(QkzDWcy?gs!QJodPM zcu*T2;ZMqkQ)5M}KfG^;NpWGFIvfC@&Jj1$b^8|X>x4s14*#$i;a5chz{RW|N&8C_ zcY&bJ?Jog8)CKTxyxYq%#-4Cvn|lY02jw8q0q6Mu3~YcIBY+(DZN7uXSGabVs2?^# z^C#_F5|;GR7;6B7IUhQq?2Px^fH_*@qwl<7#6C(S;9f8q%yc*aK`Ru-W?&J@7~og!c`Zj!pX(oBmnNXweBxH znsC}D@7MXl`;yEWU$__hm5KllT3h}eP?IkwKC%=WD zD0^XvIs}kcc5ZtKci|%s6{0OZ&>M=|{*A!W9$X4wNGAb-ZZeCxu=^-%o9;Ecucv=MsL1b3W`i-Wx&vsTV60zVN|Y#u*U6<23@N#-XtzSRHQz<8_!@ z&RxH%=7z4COMX3fvX_dehK(N=UUswGIk%O2*-BpXegZIq?2rAUW|49Be2q_OI z2X=v{lCuzV;N)!xe8Z4@d5$gD!6*H6{i@)1)&BD>Isz>DcpUj~T=1iDwjd+`F{lj& zA6OiMyD0<*oFcn#lYb;f^kazqx9j};x@ z`S)qScG(K{dL-U=3dZh%UT#A<@!;vr3Ym*M+eTh=!k0*(IY`hjAB0kc7V9mk6(W3e zgW=-p&h&+$2l>SC*ym1~vYc;hJ86=+uqHfB=0~~*`Pk=*Zqbxr(l|}GFkF-2N}iLP zMZssbZDHEdQmIW{dU-BKWmc130*ji;`N-8L5Uu}&|RT-lic^ z^?{)%OE!>oK2)w8!rJIEzjxXYrHz8?WTJb5cKQ2|-`g-Gfd{d!0FV3JT?f-R%ZTRN zuL)Nhbhg)FH~0V&4TtmRn`w(iv>C~KcK|sO35!aWS!8A5ZLAh+DUqS#t&H}LcWf)k zCz2O&FX6H~-Z4P$J*1HOD2waFyEAgkEL*P31e|D{UEdP@(=cI8`X@R_%#-%6SE8EAe? zPzQV;PRBUm!v%%#>8vQm2Rb60Cj{rmeE3?-Cs0ZjEcHbo9gJOn6~1}vX}m%xdV3Wv z6OO;V4&N4X-uVs;GX8hoOJ&MsmQbGR?_L@WU#B3STpV_X1L7IvlcnndTA%mx)52H# zvti@By?;k;VRH;1K82F;3;1281m}gvx0_;JSeKsK-nR*bY8gLOfc+HpX3*d@SJDZN z1EaA{`0BvPITzr(3k7lM!{%M z__>3lu`NCmjy*$q8NL#-3X&rou^3V!qz525;N23qRzrI4Zn~ZgN2YTSy9?6M@rXS@ zu8^Qv^cv({&jqCp-oO0+42Tnf>|`LFX$&+kH#L_5xVR0Z4g`!C7$&DL`MWt|sQ_>_ z?lP77hjG9i2S5ywW?*;;W&0*FaQsbY;CLU;!0|Q-BEK?~fkP3>)=x<-(=REhbaeJr zO##|)v=HbCAU;^kz_GJ{fg?PNfx{h$KLSVHnSnGb5HBrd;IPhvn6(@@GX=C$h`}1d zU{Hlha87nzZfwY12@FFZ2080@1%y^D)>kbCTE*E6G^&w-<8cE-{56n$eDccW(X4mg z{;y}8EVx2(vcd|E$wn)LSe^ifwI*L!EHOD@g$`rHn}`Y0swW{2rB>p delta 25 hcmbPooN3B&rVXkKxr|H=O-&7xj8jcE>n}`Y0swe^2!;Rv diff --git a/boards/holybro/kakuteh7mini/extras/holybro_kakuteh7mini_bootloader.bin b/boards/holybro/kakuteh7mini/extras/holybro_kakuteh7mini_bootloader.bin index fca97ea49d7c894d56529048ab9297e29299d66e..81108119f3eb75ce47a7cebc0f9ddb88f76f4929 100755 GIT binary patch delta 4472 zcmai1c~}(3wy)~$8CpRcKm}Q67)F*69Tp8)_!x%RfT*}DiAH#099-fgsGwJ!LEPd7 zTB1gx0-7i0Y7|G3i*dvlvzYhYTqaiy(YSp^(d$cW2-j|AeWwSX$@}Z|_noR!b$;j6 zsjAa;sL9T{y6z#A^4&h~#@*oKeUny0a z!Y4`9_3*vnY9~H`)N&P8%K0cKQsV=16$N~#)4C~Qlq~A#hlrIGP-aEzG%;1da1@{F zKx%b`HvbKwksN4v}@LVR#LxQ)wyvA?qd8B@8v$q<$qxe+aQ` zE5nyN82(+LWyG!yp|13ib@9W9OU;gIYeVe}jpEJ&39WK2Xd>P<+9>DaMf?H7={T>D z?io}NVT@>z^C==pjccGX`pDI|$@nv((Hx_+UhDUoV2syT?~Sn0*h&s34aM(STa!xg zkWObBhtt`S-FD`*$yN-mEIDLN8d*CC>#U!@93wLu#Nr6d8HzozmzGm2P;7vc8WNfI zR_X8sOn0ShkGM+zIkQjyynv{04Sc1;V#Ipp}X!T}wC zV}Z61JpCg)ogACKkqUB?Q8UisedPX(L@M)h5;!v)W|KHG2G^1NnG0|pIW;p`b<9Ka z!VC`U8l$b zWSHlUc(!S9%XcC&fn+yKcIk~15@B+5X2wine}wN6j?MWxoa-$U2XCTPd&2ei#=kM1oA>e zAik%{7|kT0p5LnOJVHF}9~d+QF{=N_^9uf6Nu8qabTO)VdCz?1?@+##$9F|)Alk;j z`nVaDyjI@q6?#1*lY8wCy0AvFZTH!}Tt(N@JWbPDy_vsIh1G>T@~4!rxH_6Qz>Xbv z&xRd4=VrLD&wc%f=Jg)f8r>0ts*|oqaXCCg171%P*cSb3<3lP#+Oi5FDnm@!J;5}k zk~gFHlVX_8E1dPjcOlKiuGw57=iiO}X?~CUA6-&J{HGi1%zA!G6_al7N(Jwh`c`3O z)li+TPlm(Z;Fhz)}ZGpaIdpVTD)}MVDVK*Gn&)iwFRO$T_a*oAQX2R=q%9X5TIZb z_bt@tL5`ANw!a(sQipu+j{Nb)OKsb^5RQfL#DQ-WWLd-um>QQUl_Og5Ego~ z4^itwR9oc7hroVqo|X{f{^jpq1nW1=)sLUynmsP7xAqeV&JZa$`$Mz9ec?g> z|Ci+E=eLwc4zf$pD{rP${eV~9rOLslZIAdu@X{vzG!b-!c7Q#FLojEJODYpwn+*3m ze&_jTsMri3ciTm(5CK@n%N$Y$yRorO3G5=ErYsoHSA>{UZ#--F{Cz)K<012SG zY!~&=MK&yQ;apO+IBnqHjfic153!-k$%Vz&ajUg%i5KH-r0$&x+(-s3E5t2i?y~!M zmNnZHPf`CA$)fju!+#+~60O%LD?6l5i0kNqyfMXK0ozkfonLx*l zKtm@caBktNK9ag((y+$>nFk5)XQ=N1p*&NrtjW4}#Zio3A+J^>s;{_mMGZ2w;mjkI z2Mw|t8DRdDYZ*Tb4ZJ%GBrc(uY_5okICMd5Ww?!%IMeTkVxvpg<&yH3sCNi7X|IUF zYpu5`Y#1k!`c+X_McP)4f&cjFsvPQ<^CW$>5>FvBR=-3shse&=GpRm@_2KGpESENZ zWD}9EIfVa8K3ZeL=g9oEIdDNewss-)%s~|EjQ9((YF$~>b_Y`oCtA9aQ`lPmoo!}Y zzckA1MMedIewH}`( zHC3UJ`@OfjeiXw}XlrEgWbPX=EF1AZgMv%Ap8;;`?(z3w}Wy;1ecsyCSalSwALTV+aF6|Rq$+eA%!#tip zyf?MVxByNR-f$61=rEGBX$Y9f+7z$Sff5s|oX z%J44Iy=j*IK_A2YdZwX;G6xh$*JY>hv1jA&L0gbY$)$pOtNQM3Q*xN6vF(vbFAB*Q zBu#+^r4TPG5I+Co#H^_S7LxAx-Efo3PI%8%{A0xH(9r3D)?sK zvVwBiNZ$LSl6E_E`gx8mBCc&{!Ofx&?7^H8Ts!ZMYRNHbi>r-`i{-0Cq0>zo-k&_& z?#csSZaDUca}-D&lX#>ws51iwI8O#_jgW59TVwEXGH$DS=#PDV>cL8NiF6|pgh}n* zseb4yvUY1I-a+cN#>b2~AKc~?t~aQhv=sR|D7b_xf{$sM8812_44N0PKmJv$6? z^G?JT?j*15j8@u!EtoDntZ=PUNP?{H6f$AI6fO7zr{Hms%AJ+)hjj0ZkYBuj+GQI^ za82y!J8dVs*?^^wneS2JfSX7geiQLa#akkC_ts-d4X=n?y`khuHb&YAkQ9^oHL9q> zKgs*0rrfE9`A>3a#AlPnn#Axue^}*5{0VK!wLYp*(j_V{+;!&1DldzcbWsTRBDKU_ z7CY17*`=pu!vji*_}zW-0x2=vG|tXJytxnYr}}JPEDQbwj}1097tF7EGP&q>(bP8hcs@xS%`A$in>_$JatVulUqRJHWqju9Vo4)H8J z9G=-p*q(>41YR)ZqV`yS2H^zEQFba%6qrBtv8@B`a_D>JvG5p4Lw<2a!t~fkM%`=L z$L>UEJal8FAQZt-F>0wG%n&sNhYXo^tQ-L`G6{M|E)azA37MGAL zN;)INfdzxckK_`#aKOZflqxXK35lxzpjj-sgyCesUM)4fiHzN=TfqG7DlCrTF1jlv zDV+CAaJHj%sf}W>ipgVJp9wv%1$Wgb_CN^>FI`DSJ;y$Hfu(%9x1P6|gbd#q64Hs4 z&xGaVzxGDOFYqE|h7C?gowI9=^up1j*%-1X+e+Dy$}9W?E(*e@WbnR)@LaCgr@`y2 z2lq{(v6(zQkc>;LQT59hYwckL4x2nX-7sNg%BYkvqjU?$ro22hHEm2vY8oO94Pj>c zT*O`jf)|wU`{_BKS&Z0U-$v}6w-9@)q+k9)DLfUP^P@`_tQ@_3`Ks)kiJDU6{qNz6 z5j$%UVuvn8>|m(Jl)*Ct=pT???*ZKhnztNmE$g@C4=EQ03`XPn8H7P7dC*1j8?#ca z6^NBc>N)bf)|8Ldl*3Rbs}P%SLF{I8zq|(c#b$D@k;4jto3h~G$ZpD^!kWmYrdTSy ZiG17?9asWum<7frGYGxYM6Nfb{tt+-PlW&g delta 4307 zcmY*c3s@9Kwyx^#fmRR)@D%}>VIT|w3J5E{uEP*p6b&E|#pjq{1c^dcjKmkOpeQP6 z`9`xKZWeY|1xGfEI%163B<>@OQ7=k%(T}U(#@sECY&Y}jdm7yA-TA&#=Tx1)PMtb+ z=2Z2`FPVxzFiq7g=FNxMbT`bIpN@FKhFo>{Cwnv_8e{hZ?oRL9CJyzBWlYZuVp?kF z=mqlqsA%j@0=#sQWo3we;*WUW78ERtnX)Q5Wg!0TEG;_9B_aAy(g;kG+Jf2^A47aL z+2p0eh2*f;C0u4s7;R>`nlp$ell&(TweKzF=^(l1D==RSn*GO66?6U!@tXL7!uCvj zQ(+G#9-sKshEF4%n-*)_XqOG?@M$+K1M)+gd5_-|Re&B0s*;%^bxXPwqviyL#sEsU zP4PibtePVH8A;OydN}|Wcoy*sf%csxyS3vmBFD7h%3tjYd<#e8 zY#f~i6iuu;U#4=9><%4A96El=j#kvhu_*XDkl5lTcrV6>r)I0@a~YrFgeXB4V_lYs$C$54b|lnkPq8kHQh=Ycm2>MaAzLC6gc08cnXCn^FY6Rlsaz1W!BW z{9`h*)a$vvLe){}L&Ff16$SZ+ z8bYj>KbL~neJ({||7m5C#=A`N^mey17{?rz<|MdJR%VodR4;jDruD+4w-;>HIK&e& z(zA~&y^=u|qubUjD%P!8TyN^mPNW95+r$FmOS>)yh2u^#{Ze2$5TZ@8n?z-dq zc$Uq|YEXznY_X>d6i*wYF<+iL8ILf1jQFoSQSck&sbK@&X zk_OI=ZoVU-{4R+efzAHxj>M<#lTa$wz@}ZH&5tA$g~AbyC`B4sTr9KIYz+$U?^N`) zF1AKHOC8?ZfzK_GbQHCXSPuUppuIp<%YLFF{0ERK>@lWz8RmMEBjA`9y+^;=82dJ$zk zyu8OCPFtKLi(#@dn_;_pia71Aq<{7(?MrBPCea@M5XhJ~mUcKft*TnpAd5b7MC5?= zX^&!>LcSo{0L!zKW!Z28Jy(KtD1^~KY@%2i3;{pr)I-2Oc5(uLZD<^^G{^;!jjA^W zbTBn2IFWKJ;0;U>fv_4@F7z$*ZC#V>SLmCc(C@=CT2%uIy&#Q=lEr(j`8|38gF`!= z-}WdcdBBOI40L7*7kj@a23$JqQg*(!WGrPF16^4X{u(T$t~8?lr6nyt78jxZw304K z)0`>%+BnAg70fs^vs%>u;nhY1{l1us?HG#D@*(r;5)?93nDQ7!&al4kKfPUb zJcP_$F&)x-+lr7PRfFn;EdI=;tgL2VJX0b@9jfZjdr+Ij3kBCg`u`T8;3l9eK(~E? ze1Jgr70B0t!(Xw1BeEzvk={Tr6)We{2Qs3K#oS4j-gW%z1Q}OA&%e;U3c84%9D+X@ zf*%2Rsk?z5D&`?yDvMb<@~6Xp>Qr1bur<#V^S1!My`7~EKbgKiq%USGhxC_0zp-7_ zI0pU%XB;Yl({j}uq|hyAn4qN64Fx?=yrrn%Sr(Wp2Y7nt7ndhRrgkXi3G|cOQwG}e zS-R0tCZr791!=uQpIkF+BEi;zIR zN&*e1&mQOC)8RkJdM9n(;y=o&B$z6_fzb{FK5%AfJen-MGzGl0C~57-`h}0MMhgh` z5adwW5XT;4cl+HQm^$s>rZb&L$B;Wuhh|ryHnMY7l2`fFcuNIbKi|O_ov$T#S1p9v z6tFsNv|Z#Rr00adM_ERfc#Z5@z1OV?4*8Q>^T;)n!TZg2(;zdaU&291%k@Pdm-yn9 zJOSiq5(_~cQvW2^ z#hz7fXat8i9de)nQX17EegY7!B`dZD#lUdiPGl3Spi(%*AeX8s%0eL+`7NFTrw{K? z3YNc~4SpSsU91k z+OEM>#JYVtQ*oAz+>yadx0~PIF%i2d`EaI=lb4_j^O5!*d@!y{sH`Ll~$>dE-~RC92gM&r-TpuvNj}@JiyUin*NxWb)+w(MQ9RHlFL6f;_9H$XGH>1lO(Ea> zTO+c@TX3vR{3G$M4CS|6_i43@V;sa#IWFLeJwxKp{BfRV2X}Xc5GEMl&_9u4f!oD9 zWJ~2?ypO03%$cy!u8gd;UojqOZ|vilXxNh|M$2Tyfq4I!cJ0uFTXs%B`ndzym!bs) zB#Q1bxp-g^<8_TV4kY0xWZuC>yomhcVC3s@F89+oMlIkYcCix<&D4wqe41}Sbc)2D z4ioqWyQp&!^6o z?IZ(-3gHj6smjmIbpy5SD8}#^_^;0y9X#&m8;t9|PrxYLuM^R? zNmrE?rx9H3hZ9Lab=aiitrz-u&rQ#{zaXmrk9qQoTSv^MY7IMjwVXoHJ3*S;QgN&# zW{@f}epdCM8+?y#&+p7$o`~qKK}0VMT6%c{q69u$l$)4uLG(8;P6m+%(L!j4^&7|& zk{<49OQF~_JmPj$!B*R06%(Q_2LG*j){3A4u00y)I#ESunTKM z@dQ+kDVs!*NFm7|8|PTD=5;v#127t~UKA^c-|^|wzH_MrQ|p>$hnOoVbF!q7$)grV z2zp^6U{*_v)+@;Y7uRszX_Oq|GE#mVKK<&*<>OK7jlaJKfl)t3kCp0)lSFaG?@^o5 zM?qN2CGjny7$v39$2t^rdL0iRmWqyfh1LCpWrpVZz3OxN_@M&g+krLz6fcwcCjvt2 zWu%F>K!J&}_qoHtFHeNv>*m)^ra^@uxiyja z9rLN0JdT45SZ(HO)tE%pO(jSb7f6O#2 zPt98Y!PJ6+4-*m>hh!o7#o3LB@618`srTRu9e69;sf|GCK$yaxqK=HK4`R;Ok(u?AysQwfxd2Y(5c*pkdAC01{{V%#5h?%x diff --git a/boards/holybro/kakuteh7v2/extras/holybro_kakuteh7v2_bootloader.bin b/boards/holybro/kakuteh7v2/extras/holybro_kakuteh7v2_bootloader.bin index 7ed8c65c2f539aedb05b3a3ee7a5ea7db243885d..c441ef2a231789f389eca4484bb6592727401032 100755 GIT binary patch delta 4472 zcmai1c~}(3wy)~$85%)kQ9%}&VHjCPbXYWG;bRy=1EPXEBpTs~ac~Kf;C|H^#4T>1 zC2Axppm}1hMsOs#7)OjTi+SJ8WpdRJiQ8usyuQSScci zs_Jx|s%>9W2fv}3YiNAXvWK1_$7ag|?|ZabbcE;mv>-mo9tO1+A7l^pw9RhJf7p-t zjdq5AOdbzS#0N=)pDMv!h1h%Hhz)8*(Qcv0Ez8qATdOZsqJ2yb;(rnq9M$Y^MeSE> z5&H{S=BL6>$sWHm*lo!eW}%tj!-yrL!$XLF&}B+BK&}OG6g^-GAI{4t#bM$Xx>BmP zgie*J8=?C{Rd##`spLwmkn<6Cq{4^fN(%U3yJbt*I9bH;4-qTNqfGv-GsGl+hNJkT z0i;r`l6*K$Yzh;0lWEFGztu2s9njZ6vLj@JawJ|yYLyyFcf@j8c^N}Zwy0hS&>cZ6 z+sg120}THzP&u)wf~c$gWJAnI;!v^U+S*V%L!;;mKtijW3z&lUj5o;n7!iNKa9YkS zq_~FWg&D$Ht3?GxANUg!OprN(P#aZ;5yS69lL7_ay$F-Ny_b@}fYB*(-_#``v;3XjpL zZ=Ss*MweU?wE^K;v#3y-MPH?toespwd&RU2FO8(J5x9EMZ(5HHMJ*`GU7>IYhukQZ zzG>|dbuicV`IF76`BRP+-#29PI{JPw4T$gTsxqX(T{um!smd~WOsh&}=gpcNRrZ4y zzK&lVu+a*nb_k!^k1ZLl$b4!}wwz6m$KF4~jKB3o(U-^r-6AYnrep+TA2NVqeY;{g zhCfTn^=kasQmfxVkk;wH<5xU;&^XsW#^G?qu+p7cGCuNx%WkpiEjc?)UF z%^X_Oh**gbg4*IeDVgy`^@tS#?671_r5XIYC3kuZ#;eG?Ga_+5*)t;;XOfdM^1V9% z#{z95c;-iVCOI*4GZo+@<7S=12gvXTMBo-6VBRwCPk{bu&_Xad*V#jS)t=wo_yQ zGSYQNJl8m^L9!PnJMlY_EqGr<1y})-cEz;Z6pc~{U%~h0A&NM z0t%Rm*vS8@_-7;kFaISBOo5XD5PyhgHqv!cWYMJLt||ZNTBBQd;*yQN)F)O-AU8w= z;`=HMqnTLL_gm$i9>mi=egVS~qx_E?x8UQJ)G7K-H=~@N^UPEJ4&_@pe0R7SqHO}K zkCRc#YvfIC;i+qE!c*IWZmgDU+dQ_fRMK@cPt&wUXW}nbVpTqmd?*Dhu9oKYuwy5k zg|K7ioeUT9xu+k|yv_w%qdlfqcG7hyI+JH;!0TuN+oF4IQqbz4w)DKP)j`ILzCfB% z%9~KkX)#3W7S6e1x{>-)cOe(Y`SfBRn&0RAN4FFa|LMe9la8NO$)wo2lfb)Wo>f>` zIfADt9sgdXW)uwRzeA7umR7d@+iXI8hRQqQhs{OY$NJ&6Z$V?RXFl^PquZ2u5F<&W z4WY$qo|dU!KcydGlh%o)CwEJ0{P#yF&@H^?f+#tNVlVY&Rzm#&HXXtu_Q6Rvy1PW= zFL^cFDV0UeH$_HMqu22ixYyY&EnbReu$W4u9?$9STK!P8wgIuH5Q=UFItO$m2q+Lm ze+%^mkfVf`ZSRJ^)FI!$D|eFNa@$TWh+`oprBQwp%yoi%4CZ{y8jz0KMGT-1)*awg+FN|9}2s6Fa zgQ)Q!s?73}!(m3BIbPyI4Sh%B>YozMY#vR8t_Xx6j5op!D@MvOMqWg z3Dc@|3tK&SlUu0rD4>ct4@<#?NuV&J>#MV)6AC&dmkObs*OC9U!$|YX993NY(;t8{ zIO6l_veIpFc?b2c+3twPn4I2=? zhU0M`4HfnL==_E zF}>mP0L~>eKugO>+=tIGqXDy@v@TFl#SNC53qEDAhU_uqLvFukSVmp3lY+8(NC3TM zd#HyFvT3mcXOqe$$wU5bKy2%Khz(v&E-tx&TP?Lq-5Bp6wePIL4PPGD~Fx4g?a|5}(JSqvgd)J`>VVW}*K)*O;&04D&#Ku-%j)~QDN~dCYEFC=t zjhGV4IfbwKNz#g`BOd`|J|w)Kp}q%%a*Ww@qh?$x&eVE?W-d2 zddsaN?O(ylr1(LE>fv1sKYhR+6BV_m5*;N04<>A^;ESENZ zY$K7cJA(g8K3ZqR=gETgnQ%cpv3?QtY=HQ0FyJr9nhj+UI|rCzIMGrRoWHf@-x(&h z^-F`yR%Gx8ch3{|hAFs?Ofj7tVT60D(OPd{;U-+zui#L$LwK9`n4OGWc;+U)l^gLn zQe7Dwe$aip`$sV(k+y^v7jWN*AsLAO85A7CodL_`%Eg$v?jqx=3h*gns>%w;bzv1! zNVidWu7c|qGRXC+M7RccZ90h)Ny{b^l!==s;7MfB<^?{y1F008sI~eM^i|3rb9sf-B>8L0aD>V(l)GQee_A{8MB=K})u7 zDZ_h6@0K~b2mK89>)HAi%H*3TU6<{`$F9x42W&%11(yWwt?9qFL&0I5#?~IAP81R@ zO44$kLPo1}(I);|!^!cjDI*@)BXe=eJH>v6uS8$-=(bqSE(DNYw^mb+oMgkc>EN4f z+X~8IB{}bpi{Cq-)y*H+CgPg<7ThEXfiBD`z_km`h?Y!)rnt(mq*%U26gr)x{{4bc zHb)Nla&usxIM*MkBIAyg26U#v02he&_Au!dy*(12Bw5>4BYy1nQVmn6N~9Z+AWUs{ zPxnG!k@eey@h(!kJtlI(g}^quaKj#Qm+B3sRs1lYH?mOQS#v`#E3*qLNf+4LNrdft za2|PoM_R~OyAH-t+Ry3tcAV^GsYGy75Po-&+dERj9Ro^E5^u6I9EweUYB-a~NgzSE z>LN)yCsQ5giFs!ZK1QzYJc<2C#jb>*g462|PV(pQUb}FZoZb~oJ#dn*cg0J~)VE77 zH|<7j{%-Qh?$HV>uz543hZU}|3-OTE?Lr#tmwyZXz%IBPWcBXV@Q3v74wGNHh}vbF zNMLo;_&aTf|m_MP7*_NJa1znL9|3+X zl!NjzQbuNI{08!QTs+vro|mwD?J#aJ;(zP^L(xa{3e2DS*w!I7IrKeqnR$$)A-^~)Vfw5jwe~g5 zBWD~m9y+l?5Q^Za7`IFiW{K*&BlgxD&xAhMg1agdb*O}em#!qEo?{=pz)~LFThH4}Y^vuB3F^d( zXToywU;86s7P^rl)e0x1*518Ndg16$A%^V9wo*2vbPGR$i-Pbe8FpY1JeOA;P~#1j z!w06(*hHQjO28$Sh`MsdQghTFhZGd1=qImC9G5s@oOaQ~#Fr-~B~M69N=Br%oh8I74#NF&+O7)7Nt Zl8+ll`<1{Nrh~Bp2BCKv$&JRO{{ebJPlEse delta 4307 zcmY*c3s@9Kwyx^#fmRR)@D+K@FiaQ(6cAQ?U56pIC>l^BiqA2@2pVOwVkEwJ1w~Oo z%Qu<@b+fp;Dmb!P)DdIMCUGBOjCxVBi+)@k+?czilI><*eNTg%y*uA`>YS?c*Qryd z&YY?~`Xy8K2d1f(#k_StJKqO$*2jY$vHHvI&`iH(M3Y=0zSC7 z6emZ=10@o>E|{tABio}#5VwvWyQLMiaV(0u3M97p2!V6({&D##`c%fpI3Yoh#boc0 z%#i$$W)*!YlccD6#wn3IQQ7!IqSyb5`N3=bi#`ZrWPS9yjl~8 z7n+olr(VT9FIF9tJ~X~T)!ciQKV8I$<9iD(JGTcWy*+cI#w{L^ zk%4_+>yeDInAo;_cByXpoYUs+{B&w$yUi>hzI5pdP%Q4mQ$;)0=~m`szBN0t;I=Qm zizhqntOn`bVv8%Qw{-k4jrHQRF?f*qW5j>ukD}fnkBzJGR_mO!k=Sp66B+zF4FX4t zNTErO&sh(ds#zROw8909t#%;-`&+%p;Otb}Sn9k++%pWp&9X}9&Od4jYUiHwJ_!O# zYsrL+*w+roy4^T7z>ah2IL)V=7pD}E{rO5yCw12yCjs2HLz)Kbn^oVC7@VDALFuNSlZ#?w5nQFqbvr=aq+$O z#}36bg?vG@5te5u%d)XXda4ZTke<;%Y!X-+1p(jdF+jjS_HY7!rGFf;G|~%^O*m}| z>tO0oR66BYz#Ewo0%0{SnH5|d+`2q7q&V1;_9BR7w5moFeNGydAd7drGaLp1gF{neM zSi*id>7JugLTbg0DITSr=2;?fv9%^6{l1h-?&y!vqJH!0GNd0TjD3jWC)(c+ozSj2 ztS8eJPk{8^v{+xFYE&JO#h-bVmDTLCCrZSqTUGnH1GU)#P*gpn|8EhBY67|hbTb$z z2ncjvfqWG>{1qEHB8##I8I1Hosd7HgK}Pg!DR-2mx846bLB<>A_!qiIL6^{@{qP6< z@B;uZ_chXer99+Ibty{+|8)3|J&KD)w(f~y{s!PTx3jeIC)0QP^`&fezy2cV*R-q7 z4ue0z3Aak%v|KF*DRjdVBPgkKO+ojTZYU{wk_YB00Y1O;i;Lm$*&T{`0{zVPtloAD zOV_w7gsk4%Agyv6GV7*Kvl}vxnx@#hq!UdFV*20x{Bj{`+3o@SJolpM(|Uh%9ug>6 zNuYuB+2QGXJn#ou<)O_RLWkIu1XIm#WV8c-4?KAqzb0D`%>plNN?M1oA+dw(i2{N> zM7ot$@7`hRZoln-spJ1`I@g1A47v5Ve|8OOBU_hd1XNy5wN=6O^BtVgnR;@2=`5&C zVaw(Yb%~sW44e@0AkX9#uaIracKS5IA%9YD9lV?}c(>JM?qjCDkZ>f@a?j(CSA6zL z9tH9f2}Py~-1AVMK*1|^K`%j2qzA7s;efeA67zISd%ZO$?{^$7AVUhW@Q-9!!8(R< zlRp*IU1V2b z7EU4e3%l_ltIZP4FoAvK$pVwU)NW=MKu zX~k1d7oRk#9;AZ#AKZm>1RDHsA!yv<6E}6>lopfY+tubzEJ!2S3h7AXawuVUi{D+7 zS~#Jy7*F-RZO(U#-?)`qLozzWG%~q33}3P47TYjhO-61G!z)P2<`nz}S-Ux%iL{ZX z%^F-o?3*VrRVT^dEji2tm-X!}qp^>Y4<{N(`PPr|Q=;8w!xHJ*mX7Zc-S*W?vWx85 zo{wenxRK0ri%WIru*Ly5#Ke^YAXT*y{6ncxf)`(+DWaEuJAeOFf)hOqNJh zS$XmcnG?RU`aX{voGl>w%RW^&`#>YO#C!7J9RDqiN@T5}=4|0hX;d1b-+>9Y80ND6 zSNR&u1k2>t71{Xj#8ojpaHkjQxJG&Z`OMS^ePRij`%xl3Kq@{uiwjA7WeK$BDpPP3 z>8^aoZ!9FgM$qN;i7(0A9WleF$ebB&$z+Y7wpm(Kg1;b%M@h|&Sg>$qN3?dm8|qJ_ zMko;W!X3I-!U=mNMuSP87}&=Fc0FNt7T|Blx}6KB>YSYL!^Qe$ro=x}d7HY#9&hE# zz$&EG2ua}Cr+tsAH3FtAw)I$ylDPJoqAjEhve*m+SIr+D?T(mOA^1qP$OT$|Y z5RNQTP*uZ3dx^7Z9ym2;*G6X2HF9&;*fH(S1mg;4m4s{Sn{lHgW_z)q0iT?nu;%pq zSaU`GTC>lGk~qRkLU(7U4E1Dy6Qf)QrKM`5i-V|4`E0x!XDDG*K=lP64AXk^FC+>I zNECf#a(>TjCg2Kj@5#WA$n?Eu@oe&sz45Q7czuuKB(;DKxWrC4G;=c+@NvEo(XkSH zJVxLfU82rQO#8+tQC`2#37OZoc2wJtFqu5g#Q1&pYh@iCV; z#Y1}c6~iBDT}_CO_Zn*3RYCUEM8fjTHNhc;(qAR+;a{IJI(XdAFq&3=pN3IvNGGCi zldc*qo=b3T2u>$qwK3s`ThBe`{ntI^{(`9CKjz8LZXB?hYc=f9WpWlp??h^DN~Ot? zm_usF$jP;RKJY!Z+0vQ6C>_yleTbgxv-R*sL-)FnNh^X1xZ+?$kZ%W~{!UHvz@rq=kjv!Y!6%bu zU$e|WZION)!Uilbb|ym-P5*Ch(Iy5CV+8YC%C@x#@s&J$SSmW^6;}5Xmg%1x@~Y1nQu_-?a0k}>Q@luK90`j) zEh9~;4GK(x%kfO9{6@40!)?m9Fm|Ms#rv|7+`Xjw$ZC9=P8z%naeuf`;yVN}V2Wr)uOLa%YjfBL1D_h+nyKKp&Qe_(SFa zd0gJA55^T0eVCR$N1un}XD8PnzOw-F$KHc4bl|OUr=A6x53~wsHBk2kuvIuPzvlgZ z9)!Lg5Ktv36(81;`wi2QCTv2yLdr<=E3V%#PQL+`N-RVCpGy$$2c+nOOA-H%?PS&| t0UOBvQ`4}T*iWT1RSjgs=}6{G1DSL>Jird|ng-x(4xzs_katff{U3Kx5hwrv diff --git a/boards/matek/h743-mini/extras/matek_h743-mini_bootloader.bin b/boards/matek/h743-mini/extras/matek_h743-mini_bootloader.bin index f00008ad995960c90bf1063585a431df485344fa..aa47d3e32116d028bf77e107cec366925af0b589 100755 GIT binary patch delta 25 fcmdmRmT3bJ=`P_iGqf}_GB!0dGTv;yq>>2$eIE#! delta 25 fcmdmRmT3bJ=`P_iGBq?cHB2&2HQ8*wq>>2$f5Zs% diff --git a/boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin b/boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin index 276cc5c99a30da2de309b3c54cb516361718ed54..954f7f6125473f97af647657b78f79cab3606ec4 100755 GIT binary patch delta 25 gcmZp;#ME$!X+!NYE;B<*Gb3YDLnGtO?aL~e0DL$I=Kufz delta 25 gcmZp;#ME$!X+!NYE+bPzQ&Ynv<5ZK)?aL~e0Dj#GLI3~& diff --git a/boards/matek/h743/extras/matek_h743_bootloader.bin b/boards/matek/h743/extras/matek_h743_bootloader.bin index f9e6043f8109688c3283d06b6bd6466905604582..93591c17c925d9502e45b8962cbaa6fa8ff023ed 100755 GIT binary patch delta 25 fcmdmRmT3bJ=`P_iGqf}_GB!0dGTv;yq>>2$eIE#! delta 25 fcmdmRmT3bJ=`P_iGBq?cHB2&2HQ8*wq>>2$f5Zs% diff --git a/boards/modalai/fc-v2/extras/modalai_fc-v2_bootloader.bin b/boards/modalai/fc-v2/extras/modalai_fc-v2_bootloader.bin index 8675496c4ad19e30819220007ed8f5ce2b21525d..95b62a8d68f9889e1292d91225270afccd1cfe77 100755 GIT binary patch delta 25 hcmbPoiD}9urVXvjxXcVK&5Vpq4ULR9_b+Q@0sw%l2`c~q delta 25 hcmbPoiD}9urVXvjxQt8@43IKym2~q$6 delta 25 hcmbR8f@#VNrVY94xQt8@43IK)j39SGC diff --git a/boards/px4/fmu-v6u/extras/px4_fmu-v6u_bootloader.bin b/boards/px4/fmu-v6u/extras/px4_fmu-v6u_bootloader.bin index 2fd7d0d592dfdfce849a84954a0fa3ee7c0fdb22..60bbe67ae126da13d9030f133dd1faf3b47b2fe3 100755 GIT binary patch delta 25 gcmZp;#ME$!X+!BUE;B<*Gb3YDLnGtO^~)NW0DG7S-v9sr delta 25 gcmZp;#ME$!X+!BUE+bPzQ&Ynv<5ZK)^~)NW0De6QIsgCw diff --git a/boards/px4/fmu-v6x/extras/px4_fmu-v6x_bootloader.bin b/boards/px4/fmu-v6x/extras/px4_fmu-v6x_bootloader.bin index 4e40c12eafef8e8c4e69b99ecaa083d639785ae1..ecad9c2da1b48cd4236116e9b50905951e3b6946 100755 GIT binary patch delta 25 hcmZ4UmTApfrVU>=aG4oeni(0J8X6gI{=Z=@D*%*^3a|hG delta 25 hcmZ4UmTApfrVU>=a2c5znwlCW8K;_T{=Z=@D*%@>3kv`M diff --git a/boards/px4/fmu-v6xrt/extras/px4_fmu-v6xrt_bootloader.bin b/boards/px4/fmu-v6xrt/extras/px4_fmu-v6xrt_bootloader.bin index a90fd47f8003c8a6d935f5497c53fd7e23e6cef9..42e7c4b9d036cebc3eeeca11975f8268780c4923 100755 GIT binary patch delta 30033 zcmeFZX?Rpc)&N{}@9iZENrwcIbOO2Eoj_LTB!B@#I^D_51|%#hi%Un)>3~W=Mxrv) z&7y+n2wWUlTo6z}MCd@2fFY5^ah>UAnSn%Jq6n=C=xq|Xx7Yif>Y&cIJ={qyB{ zD!2AJb?VfqQ|FxOJufJByr4L!X6-E{$oRh)?EjmC!`Sx!)!7?c?EkyyH~#)OE zEB`3jYF-N^=~Y+|<@B2L|0=N$6s1B@kBo$60W2){Az`84%pze?puMm5)%L!{uc{2E zqz#i#Nt-ACmO}|v9~P7n7Jh+%e3X#n@0gs)A{H5uI+N94h@(taZNkPBdLW%rijB{; zE^S3Q$J-HGE1*&(zbG?d$mQ1kUUlpfKQsSCIZ<6GPuqorC-{w-so2Wz%hcgo{@ctn zT+08PnWNqOM_plrbV*{mFa1mzn1hWKyfLfN{x=TgO?AIy-pn;zZ1%6ZIm3zlRNo0N zi&;PR#`>vXX%8K@*;Lz;Ua5;c9*}Nl_+J*)fuUC*-=Yktyj#uD7t?!bTIrRI4k2UZ zRe%J-qVYUP45s>IZz zH2s){MhtVFGa zs8;!Z2>2-1By4iL(;JHc;0gdWj7PAs&Vbmb3M3|&dT?o6fEL!8)c`Wav{x>n&a5?~ zn_oLDToix{H3d~blTg-!%i;nk{9ZY!83DJDI`dvRvfn)BP;5aqhn7`oOs`Bi-9Ie zm4Udv^>+{qG*L42%zAUuMe3gVvM;q<58_HZqquBN;Zbr|uBC9&wVLw1XIgtH^@85m zI9#&J!*M+xmfP$xac+-`d(J~mtS>9_7`Z49A(Cjbr?CRHBlzP>veWTY{@(1rByW+F zl~{N!@_&=0sBHTQwvq4(|8sT$E;*E(^BJ}`wj7^wyyl#Qa<-XG!iOu*Nt*Fp%`tf< z;k}hZVeiHS&q<9X7nQTxG1-&C)c|~jq#*e}Gw7^2D|N7Dfuc^rSNnusz?Ak;?UQEm zeN6iVDS>o@S#T_k#Ot*S%|a5TeMGx(1`3|vX|LKjCEBL%?|#JG@0by7bxSDox7244 zN4o9R3D&a`nlYpw-G_vSR`xb;mVRM*vq_k}@^s&4#haxYk<|2+<^7KGS8B2ZNBK#p zkMyZ=pFIkIHVf&V?+$^aJ z5#Vn!r{b;5^a9B=5{4u~*qn;A%MJM4);^+7|`FEAftUe(%7M+pmiU9k%Xs1P> z=yOt1B*s82B@$CZEIks_&=t_4u88l*&n}xd?cb6KIyDt-Gy7csmNZ3M0HBd8$-rZ( z$QO8%NhB+VJk4#^f5cVa$ctq+fm>=A&&C?j&jJK z@#?iKfz7I}fx6`isa7bQ&w#e9L1+0MwT?uta2Ip5e;D` zfM4YNfxpF=N5&;wYe z8JI1HzJLzV{DJJ`Ko-OyO+i{u7I)Jf$PLv{@@S%Eh=tUIFk?A@_`dJoux^+IP>Mf? zSQ>P%f$sbKKnw%jC;rj%XBlja4_(n8-65& z=+r!|Ye;s#JH95qJ07SJQ4sW$;Y8nOMYw1b?Wb-=*BlDm>^sps(}LI-tGZ29)KD04d|@1n_<42*O~)@b=l3Y%5}^gN<#l3yQ8o=YvV-gg&8rO-n47mK}fL@=r)e z7?PZt9G4cy#_4nNM;FD7nQ%{OSw&n`&CIx&(8`W9ZTcF-8mxYg4j|P5q`I2h9wpoM zlg1>APqq)Q`PCE6A)We8&O7bV9M*}DN9p?EKdtk6hSps2#Idq?zihD0Q~xJYKaRZy zU##;-YLfai)E`vyg=Yx+GXz;QLG4_Ho}lY^1U;=Dl-ZBa;os`A;(1-IRe! z-bg11z|cO>fhREYBVipr8*d)u9E6UOEdc&V@^UG()P+sL1tJOvJQr{!jN?- zEBhTwARUS0ezasG@G(srS&@%6Om>U43u0hn?2GlRr=>;@nZv9+1x}+Hz z%WUg58_ErKMlj&`%A{$@m;$_fY)7j>P|&sg&o-Wd6cSSHK9Wr`3<66JWX4DG4E+d% zW6fAi8v*Q(Cg}GTu!$ozkZ@c2tryGhyw5_1PnE-0G0`uum;i(`mmnt>;#TT z0+p@9fnD&M$4t!9M^&LsX!~k2J_~H60&l|G*PH2!Xge-O{7nyrFXs9FF)!N*8jv1n zee_u=sleQiU{fU({B{*;tRUqAY#m1dC8(GaebWk0^nFP&V?czzr4TX{q^5?$env!o z#cf=|^{AAvix!J#@c5f&NaK9{yUm}My!G>XrqHy)Hlhm0skv#Cc#TY4&iV_^Do zX~(3tpQKms0tz5=MIcaZ7?i+u^r_elX37l{7}i(;gkFFF`8$TeVhp?Kk*^;zmc(M5 z%ugC$s(c3++7X#wGkzgH&i^`oWb~=N)%8YB7H7#kJ3$*MpDXjG3Axz8FPcz;=klLS zsI4gq#p+{fr~nY@ZMm^n(y^<|Q7*c7C016dYSuM1-{KdSwA0+yI^cHgEBcXfGX&&- zyvL>VW_({5$zd(9J zB%Q)foTN+m6Qo~`q^aPHq1dS6OD83!6BH<_XjV~uR?41)gsD(#ZKT#u0sf6iDgU<$ z#X-2+CXiwN8Q@)$*r;K_aD)D=TfRD zsNNgYb3>~X5W5DkAyrCQ-wq*;}Q^c+rH6=iys_4>A@&u=^$<G)P~%H~9;b(R zW)=E75>EJk?MqnwYoBJ-uYHP@u!|jMnyC$4&4@o{im@N`lhF_hqEf+Gsbtt$>F!C? zMw++4r12)SIldYRZ}|~BsCqE;yw#s1P-u`V3VM%+^u|cvj>yFK>tbQOv;8Q)zY|wS zSN#fSMtur4j!DMGItU9Ptc36>1RsP1D65(P|L%gICM*kBO7_CT)>M(SO{EH*y zsm{Tbv<=vTybAG7zbxdch>l7#RkNdRGpWyry?QCuh@>* zG1X%uh#3C=h6omKM4Jk#a$%~m{_|4)r1OA`^MH)=(%pjq8PMZMf(+ik>7b4u&LBW7 zto|+E6`DDpZU=1W02{yf-h*Tcq=rMv<9ifRLm&m}5TV=0LMj1LsgSzp`<`OX$3ZF? zQfGWWVCH-@q>>=@wQm=sRFEPVKjr%aA&t5?nD{&&YCo8YjoSe&130Cyk?%HVPa!BA zR81r^^`r!jzO}G1onwkKZClK+pK2tsn}EZsVU5+3wgMuzM7E^f2cj6!E3oa*t9<>$ zrU(C`IDM$jl1*tlEXe4Bpl+drj1UpIkfd&by%^;0-nM$UJGBvaquhYIu|ip+YDsIN zOS@F`c{m?GK*B2i{qnIhqJ$Z;(IkuS_+s;KyHNqtMWp9OQ&=>$H%7*lvAQK%mXBxk}O`9@6jnMqlB|zB*aTd7$RYSl&Cgj@jtEnC~oMZ9tkAEHu*YmJ6$F0+{+TJ z%Y$#1G`I%oRl3rfL8o0cch$C4ovXB~EjKf%Z7V53 zFHL~j6^IgsMPjvx3`7Y-k09R3rQ&w}Ypysg9A;{0D^s)DiVP>=;)2?b49CXP709@e zPpz1oV->0PsxV_HwierPUd$z<&4Fm)vGCZM6l-0p z=_aKcQz?t9!o{|E=(@*rGeLLTQ*2|bS(WeDk+2|uvirMs+4Pn38XmS%LS~pqPo;t3 z@PAEUmrbG9E=Bsx8m*N!tF9)-iG`vdTN9HFk-4C=9T%j44Jtt2 z%NXJ+N%if}y`s}}^Qi7q4-!7+pR3GBnk5He$0rTWWDi47XJF%>EBTKqho(t@j}Ia1 zQXMkxtw%;Y7a0>*XxOyk|+bU#yI+9yj zm4-L+4^|nd)@puL)jb8R)r2x>4tB^Yhkg|>Uj}$RQ!R@^XdFjmeG2y>ENqJg7@!>j1(k50+FbIF!w~<>nUwlZ%BIG@%<8B-oC$<19Qr z$23#Y9Rx8X?wA+F8{PkukV$U7YW+&GqdL+6Z@=CAretL2aP#YF_R4w+>ZE*>YCB=Wic8TiGcv-x;Y#jB>17imRED|qH(T>LYK*;vQ}(XG6db!suC`~5+SOXy zuUV4RjmMOgGw#KL66JTBZsL@CrA&mfuelf@Hw@;DMar_b%-7G>_D3zz0-zrRP_H_A zk5{ce#4(dPB($TFV}v1LhC5hR#o;k^km?D|D!Wjwb|bc0Vq%Zk<~2NIrTMO@i3R=; zNYPtaF3O9e7~x-`DP>n+y0I)alBsH1fE3mYkOC!a;?t&O;D`8$(?CIrkol^i9D$XyGaUPoCOHU#o3tt>y^B zc-K$3KN9|N47JaXl&!L9TT3IP^t%7#dZ1Gp=V7-+cgr(Sv-y~V|Gsue^1}9?04szg z5uJvk^&Sw1Wbx1Zpt{uLd_QoDf?wTaHbk$1guElD{Y`#S-Cc1xu!m)Fp-do>ef+Ar zqO^@c#tNt57;)_8YLIY4YSGO-}rykjm59PK$jBA~(&1CB!5G3PFU4(3I1o_+< z>4OFZ>slG_ECrz?6+d%ER&0MDyOo8h(88|)e$9-`n32Ayrl><@Mq1dzADW>{eLdLd zRO@qKsUJYHNJ+@Ra=R8#LJogp#`r~HkOqG6Alt8=88vCPE6y2}w7>@#Sll{@{S9KK zL!>o3EG&K{1H8`>S3n{;nRd<8H|B;4m4&^XTJ7u}nxF7{(KEPg8UFW;LoWUrhJsLY20`5c%^apY+G zg>SugrfgydT{+2y*TqjuuY( z{~(56U@D{^0N?WbLA7&@Efe}0r5g-=RmdnSdrZQ#T7in%!;uy4;GetCFmAISk5!M0 zDfk)qRAh3if9plla&kSxr74D-o6zd8Wjig;;ylVd2H=OuoV)MtLH`1FXLMpPP18aG zKkWVt{0=|q{^aQ(UKuFRm!@zE;T=C**bGV?W);GAKQib!rH+F5Yj8^;lI#NjZX;~L zlva~29>6>lc4U#Y%JI#AGOd-!p0YTJfA{{8csc*={k8ZBe%S203YQ1_JlmnArbXkV z?W#Q5H4Zj?SS$|%YVNR3EIbnWv6-Mw)8^!#pPiLFBAmDu7pFBRI*@^0@O3k}0IJ)* z;6Iz4m7xyn*W#kV&3XsYm#(1}V8IX?KrGo~-MnH>4nD|_o--t7uGD50-By+Y+NhnA zHoZc67t$t3zY=0Nb!(R{p_}oV6li4Pw2@B%R~S%LQe<|2%!aN4#xBr&-<)D><44YY9-rd(&&{hiB{SShFpta9<2xR3 zs=X<&k47$|gf;S`)~9T{tcPq@th+pQ0Nv+7hTGtT9@noUi$coMy8)<0>hkPCnQ=2rdU26D3rGlIpj`QdRy4 zTeVas%az@l0^rWzd*|g)H^cld)Ack6{`|xTCfemNVy)KS)+L2YOt_^CZX)Z?I!bpOj#Y7Kum@L_%)qJU%W>b z1@+>B>YABSp@!}~MW;POZb(SreEG{u+Nkluzrubv)BXevlOiWIZD%-b2AxY^oD>;E z2r$(%q+$&vxL^|)mTTG^k-Ge-2U7-J2&C7fH7W9#i(zpCKl8!bWS6hSrw1|Ps>@`) z62Us*L~rn|4`xxp5a0cv72EmJhjQ@8{Gx~E+g}UicN@84IOn(8W~AWrskXw_o#v$P zQf)b{yS0f`*F7m*3@3Qj+NiRDSX^}uocilRnr?!g!QESJZ<%-YVrq9U#k|wY;H}mh zZbcQ5YnOyRvO4LqJ2 z^I|WkfoobM5Mc6+oeRvA@N19{KRhwH8gJ*#>Pw)h*v1D0Z#1}OBow1fe4RA~|C4X9 zX61bDgTurMit(jJU^7ASxR0*M=H^-+v6Aa*BLHDC$0IN$^PgDfu*G4vl?7)F4G{^C zYTAszc-9?sNt+SQLV^(DjrAjHXZ!KqbC3n1dvM31*-qW#c*A~4qrqh%vHJJ2w?UOe zR}IvAI}`<{IBH+_2r_=XNX)cg? zkT(W}MVrLmv!IUp#>a11V9foOyxe0FkO?T<58gaLQNMyH8;?95g4vYdGeEQ~DnW&h z@jVN)c6Ey@(q(dx&1No{ZoUUnSx6LQ*cd_vQn&pC%cKF^$YPItPTFlu(WZdAfu?Pv zv;*>Exnidp%6^eGPI8XikmoO++c3DlaWrzxt=F^>iAol~jkH{C&UBrV_OJ_ESA!SR zY3(`bLzF$G{iK&wq?F~Pgv2E2l(eS~su-b&#S&oIp_|h%{)-o9zawz5b9~KX$=<_6J zEac#OunXn2!eJ-Dijj%Rle;GarRpt<8E%`^C2cXzbPk}W4EzrW=5PB53~vBj8=!1p z&Bs9*p^=|R*+^-#QPZZVQdYtRS6CdPtC)xagccfLkXX<%1YsbRf$w>21b&rI_|tg% z<`98kfdLz5Lol`zH9R9E%Y-w@*EKEb8qoh_f^wv4etkTZt7C!G(`T+oiQ#G%o;7u;GS9DWqVgC}=-&k@z>ruOo{2S6zgj+TUZUWj z)voB}D{Tp7LM)DP4;=Gwf*Qw=n4IjcDZ8TXcPTPh!kpb&(d0;ogAPWIi1XvB% z*a9SQ^97v-I!@>NY`TI&az+7l(R6d8?wW_W^+ThvOcwV7Itd>j?YaR#tQ*QUwgkoJ z`O=1DCM0@8`~wXsc3B!R%>+_RR^^DPlpsk+XMi(hgl~*>nH7)82GsyNmJ+HYQ@-dP zK2?)Bd>RW^yj;i+iQmg?zQUWXxaCHAmIG~JR!IDhoH8XI)=w@3Z9v8l zEIYwNdXmc2*rMc8VYx5)P3ivaZ=f!>XkDtG;c?- z)wI`S*zh!ctJ{!jC714R;7-%nhKtjS*u4LMO1>X#*S9=m?BDQBU{SZQPD@jwGqR{| z)6ElwQPBIC5Ypo&Rn01^xp7tF)~D&F?TGYGde=rRe{u=mW%P$sa{395zCWZ#KJ3%+B71WKHPFCn5|H=~v zypVT3QGoB`FF#Qnb34F}x#F2H0vlKG!=BXHy90S#azwcu5<3G1E(zj8szTzqKru&D z;E53bXW&D#>cXCK#YLjk0%My+7WcGI56SkXR1aeI%UazkM<uctEN@M_UDH+re$66pOe-aAF+Y0WhGq6 zz_`Fwl|t!%{JR!ThUr^i`fmQg#=BDcd@DicR_Ow9V_BKy$LKLI^)XO$FTcOBVB97@ z(&bb#Lb@LmUH&{<2^Vu{NKLA(h_i4i;cbZ){^8HIrGUyd&6Z}{*NRw`u))V`mT2va zZ@P!!j(CRDeCKHc>_W4!%?t92yWFg769iHMr*P zhVLE-`yu2*y`SLw=wf6f`X8}{wkxjV{!(l*RTLNuSTbO_ws#x4aL5r6;E!qj?DC60|KZ?G^C zlq&@MUytwqpAi4fQiGld5alUsliK;A8M#Z^@EBRt`EPqlTB4_9*%-ki@jXi?;In+z zQxk!U`y_tBQ}@KUq_B7nG%AcRp5On}$f4^11q6kSEvpwPxj|eKXK;SDp6_|e1#PBC z{PAU@AW|&x!m^UYAK`o^*HGk4ZM{!79B{+%6aSn;dBXf-e;zgYUtz;y+Ix=DT29$=@UWNN>CES{V;t~GrpLJ2=!RSEh zoj4Tw^He1b13E#7Km_=g+$<;w_AM6aMe0;gNP%qb~k~5{m6cE$fAzP4TBH3vw zQSX|>t=1H-(+2z+>xB-g(;5(?`NF0|yAu3#4ko06*V(~@NDNH18sJ69NSwbd;0L6f z%5aKa(~xZ7Xz$4&gGa`Y#jo1Y7(fMV=Nm(iEjcpd`n|TjYTK9lh_g;p}Ah54I>>!ZM_b z2Y*ldiiEhSsq4sEbgoUaWpgvMsUZ0@gkeqoI^dP{%5ju^9U4VLBMO?Vz*jxwWFad_ zRtx+(ESIG>9O+p~P7y%sE=p@nDBtAL)lTJ9y(Uf5SXD2VjNpU|i1&w%*nADREFjJZ zJ!kVb?Bo?I^6c3h220sEP;3wcC|~$DFw{h_oXFzS@<=Dr6Q!dp8bc-ID-s~Az<11?#7UEbqVfIMhe zR!|ey{d=h$il;*HTG{AS8VLRj%d-A!ohQRO>tUVMA>EyIrrX%6cf2MP5Wfq`;`K17 z-wi2MhGm~gD+*!F**ewt=Qc}LxJO-b5%(Qff7UI{Dl`a!#nNM%{~5$x&?ctZuIZgroys4qMw3v;L%&ia)y384KCV+ zL2(M$A<$B!O9!lS0p^yYp5+1{Z=_bea|<;F#MZ#alGVs~9iaF!^uImd08UizLC*Qe za@hs&JDF7&4_+y=OAS`T0&JLXoxdO;z6HMG9fcObk$4)uYACNPgsTE9PZKOlWSF7$ znf63`lS*}d7x-E=rEMORd&d1pACuT^BispPf9;~d#B|!zqk?j9 z>-%&%b)Gn1cH2X}G<6;mdpo$*&{5=qr-p|XdEj2w2v^uJDDs~T)%MJxHN|RpVvz^d zp@;qJ1X)}h!sDX6RFrzuHTQn-$-;v#s7}M;e|Ubez+oc1F9?&^Vu(E)-Yji2J~<86 zmwwNiqFw{3&C-73;y(Tn$6z~I)_t+1?fS#6BQp3By();|&PK z5VBSed>@4Gi+93C_#S|;f8{`U4(gGmo~u%xr$#Yug_1fyAOrvR&QI?q8Wo&vzuQG+ z8(b(`a329d`G)&spNTHw^i>%A#3?vmbdEI=Ym~+N0$^BOHiU4mm87E!D*G+rBcw|L z6c_mu;Qwg9=b8z&`CUPj{iVzD*CH+fdZ8nyly1X7FU65w7}CqeE>97swpZIoM2H;1lMrVK;RCc(w!MGe0W$b()zs?H0=_{%Hfya~pyxfn(oXxgz_`oCMQ&^$ z?U%}8|ECF&OYRQouiX$jKJXA06gv_d1vnv)2~KJai^%HT;>*|Eg(vZUS(Ag4`1jX< zkk5a+rZE1SR#QnPOV!|r?RPvs==tYUzLOCcVRqiy2|~rrrNh9N(7*_cyM9}iO~>??F5Un)cag2Z?Ymwh*umi*IkG&h`#WmZY0#%%llr;!9~1bZI&Y1 zdBt{?uU)Id62D|^V&Zy9-P)@=46nCj@!uegN^LLkTh|ujXZUZ|X2dthO1SoQxmFA( z#QQWKSZe?Wl#F$g@hbk|b*b!pXz@Bs`Yo7nVhi3Vi&`+Gq&V?5qzi~wL;RL?`S>({ zdR;lr=VM;dWgU)S1`G2fwKK^GxTp+z%3$$SEqDVK9+2=B(BbjZU-IOXv{(Q!3Y)t6 zV)E4hRhYu5YE;!7DYXKkOT7sD#0fzbo==qU_3MWv{}lZ8XGDREt$gWcgm+ZH;6c>> zE&tm3CCR&kg-$%4${EwXSa=?TF#xMMb=wd8u$L_v$Oexs1dND@ps^zMFuajyS$A-W z6LS<;reEe)zMN)%D=c_aEoc)0X*U6cdPbrTf)7T3xCINfuY>8gWUoZUCLij-$Zg z;2q@Zqu#7|wF?(he4dRs&){)ib6YC1zUL*pV_P~Yr8aq8Fc)>SzJe>`Cg)GNaMYU@ ze~&8>zHI#6uA^Q<{AAY$UZb7vYL3dQz0j?g)=mY~C1rwxp#rMARNY6t1@U=M(HP(B zE)y_AZBLZ&K8hzm{M-G3x16T(mR^YVve9MzXx792m;6cn4!gR&R#2*sdLNB{*uU0m z5>`2IVOhVU?8|1PU)^0MP)wP?Fc&;!f|@xG|Lq#)jOXwzWN$rt)cb6FE)2LVekA-~ z7_W1~dx{0So6Gvy1s$HF-rV?jcei4W#7v~l8+xuZee6Mb@3#|xGq{J%Wx`r!Khzo( z-wCyl_rcXL?6TdE^LTuedzYfJ9l%`hTaRej>ri5gkFvY1zZaopWH85qm!POIo@&p8 zfk_Tpw$}53_feSd-!2~Y&W9z~vocz^OwY_S316=KntQWmp2Tb?XOy~qD@U+U$tAUy zf+wb22!4_w2e;+>qu$4W>HhUVGza~a#p|NHs;KxJ^&WeUpo+g?q189TnB9R;EZe zt)ca9Fc+DGBdhKyyU0=7PhG1O3ZhPcl#&V6l9D^II)l0QejZV zo@?cp?kKN3-WWk(o{dx@)oVF=JIb5U34lHGg%{Bu^hQw(kGGS$%+_t@yV}+JY6YYE zYzi+a98aaME2m*org#3RRD#qZPo~|YB0bV?eN`UgepAXaj?H5)C?S?W+G&;cfmFbC!2 z2%0Emr^#FesruehoB@!h!d_Oo2BaR#a zN0*gn03USRJnSgDsiA-a_C@tjlqQ#U=LiW=(4$`qYmS7E91LJ-VcB5Go|r;cXoV+9l9!qgJ3b;*&LNy zaUm+N95e;AFfFSL{)Uv5jeAEC;4ZO;BWPpU3$f=c1LqZ^DR%NFqDZl zWcb%au%(D#iz3*f@?Gi=7ka4eX-)U#MY}0@9z^jLo7SeqgT_rw2tJ=%Up zEq22@q;9IXtNCG1=}jf2?V;i)_s>1h2YnDufT545UL_oO$IQ37?r;g<8hyH@090!w+CL^>?l719!1KsDaY{k;K*cM)I8vUcV|CE)!zt|rx*hhNFs*#J2_(la^pEY zXv8J)OF1g{FgGz$E9yIA(e84Eg!7*2RnyncL`)2;33J1)yNbM?`&C81f+xv|O}yzf z_D>0JUC;MR6-J|u9Ml0(1Meh{r6RqNo4e%hC6ho)4MO#+hkr4}cz@COssE5e{D$Y? zFCEXleZ#Wo@GsnRk^D>Ki2vU6_6-x{eIBX%;CWM(+7O?G*|%@p&AVS4pJ1$^dq1c7 z8|XRXFRGZgZ{+f6e^0aT*l}6fad7%|O^hVg$Y39(*Kue=R~iPEYXL{mO_yeH^EkAn z3g&5$k=GbIhpXcdc=<-_kwGotuO%^AUd65Fu6YvgjJWZJ<~jBk)pGz#1U{w<`RU-n zUn*iAEyEMl;|~F!z3$%Sk!86E!moCO#*DbNDAs};-FH26vea?`n5zcD2Et?=pYQ(b zD>NcnRpTLePRQT*dk%K-$*)g@=g5yY1f9P$95$=m*}x%wlCC#2G%U~(xi@d&8|D%2 zacM=IjDl`g!<*+oF%LEijXoU-NIiUTpt3BH9l){8zQABliE4 z*2!R-^^5K>xnhigXIb)CS@eOi95@QPI{%cEUU&*#yo0lx#CX@BQ_@;^Ay@}-7sSui z4ftJF9$|Bcj}dX0dKBD9{Nmp57-K;EOOP1k*+O`LKm7^5cFRaRvGo!I#uTE;YbULU zu9@Y6VlT`9b!pnbmq8*|mVQtZT!q-ndB3{e1$%^Fd@@Yx2gUSb@K^#ab#gJ*tBrW2 z#VU)hf>o979GKfzM~G>jU=&;j;nmv}c&ahj1utNg##k8W6F)s%)hUag@KIYw+Ka=u z*s!XxZQLDDz&Bqe4H&Q<^)88nVfA6dONn5n`%i-C!Fh3Rf*Lh4tRethu?EFc0Js8% zCU2Kl9D&DitB4Yj^f!Qze6TI}MLE=Ao8K@@`+)cE#$RMchqz{`A(n?7D5pcy%khg@7+{j~W4&GQW5tbkc^4$!m%IFa!X>0K5vpv*smpB1gN@n{W}zm)t2@SlsI+Fp<|HB=-=%X#1qpFJKbg5Xc0- z)lo3PaiNZeh_~PNLP{Ir`?u$pUdWBuAxopD=GiQ*(Nm(Q#nfJw@*Rg^4%m=qCGHKg z;D854eAZIlcVHDn@pa%{Bn^=~9A{&AcV7W033qadxshroRUfeN~7DOE** zSz89pRy4((J)IuER*@oJBp}Wng3!(iEerb zW#4v#8$)y*wAvG9h9`CPHi3sTo_C1kgm~RMm$k2i-|&!&JzV%IkT+dT9xj-m)DY&i zJ4eRXqJsZOXhUHq$$Ko!*X`8f+x$~I3zZXXyLzK&{)3%m_73n9M>>EJT$qmDi6=q) za1iNB0QMAR0_@`bkTSwG6C5P()X_qnok654fjk#{jqv>@XaEs(0M|r|0`EFtgQVmQ z?0urA8XMl#G!Z;VpkK7B5w;Rz3W(?VCA%{4=|dZLy^a%n!Cg&xzt;$WNqGFb(-WG5 zh9;b+ya=1F(Fn8YIJEuU*KuL#Li%O%0gR4)xOa7?I0p{{}xk4I&8e8!_`_R+ zvvLDesY8*}c0ZJa#B2PO_jQ&Mm<*v{2WVJ)Vzf+^^ft~X3PBCP&q6E+-fsbMq2C6F z$YS4h51EUmMHWxW@cafm0K?)8=?|}ZBs_P7?C_*1NKgXfoez9;klU~hp4=|w!Rl7q zzYjR7Py7Pj3xW1{B{7Hua>W8*psLQWSRf%AlMSk>>^^X_B(8DT@Tk?WvKLN@Pr)~9 z9RKYHsdxwP`CwR-1=>V)hJfM+?Mog`m~B-AG#YptxSN82lG}>X(!n*aHpH9vjZ6O= z+!>|-OCWm3q1@Vo$f<2TsLKOrszdzdeUE2=c-+~)k(%& z_-U?0-u~g6!i{C0#XwJ}jjbp8G;4%lYy9^T1{7(f#!R;Xn50QQ9EizrU>b zEcnA8JQU>}6WOw{l43aB$pRG}2we7Dgrl+7nQpD)zLeO~fH+TLVY@8j7kxApzs0wH z^bCHMFFr6Hf5bm=;CV_L;QJ3uz#aVPgBHVEeh;jtf^otBAq=?kw|@>$ku&dwgM+xC zuw38suN|zR5<~nC2le<0uW(KUPvn`-y+bZW+=zDA)J|Dk2lR(BL*l>qgyx^MPls&Q zL6x_x2jM{V10N?|1hKFS9`o@@ho&UV_ibB;i?*$l#b$5-DQWBHmmC^KXLxC#)99d28@k9ag-0v2hPa(MH+|{Y{4?I zw@2mkzZ}X;{CAk~#v-41CbBh%kJV`&G;t+2B;<`&l15XYJ0jIgfDVnVBKd_g{!yBKtTk5cB;8Dza@Nj@5!zOtq^WMXw6HbR*`1+P1_SsMaXK9ziixTix85cl?Y>xDTvH)l8 z&%)RQ7gEd6sfZmqg&L6y54Gr6@aAnbSm#@%whY@>PF~Vy9U!G z{^9Vu3O3_FkM0gzW5r^A>ya$`g*NhZygKr5Eso>4bQ?J!x^xvV+I!>y!yV^11vo(Y z#jkzYCb*$Xc!SG{_xQw-A!6nAiCy5%uWs$rUGa=?;$dnyFD20qn=9)X9~cYQLND;D zCvp*j<97jh2FSU(B&P1NT{^X)w&&`zUGOM(NN--M3kK zK!Xe!IlC65Tp)Ymr0)wS+uM-$z{IgMd}?>p8@u`-vmSI2pcowG5t`Z_9U*H|Aq~U_-!+dCzNx^u2&=0D=9^f6 zjpHEHL)Za}Ht~G(2v9&=_(LT5}D83ZV?xwuSv_XiE znOja@T%cP73)&uf$E#KZMO7FsI(J`G;dAyz-Azv+NKQfVf~;;`qU-hCC#m1~x;*v* zb7n4=6Dj$(JSOr@892yag~nh5iHaufJ)II`Y|wV9YHU;5(a3wHsKzdp3IwcK?P_?- zN0-ej?+{*a95L^MJoT9^=D0JvdQl9`6}Qgg#&8Ap?zhc>GhJ!NxUX#b)@!;Ci8eAu z@Vso>Y>jn(W&6Rp#r$qBtuS1Sww=+&=SExcg@A6Wr=~2=8fzme_Q$ON0wNZJ6w6l- zBUAZzNa0m8aOce%>*|zZ+2~#s+646R+L9HZC5QqG^dg%DgwI^7eGzF6%419?lIF%A zJe`tSv(cL1Bn`i^=GxviYs+%2!!HK3dsE``_SKPJ2-&e@wkOwCZLP4W1gx59u~^Bl z+e7643*b^axqs1typ6W*jRX(!gQ&&tukZRN?oUCj5Q7(E|cSjJU9{f!nV}uT5#&Y+i0krB*BA8 z*jp3BprQeiCl4%9LrUvZkP{{Gp&*V(i6L<`2*k=!zdh4YJLv{XYXQ7+k;Ey%pm>zu z-ZqRP{!0ru!-15MRwIL*Kf_JY$@hS)!8YkWg$2G4yJ}Cv>PiG6AH#|hm z;{XNEP|gg*KR3)ja6D!F)Nqu6j=Y9U>7Lmzv6bwdMq60i3Ub{~oi{xifcYsn6X8Jy z%y&>H%x{bl@_2s#@j?)AE+5y;egX#Q@B9`tXA?jPL0aD@qwLdNOxbSGub%V}t&q>9 z;`*nE z0^uW+wSWanILu7dg~!70t;R3~x7;8-um&snF*KrRh?+*6fr`P4oH!3a?xgM;`#WtL=M^-l61Pbee*i$QJT21{;JaqBL4#!Io3kRlZs zc3DXuR+!-|fPt#HVC^Kox&cRYH7d^Y@S@?z3O#1Ja zrRzJ(dQjOE=&GD8oL(oCaQdYPBKZ;7Y%(;q%BF)mh=HkOBV_Po2G4e6r_O9 z6*W-7R768tw18|<2rI0(TNyOS<62a%D66)`3e`nWk%#g~5ZP)$S{}xAQPWD9A#IZT zJ4xMj_q*SBZ@%y3KQrfl&YU@Op8v;hnDm;uK9h+3l5}n}8pedrB$auiM9fq}z3xyv zhoJ>Bh&Q2x~qeeEUcL z3NH_y&p$$V?We#DLijVn(4&NJ0qsVp#qs_Bk?z-d{2#|Q{wLg6hBE#Xfc(j;T`S+t zhCjJb-Nj(M;2#rErXTK2TFZDYhIr!ETGKf_>5X2?(C*~XLxv_2PP+^yAAb+9)H3-c z52v-jn2^&}Pyab|?DeE(^CoUQ;Ccg`R@tcB6T}KPAEpuRYaW`-GJhwOd3S?+J9CGY zLmAlFKy_@)muXPFJoP4`eXN2bKY;o$GMYaKT_@C=5`1)3-YVcX>fU7krQfsvs#lE} z9Z)u9GIS}VH^>FND1&ikLVZGeIoe2qwWK$Gx?HAJ?qO=Kx1Kj`7>^9O{ z*KkStOY?oE7maH7aqvzEJz8}`Hh8nk-Zi4t6ehV@U8&^1^{{$o=G;LsHh^{llZL~+ z^BcIWbUb~DY@_IMUo(~NLogXWgvF5cb1aBJ)zn*zSr>-M0jMoTY%m%!ypbs084s(? z07NCk%QukhW|Ogt^*z>iiiPKoB&4xkuwZhg<~?Lu>Ry>z;!--FpE1+&ar-7yf^hIi zW_sZ)NR!yJc-+c8Fh+$aj25o@UM1&pJ6q=p!6R8V<(^Ygiam&h1A7j&yzN^aWjW(l zHUd*nr`V$qg5pjT!r(n-X9fCms6Zdt6ZDojm0{E+4nvBUahGi=;m#y}Je~;qDplAX=o*!)> zlz`M0f6E5RNFeN_wiMcmkuG}Nj zh8Y3_4{JhNjX6Pa(LvUOM#x9xMY|_L>_jRd-UGB2qtyS5vD@W>VkLguzp}psF|}M+ zel4sQfv+>#hepUbmNn`zUa`I8!MUKLISp<>?8X z@w2NWP+RKdTwNsj%6wLcaFjAI`baU8I-| zEjMUKDwZ#-@T}n9p&-l??w5jJ5q2Ke%7T(`_;?{)RDM1_anvZxh@2@OGN1wRr$HG| zRu}d5_Vg89M?e;*2r@|85l44P{KL(W_;EBDFnCBRjMGAMyGgWx$ z#JZ$dwxt@}=DDOsb2An-2ZVypo}e>?U7sbzy8^)OG*z2MV7s+-8rwh!F(-@E*db2S zvYyspL2TUL^Qf_n!9!&$v;ztMrq*WDD`9*0z~_KQ;n8ZaCN#fiZ+ zsIVERtWVE{a0p7`uvR7B9y^0d{?Sfy0e5D1Nh&*=FrmD$cSt)b8SeNMdt?2%`WIIk zzUMMsE9b7hlM0Hcpdin^~&27zsV!LXYEXXDtFB&Svv2F`uozA zIi&YEu2C? zk0z(mJ+EFfNuE0^WKph`WslzlxSa4UjP8gGRnJ-!TNM4i2u*`Wt1os(j2X}3HCxIH z-FYpArr{>=5K+AD>yS2K)p6KGH1oGkI|$~C!Hm+~oL5d*^akl^Lh{~mQOysCj~|R5 z0?LxU>XK=?nMjR1f&X~&82&Y+8vhTHCBj?hMyN6Zg_@hXGU%2hdO7)09iG}3+;9^dwK;`iZtG*nQ%32NEpE@kDK*Cx0 zNQK3q-C?#^VBtO>9QpEDIv`Y@FBmysHLLe27uH%nkz$(AH$r#-Tu(E$<^AGpztD8P zDD{~WB-8-4=b3{kX<=P&IW`WW_?l1XI;pXR@8zAw{R+2;^fajq*nH)|6u1FTy~MRe zvVkrFl*)m~bJBsztoE>rIakY-Lb3uxskrLzDS(j=6>b5_*TKFbTbAD%@du-z(SdI zhzvqF__0ZMm#1|weaMdkZ1IfMNbrE??()lD35QQ*=N|XuZQNG2TT(TlgedJ!m(Ik^ zJg#L=@=f5y!QS`=dZTdev_*Cbj@M^W)kh&Sa7b(Tu#3g(9|(`0c~F)&AbfUaa@@WB zu!hrVOs`45$I|C-LXvB&Y+}D)a=p#5Y7?4HXQ=NC{DMtkmm1WPN60@tM)r+AQXg=I*v$|6y`JzZW&l-0 zKh=eXvJNJ&QB+`X6Y!b0?w6Dpgv@cpF#9sA&PmPYsr$}LTr<{C1l$`LAJM)GN6Y70 zGd9KfHVwqLZYig(J@WF~I)wDklWj@xA0L2@m>G&NP>N660q(>zkEgKYDr?iCM@P5L zd%$>S#wO^yDj7h>3&sqG>;hJna-D+~9D`7*nZO^ww?$eBG^=70o#em~&Dbj`D?gXi z=4T~NGs&{Kx^WuOzvepasca#S8(Jo|eEh6D4oWko7^AMBxDFoJ!rPx`WZc7Y;^{c# z!ZYBQwp&rWu08CR8x$7;22bcZpJ=-YT?HhlQTRqh2CN&ROM9QzaDsC4slTiCp89*# zBp+N~I8$*ugF%XDnQYb%T1S-jT5~wqb8|h16*D1eYYIA~)%Lj4ai6mA;&*cLu`X@q zdQgY7j#uf_S_|6Q27b@pR9rXPCcEs(Xcj+QSvVSPEpaezDibrtbmq9e)_diDdf3v|x*8RvD8ro(%xS)nh^H zv?JVyz_+b$UT=w>sn)(Atp>J~1^verQrP?nO&@~PivdMX6OqJ=fP?ahQh;fCSVAVt z<@9+Nc8NDtFVD;-Nwf91@k>ztXJAnMaRD9Yw#o{(8k4Qk1)`txy+Ph_NT%DGD%Txu zt+HyY$}YK%(^Oa^bt>z#*5g*|LB;Hg9=4)T%>F7giuR?TTXy4Swy_XwgPuSj)2-8P z2s=Ag*d(;sSW~)bh3kv-FM3GijDN@@N&Zq7(T+1Q!!6k;6(|=S6u%4Fu@#DpYO-Eg zPU3yKCDtyhTI+xjE6EJghd9s2wZZ{*##Y3XmId({GA70b$bDlkQO? zY9!v2{0%0RdJ{{Q$WHlIx-F%B1ICk^Vn2jsLGfsi1JobmW!gE~`PW%-BmXV$$AsY5BeVL&tY4*JCf@_%S(aZ28jtC421H3H?ab2em70t( zow6ON?RP*0c2nGl&A|OFi!8r06J3>AXI5@iL5pDY3yqzLbhNO$GbiCezh7i1VK>k? z@YNBtjnP7PXF_a+zlfPvhg2nH0=-b8*%HhM38;wS>Gq^9l6BqVgH8~>XfU<#iR**H zq6_n6_XmadE>y}2gZoq$Efgq*%fHD1z|;0`(y}0T&M@>Q4JBU70WW||7)Vq~dx3T= z3fkHKj3wDZ#@;1d{AMi87h*5XeMrG1@DSA$9k{)k#Q%n1$ zdtx6$3Ra;p=%IUsv@We`svqh$c!Ue4uJN`;L^Fj0$%xYoHL2QeiW>M7a8NB4)p1s~3fIRq)62CB1!gHL0-5(B$|K|oVrNek-kR2%#@E9GTdjgW0Y zo(j{SJX$Ei8a#;7vN+NQQIB`~`|BbU?th*C?S010Lhw3;pA=yz_W)NPQUUW4c)CHV zSn=`C@*=)yK@Di4%o``0P{bE5sNGf@m7+2=8f9mp#;u5nZ8yMh1STdGefZjd@P2n8 z{Y3bodnDZ_#9kgb?8JZ_P3fanCNE>PwEeFNROyF8>E$e2G~CcgrQBk)tiwl})YAf( zi}7$71=Fo5%@|X$ttPc*LCuAlK41&wA(!ZZFY!r=+=^|+ zGIurxB72S2Gz!<9w?36(O0uUDZzlF-S)dwUCN{J~+*$Z8fDZhT?jKsyZKIWthp)1d z?DEpT097U5l!l6MRVD!+Vb}Qc$QxOLTml!RD8fhh~|jqVw@Y=6y~xv;lV3W zk<2CKakQ)kVfmGWoS=9!m<$8$&}wj9Sfy5Sa{!(-k{PAM!tce@}1+?(!Bhppi9Or|67s5L}B3%b9!nqf; z81x3{WKaoo&u@j4tLeI%;s{AseFWeAVB4b^?x}D;;Q%Vb6=0(dt20%>B;mfR4-LEP z*1EJ}cgCzlNP#wd5CSrR{Ya&7=IR4B=dEL&RQ|Xdcpc*Nw~mBtUYLJ4vwdl1oe78= zv8XvXr*~Qp-VK~cRZAb-*=P}35=LDYcqlfp5p6@@9%)AtOvQEZvq;@gOX;QH<}G zgVWoU70hWD6Tig(SboEe6o(aKCV+Nexdg^JHykxVyhi;2;qGsFIKDjd?F+w2npxbY z@do8{Eegv^##Gl?>`~)8KUQdi#u3w%>`{nX2MtP4+4tcCF*OLsyK8t6P ztUf5b<}oJT5oj~YP4XVKy!WeW3>TvK!GPfN+*aI$Ds048#~wm84W(h)JxF&A(z%0F zAq&SBfbK8g>AkAW-al~qecbDUmP_8(C~nn*C}Z+^Qyg#|5dP2IHcLB3Z_TbBbz;a-L#2B{U^C zyKyinttlIA>Ia^9s0IsY3cja_`<`4U;GH+mxJDguzL~V?^yx}_JxE`1MOZ+_#|9In$WKw*DoPlL+~K< zEZjd{M^DO}+H9JdQ(L#NYU#r(mRZTdnq?2MgNH(wLZ>y0AE~abTU^5~JEvvSjZ@}6 zMfj3cgzp1Y)I;QgP>#Uvw0tGbe~&_emLkkSn1Zlk4dEMby=Q;yC>kfre00TQ)e9eg zVsY)*+M24dE3CD3HH#N68(VpA(dd#Dbx&BUAA6#1e_0M~qJ?+uApCs@;U_`u4ju>p z3%A%!_y=|ZcDZS==3gcJnU|f(dGwVex{vVNTTmy>;ka%bAKZT`kCw@z#urQ+UpVeJ z1%>0BBgW8z$&1erzWOwv>rWCs_!;yb2)hwBVpG2x;dO+?=Lvt&9nOnlZ_COvj_q-^ zTw-JdBH4w#`*)9_33Pl18`0PW{Ki_IShjfV|Lci+$I_c|vG!{L8%rESxay2G&?-eD zRHx?H`fz`f9lR8XTW$b=SVvVYG>@p|9yukXM6&)47Y zbk3PM%X6M{&U2nMd!AA3dq#0c$vR5Qk?Fsf9RJP1VQj~Lb@rxG$A1_7rvHEa|GOLT z|LgiI+a7wKwYBssH?VbkucIZo^=Wpb%dOvKDL9p5%dO9?+iV$mDi?BWEQiFWgIKKc zBXLc@!XokEpu4}}1$Y0-7vc??dbNF?eXxAT$`>dxEF);x9A zO8LCZ^ql{dGBAf4Ys{9#eU%s)v$~OZx8Tmx;W@$&d0E&hg!2k>wzR+NQzk#~EAtH! z3;s_#1b>1#zt-^_hm2;i#kt9n!PT5=4XnLpaed@tQC`YW=Q zavi^j&r%xDz*Wj1lJ``{-vomCc2BhfT|4L0aIg0%8FO#4+3np7 z^Fbv@bUD#T00W!2K|l@%T5h1x^_`n7)Ty=5{ZZ#S?czQfV-_%2vd;r`XT0GB%+YLs zzVV_N2Plz%d(LdK(#Ze>!JM2D98LfM%qanLOn`C>+(h3Lr}(^+pl_3N5Pi*nz8K`O z8KR)_<_rOSQ&z(aSDmBECslo=1>A8>-p_n&G98E;&7 zFV|W@K=9`V)&U5a1cb_jpfa$j+Cc^4t|6$ZJhxbr0LZKTc2hNX?rk5HpsRYdFA=-{ zjlh~-TmxXpM*)FevWlgnzdc%A3}B3c1xzr%)u)W#6QnjaRDZ_RaoSTEo;zKK`%B<9_{F!-apgR{!+v(LO3=Ss#OO`30|% z`_^mcp7%C$?cRI2hrK4Q-h04DB~PkSd&$1Z^CEX+4RQ+$3bJvQ@NmIX8TZO@wOCvd z`)`*OwH?2}nGzQX356wCdw62uN$hC1mHaAJYI)lC!94o<=Vi;vc3I3~TQlujW~Hz9 ztLYnWteRedq-eGM zO`De2i#W%ncej-%~JC(%`gn~ zEU^wa=c(=A%4pp0rH>$w^nbQ#?c@1j186=H?ah6y+vVR_0YG2a{AvHmvhDJfSZQ8! z^?U2yT}LR4A5D3nG0}9qA@H2wjdvx<_Uzp`-{t++gI@11J@VT=Qzck%mFO z%I58|vXqdODa}USI)LUGM5ongui$CXQC30QC-cIZ;&Rg>07#WqVOR4BE`q(&a(Wuc zF_6>5a!SZ$$8svbt?*-Ufw_pMMDy5PmVl>f)&)7exr_{-i$u2h_kqgnXJup}Lwyd< z(=uBMWtJAF)1;*^yQFw*F^tTnkCzqaHId!?O{R9nx$_Do89O z6D0f0#WMuW=sX8DEU2e-3u@K&k7Rop(j(CXYe4C4fekHIBC+tpVeBnGBT@2SZO<3c zt+4ne%#sb!P16G>%G6d{eUaJPODU=W_XIU%b|mHm%lKDdvyshFJ#eD>g`e|9HXmwK zkGG%q8em5lVtZk#qy8Xt{)NASuc)_*&aw(SEVCufV;Dd*qw6nAN8kDmR{OArrtV$U}KH8Vb%zP_XI}snB|}cc)x_a`Bz{hr9M9B`m})z;xK#Ay3^0A#(NEGcGT*w~_KZDck_0~4XcngOK#y~BfnQG*>0 z9cv%UZ-Wj;iOw2TJ-oe7ZOyQj*(chM{|w6}MdmN_`6w!PMDJ+AxGo_c_7w_ z_BhB|KvE(E6_6RREJ`U*wi!IivvCC}9%Vtc$9yfLR0Xu=A8=EK=}cpWXIQ~N=MYq6-g5x|Xqld%blS-3e@U4Ml+jKUI z-(c3jmdkMC-39i;L9u@*o8w+!EwCe&I@H*~*e=6hLy;UCjBGx#*%G;|g4DAYenDc| zu#C)%l&qAT6gF>UK~YMvV{~cR_=zc#DyF7PB@G*EGHi%d+Z$_!1MI^A_Tjc0-Z(ZY zJ?tK4^Ldd@3Hi6&SQqe8I@wF>Zg^F;pCDa=Zz-(k#kwGT@xvF%n`Ao+>7S5J$8bPM zILaG9=>G4h7zWk}yGoN%vuCBm@N&=BBhW{ENy5I;vG_TmyEM}gZ(9jeh>%Xb7^PHJ zre0&uT&(6>2ApLCNVXPGSq;lai0uEVseqcl*Q0G3{*St5Xp?MHwQ2cmo*F<83|F#K&!R_6;gG~hK6=XVP8$<=&Fz|Sz0nQceH}J8% z$kL=7lnuOL02vH+RR;m4!Ev+VRro+E!tsNTNc8?*zS-~slnFV%2-ma<08_OMBZIl1 ze%bGXef@iz0cWg_PoZppHe@i;_V;@2H|rUoo`VeLA{C*dUg+Eu>)hRc*9%D0!Es#a zXE=?^peutDazQS$sq_sZnxnBdh$qYo?WX!&kgIwKi68h`j^r9dC(zVGvC_%A;fB*8 z@oj&DXnBa_q3vuWzUnvBLn%#PiyY!^KMMthFNP=HCcHHMIY*og>9zJavcmvn z>YF0V$`{DCnGNzqI>;ayHnA-WuIPC5asRBbANPMjGbZ4A2N*GzAtH`yRwhRU5HOa^ zbv&uMH(oK`E`N(B_kT;iCPLq@UDrQE*6bsB!&ovBIgByk$N|!l*x`gh>@e6%kW_He zVuR7z5!fJ@NwtMJl!fsuw5ZI9^(wojDq+S)noSnvxeXTlt-_}HH_)mM7FZh5OZsbs zzV3k3SQC}bxTBY^_NTWH5L)`vH<0PRcKx3Z8N^X$>qqi|QUX&WoG&u#anMNF2HiHL z7SQJ|>S$Pv2ZX5;t8u;1GVxXih5<>v?J!8muX4ji&dK5Y;heHBA*lc`5|wsD*K+&& z7!;NEMisE>td?x^V0kww_fuSE=H_bVocY?bX~UuS8xchTaLp6rJRRozs{Pf}*@l5n zR{6ZR!eF6*pl?p=^Vat=DA`uWnH{1EeJrCr3+!f~{w+~NIa`6#hl{m_R=|~vVHzF3 z$S)xG#MqWVJ$nGq1Y2UQsV$R7hJ+a>`{Q+5PC0X@h3brl>)F&n+i{uRUSz-S-2!!Y zKq75kfTbE!=JKPw+9P@IiQi%6qSCKusN!qv$(yi};DXs}HQC+m}J zR1i+Xjc8+;tYg<&5FcY-I;>KRJL*+aV!miWxainBRpP zm_8TOQGm@1;Y@{*!r{ZzlshoKO}J}nVcPsq!@%}cWF^Z(!C}~xFZiaag#%NSNtN(r zOYDnYa8K1G8KL}Kteh>zp5MWL3CK*a*8oyNc=d&z;*IY6l&K|Q0qgeudP!+?tRE**2O{2<$!EP zT?%9mKyG+lGUVQZTzVY~i}zYcG_>@mZMge=xU1Yu59)FL0NRP0T8eDIh6WP)5zdY( zkA18XnQk>B)9vs)KNXqYhV(F`I!GfR`KBNf9L&olzeX!dZ3-@h%iyfp{5+X?ZV6JI z8C{Rq(RE1N6KLqwShJW4*JKd33pnP`Adman(R`>e5^B5gfY_A!;m~?rjuQf?c%X}_PpP{Kw@EQfaj^!Q#${mBY)H!?HA6DN`*KKAARQM@Ru0oD zK;rqMuX|z}QyGYD8nJSCR>0r&ATCPsP(?#LW7{<=mF+IwHScL)=6@1&7Gs{NZF2py zhlX&I>J(cLo6eWR?(_N;yC(pk6Y9{PfoJv$#g*BP(RIb}=^KBEZFK$Ux-qqbGe$hM zm4=4Jb$A;R44eV#9QW($3+rIP;BLD}GiP$3D}up8{=HDrLdgK7xBd4(DFaG6D81%q zp`?aV4wQELf1sE%Dkx<`X}kX-X6BqphGHfZpZD*@%o$)X*bFE=)+mdWaby{A@QP-ER8OAYVOZe>;*!zp*PK`Z_-(jIW zJ9Olnjr5c47*mu1f9{5kqnAJ0cIQ)yPs#J}32Om0X0{cX?2wdglo$NpIm&S6O}OCacsvgjpm57+}#Kx zA{52SwnQ<_pD5dKt)!c*{DOx@WX~QsO#fdwNvSgV{4t5-R%6zX>0zx zx$@d1l(g2icJtb=)+V)BujSE`b!sOij*%zpDzDWbN-T=y8W0(r5)DTIVDoTuG9*>o zGl$YSY9HQ;#7tSw4$OyB#!ux^cBp>61tq zzX)CSny;mS7uy*Ia{4$&mj9(%&H+f^-7XS@?DUo2i1i?8&I~O?WYM_#C7)!VmSixLv?DHGV}HW~;_ighjSdrlzolKNN6^ z<^*L2W(hLL#0fH5p;aSnBL%mGP2m*V7=acIVWHJlka{Cjz{P=B$#OsONZc&^YFp_T z5=NlyW^&5A3*a8f3otp!-Osq@#t1qk7KfM|MeNIFsH5(>%|&W;`*l5&xj8`cDX}of zG}`U;+1kYFf8_nlhp>RXb^bORDYU%=q)-r2Ga!FTp!9#2+7*9KPWdKt)F zRN_Opv`RLh3tqD0x?oad2a=sg6qgL#qg%LKV8Wh@Dmc}Lmp1!aUv|hE)*vpSb!#Y* zrWUXHL{4{NPHlz#;H#qET70PmiRS@P`Hxa!XD}+Qj40rU(&BYEnubTCQgft$=-ZoL zhe5`JepG5eh3W1M+zu|DLwUovN=~C+V`9Y15i|F!{G6E)FGRTPm)nauYFs%N*XLM= zDe-C`j%(;$m*8n{7*MTB@4@3{R5P6`#W+;lW4?wnZL_m;Zp-E`ZKg$<#zwkxF5F~M={2FOVNCXxAU18VT?KF! zdam$vgU0c#pA=MW8XW_h*cMpe+Pk6!?yV_01$44F_!^Jcxy!U5%#!^S1aRV6Y?9mJ zIHl`ZKG(HgHx%m41g+|}Mp{e?GTaFl5)(p-9Hxt`Pj8@rlRFq+F*;&bh);!BK*GHt zte?a&zC<+D3RNm1S3rxBr09jtwa~e;P3dak4X_3qfWwVSxxtTktsUzZKBVj*-^+or zut0f*G!=YR1%(B(i>KORJeo7cWXJSeN?ANHYJW60H3rF?4kSbC-fjC{G*jI)7$faN;V1=b2IUS!mV=+nR9>@xNwuKmA8=zP0^(S z2>rs=xw^Z z3ykL_*W6lKbi^ObrF`M#TdeqF;fGt)!-|4>AQm@TDRGT+bThu_Cw1gsPnFH_10>dEd_J6r>ma8`q)&w_x0O&yK_Pp7cE#1eADiMEs7xBbgskfiDP8OM zJZLl;PH;rp97XvB zN?G{({3%2HK;%p=tVcRpoGJ`kkh|=wzvh|X$~&fl{X~v)R{JDf5{xqp5KeJer{NUh zq@bQdhBzH&6=GQs8T4G7j)Hti5V0zl;uIaZ!9f$&ZiX!%k)((-pDdlxzvRKJcEaaI zrRl=U3r6Aj!lw%wuuB+r`$Wa=P`~#HVb1O9%#D#h2qqRcgnuWPTZN}?&(ByMQE$Ly zS*>a(GSExEY9(T$vSXjnetUlIjEH^%9y_#E??n2_b<|QU)`bW0NRHMCA$)sbO;=a} z%U|t5K6`xe!v&mXd?{e<8M(tEb=p}<{4xwPZ$G2U>tTF$1vM&r)~JVBPBV_wS}nf; zwaifK1L1*%Sw_2j;AZ)CXr*cYL6-vay&PtIW@wo>Yt(AsRAVh|!r_IwjI)55|GW<9 zx*y?ij1l@4mf-_J?xOWr6y8{5g#Vq3GSr8n_t;nSd+mq$OZL6q*)Xao1Q%uDokGSP zxp^H?hT9Bt|2lRph|qI6P>G2#QnMhoW~pIe;T?H~8FC(f&CBS?jvK~40t%7z9fbpbo>5f7w zCkiww56=+F?yR7UQK9k9;f`U^Yj7tFLq6|aAe2U=#*iI=%7n3%ZJPEbxSS%=y&)v- zl2O4Cx7k9(6XY(6!IqRuI8WM0pPQyjfO>O7O4~fSR7LlFLT5cjL?|TI`imbe@1VqB zBmlIv2HFk8L<8EvaN1m&E27U$jSVs`#MIA)`+yQd5l|98s_L-ctek5jdvgS@a^=8* z&T=*AM!;a%p=?`LlfuZHi%8o9+n*XT2K;S)J+KWwdCZneF&q;D^Q7SVQ$AG?5zhX} zj^7X_-BpM$3QO)<;y4*D?lEy=;b3g#7isXBG`_TbuOTV0GdI-jb_H5<DT*c=2b96Z?#|PRMZh3_2uvZd$cu1IYCSm zn?dCcSZ!=e0j;*pwTsW^ka;AYyvuIj)vn#3Wk=^5J4nO*VFS!?7vIb$R_(G|dCq=< z-%-;Cs3RSy+NdYB?R7Ca;uo6jHAPziM-yR_WWs%^1FU=wO2LvSPEP_e0N zsf7|V!@@Otg~^6@?XoD(C)c8#+rajd3C6_~wjOBwMqVdvdX5MgD>t@tHj#gcyf zk#N^iWBiG50bI11!q%l@@Oa_m(o*x|LHkOOriK=BpUAJzR+&DL_stGVHW}WE7w<0Q zG^VgrCF?m8jQSEl_aMkGlY12UA-*JF`lA71>^-xo2?1fz5t%`07WjnB zrQj-Xu&K!FCCHx~dJGWAqH^TBNBI68t%Gm_o>-^lA+~@yZ@%{Cstj1MQn|`D{{rKR$x@;)>94&PW@0VT-2Zpt-!?x20( zLEr{|82NP;k_o6M$Y`I#?tnd`x2|Ly+%CIE-eH>O8U&&T4ESV*&jpa-6Zs{ues6(q zgSh?{zLB+gI`(b5N!39vm%(;j!QX*b)P|)~QLE)N08fj#v_`7|rw3IB8FZ_>2L?{& z%3Mld%zC0KS3coK3*{v%7cLt*&^QKp7A{tSoJct7#9pBfpPgLm?G+=Hkks6n%!gc?I6!Y1o5|?Qmntur4$|`M2P`o1jLVHB|Q3e%}K9$viQe9~dOP_uC%Ggwt4*JhK??WaPJpc2$VBor- z#5sP#U1tf;^VxLcrbgiaU+d7IcyqQY-kch9F+q7Fcsz0l2%qK7=Us6Drr!uQzl*Ke z>`IZr`MtCP1sUh$#;Ei`l(3PPVakJar5O6jf%K!EFq|1S5H6as_*3TY_>40xO_Y%V zd%;8?7-6X?l4cuPr)`{v7cEpT5S?^_C)K8HZ06I%WSrO;l{Ueo%R4^hQAxm~<#fyT z)!gusQojcou>J;Y=R6pw9?+C~6ZmX+s<_5BSix)0fPOSAal!}7bhYnBb4#dm=4)GZ zKYN+$7aL7g#Pk7rE?5Q9z6XHCy5T?&L(&`3(t4yTtyP0D@1L|)918Y|hJnQo(PE=4 zu*)^0()=T5nStTSuN^s)5)=JMXQ-vba{oB{8ap0W0D1#lp0ypL7oX@LOZ zabf9&09)+uBxI}+)_8;P)$+_SpusTZLn5n|P7shDZzc$71QCr$rEWhe(99_5Cal(+ z$1;Va6`Az}B^$%c*abMfDy6=8?%CGe=(X$4xwOx0peCyt>FYg)OfVQnr2`O-kH z9`c>0wH|D|y>n(=)wQU4RxeJO0ZxHhGi`nyMj`$0kkM>QZ?!(rdU4!ZD6rOEiy_H+ zsb%kGV!7Vi^3XC=Wa%txnp(FAuUUL#@j}3r)57x9^^1CyeUfnM{<4~q`X4s$oC^d6 zq?M2q4V5)L1j6%wq5>NZH>UMef^~Us%it)KVQ)*D_b^YU7Y8H-6d8i;fznZ5hE^}L zR(}K|Ce|;)I~NWyzuQ_ZsuVBJWhR$3Ey6F&J^~xRUU>C^5^NIw@xX{V>5bbPyJJi& zIWB`6I+GlPHXYMnEIdrY>A5> zEWuw2FFaV5h zB|wW@(8!l_Nr#8oGWoHbm5UcE{h%NT7VsKS5d)XW?{7zJyf`f&oLHrG#QEoV8Sbce znC&}n2T_03#ET=35%!X3ersWJ^I($CKuU)E5qMsNq=FTk2I&DvO7PoV2hRo`{uc&-$=Cf`@Y4_&DR6_?myee@4Z|yipB~cT<3jxE(#-jw`5O__ z`$@u_)rOITA5Y<`bHJjJs&cK)`p$wn8#|&>eBipbye)A?KF^4^`-Q)(o{aw`bgr&o zDDnQFpjtC6={Gqdy%*CU?H6ueGYT&gn%AhQW{2>XH6Ezt4hYL19u1i{1HwxWm#aU4 z>zWLPT$$~+>2d%gdcpf}A*F~4LmwH9uLzZoWEs{1Dq{jYEXT=*iT-E^sOk1T_!G#k zwIEl8q<;#IM|24jBZE5Y*ABn^$V_a~@F)7eM8tAG16$2-URwrLw}=@|7aSnf6mRi9lmbCa;4x*S%&eJkn&zG({I@lDnha9F&UO zU~3VhQNlr`2%SwC4ox&&#HkIvw@?jWoY%NjV+Au)pT=ie)9moy66yqz+yq)&fU3NW zUdC{TU0oZ{)9 z;p{#M0HASstgz;(Dby=bq4lX^N8C(?Bi$6hK;ua3*fgWk0yn8i7~jJk8dn;yeMo$- zqp^l%k$5b|KAK$`$R8k5w@U-pFD1^EiB*U!?+|W`P5; zuy#L$AAD>hHa=$UjWhg~-IT?|iFBM5oR#osrP~UAgY#x1pBV>1CjQ{DCvOMDeF*!Z z@q|j%7(?C=Zm)}eI;DPrQcchfC?C!N(oHSq#9FnzlurVLWB4z38kW)R#8d&7akz*Z zM5Zg;?>z!|I10=E^wWa*@yU+fh|*wKgY+uE{C0V_J2@)70tO_oBWPWX2P?6x|&dD3hsMze$ zH_YPV`>It<6X1Ua^06r})gj@dynh+43Q9^L{>jp5CJv8^N3SIqby+55rTk=n;3oU zcuw7`J~IkR3qw(9LliXjhT-*wHEOa7?40-?PH&g(DpYvhV-Xn&@XV^gt;ZmWR%>tN z61BY(>L)^dzc--*8=14_Yo`|z;?M`~%ZnZVUYx&@#fi=GKbOZ2Grk3ui|nn+dby2s z>{LTcN9;MzF2tUK{Z#CE%C24(`@VQ0P-m@u;fjSz7T&*b>39GLJnA~f5q5K^7JLR# zaj3I&<{LgoQ~Wfzw^xb};HZ=t$u?w2>!76U6{G<1dcZ-{Tdum_v&@j7?getzAxKN z+Iq(4#D;-amOyJU-a)?!FUhP#tJa}(v zaeV?9X@W#Z6*(njUy%J_hCCr*geH(O!Q2A!&S_>(z_S)o4aVpw2tWNbr)0FnkSUr| z!HsE)BDN`rGb-G&&$?zL3^*SmXXk9(cp=xB>Bt1fqd3o7a0%{I%y82N%3ydXQ^fHJ zp1rgF36`K^z~$&WU!7?LMAvs_4mhWO<9TJ~EA_?T`jKvq_gsv}XQI--!k1|BJQXgs z|J93%PIcbh&!~HNayn7L-#s+gi$3#iwP}H55a+7TAWx=|Vep>v5J%5bVLVYe#@l(w3$4KKxGVnP znUx}kAA^ma5hl4N$PEo|m$#Z8X@DiCFUY?%Pvh1>dAt0siM$cYn^leqzLLAY)(YO$ z751R?Szvkn3Y(H0D&s6%PQ!nHXBoen={r-#Uyz?{HbA{HJ2nt6?1$Oy@|xM(_lUJ>-?zSOcm5&cAcziBmoucWR@)g^7oG*7%<7K8c8ST;vLs7zlU_0 zfO0c1hQr}GC2;ZQa;UjHj0(Q=Sf4HeuP4mXF{-VzLq8_C8iI^tup4`~w}?xr8@Ucd zHFp)+-LTWw!Sgtz1CYqcAT)%W3PR?8KNSUVG9H97OWr}AC{HM(W1!(60c=71^Jnhp z#q_350!luBvfhJrVD$9I!MJecmo*Sm^2=T|G^0DI(T;(#gMaao4#vbfSO_zF;2?B? z@m9wGe~@%TK{wL}?mmcjc6qzw90PYAOtU%$79Mnro_=G#u(D;??VpqWQXK=e2WfIw zsT!ac%fauV?sVvjq8$Sj2XTpGp!{I}&u8K7xPx;6$e+C+B~<<)>zKh;K?Sr2=WDoW zv%nM(oGP4ev0|H`Tc>ukfb}IP?U6^?Mu9xuv+Dkeu6y%=H)$9!<8$}I)JoIrX1%_y z>t1kovyi|TR21q$x}5rqTBs$O;T>Fa{;XI;3<;Id@Dq+?7($sI-&EYLP;RV8-8%AZ$_r&`$6!~JR;-F>D+0>H6 zv(M@Zpw7p_%Nq)Dneev_`SE-CB-cg0OYm*b6-tpMymFk0BL}z&Jk52$B|axB+xv8f zAz};sa>2oc+$+n4NgK=Xqrw9lb5rk&660UD=gAy1)L0|z-Uza(;NCbLJB8@ROm;D} zc@d`lG)!6DhPOr~4cJ*UF1!o2A@G<&`KDrgUbtsdH7*kNZ_?#&kKqQCAhObxZUSu7 zhP+jLbc(SUnuf>Jny-0uqGpIeo2JXGq!lc>UR?v>(t4C-~P z_DSB36aQn&cyi9BSKmXq5|tUltM%3c1f`IZj4IZ+sithV)6` zQU$K}GJWVynF+%AYj}Z3>G|hn`yt`x4G6wP>yG*IQLdd!l9>w1 zW9Yr~==)w|e9KJ$&f)%KsTDUU--UXkQ_sfgnZ?yDFnH5mcz1tl61+nWjT=Da|L7St zZFj(DKK9wU^7qfEX>edCzaG9erc&+#0AlbRYFg`k$9E6ReZ#q9z9kU#_HJ{cc!8d0 zG>d1O&vCEVZkL(;1V>8uE{*^^n@e|3f*6BnDH89B#B(qGaLjiv5adS=CUUh9=2V-i zOY+4hq!udo6^ii*1@2T``(-K#!s&u9%Xwh6PM~m+#iJ3aR7skxe8z zuPVS70|rN;(Fy~>Fqga^x1N_lz7-aOJxbF{r)mYfMeQi`Wcip>W4BOU*!3Z_fkmjL zy7BJa)p=b>J{*sCU&u-gZ0JWuT6o`W?Co0(azz;d7Qr@u%k_A+y6Ujyi2H^Xjns$< zsac(69Jm(ktj#&uino60#k=py`QD30edpDPs#GvmlzF{m;*7ARhS`lB6?)(qZvX~z zxc@f>2)2?tTREmD(HEU;iebyZlUk(yZ5+KD8RvHqkalsjkg|VKmAXP9?C(pY@vg@# zf@O;POCO>YyGZL|x5;qoj^){#s+nziKCg@38MV?o@Fd4k%UO3SM_`NhJeIBK91X)@ z0^7@Y_lMPqoiEGz?D!(>Sq0?s*r8BQ=`J1apI{AvSl=z{Zc7g@%1ceU;w-HsZvP)zq&0+OjaZuFV2d?=|zH@MIy-G{z})REr} zmJEE74+&+?1a~->-6H%{l3JcFIqj`b0GH)0m=ersp5HH&&Vpa9MdX&CsISd;Eyrx<@ z^;gTAeev`-Hw3qEAH!0VgRN{>RZbP`VC6^ExN~aN4#&>~PAzO_nEmJh51w`nj`h-1 z}iAAfROQWbtit934Y)~el_PK%0!7Mn~ zj3>8!HtW|Uv?G^oTx7nRX1xWQ_WC=h%XAy zVT<$Hr%p-R-&#|(w@;CD7XY@S=NwQSw1kmE_ksSPGaNI;PK$4G1AWoBD zsMG!6B_jlGj^J!P(K_HQ5Qirv8c1Jif(Y7^L6Aj__7GI95Qc2ea1f15Q|PmwY=Gb_ zm^=0Wift;x`N16mr4zt*GON#c$pYr<$W9p~UOQ^`|D-g0;XTS#d97R*cRT!_?*;j- z0rpiH>Y>WITkYP;YjKpemr9*Ju;^ev=>v8RhCY(|6m)m%VTa{<_wQtdpgs>M;~)hf z9SwyIdW`c_8@nN@9UZOy+zswKRfOafcH-T}suA2hKhVm*{%Ej=|vw>DW>8r5AQ~S;{*sH#g97?XEzJ zY~Y6iySt<2)88SVzN4n(rvfgO2+%JO|5mV~J{Hey;D&SAZV(1n!;wzN=FVr7gRiEZ zGjg&dM-z&UaUX*R=LRm}JJZEdHL+i6{$fe^4&{HCiS#CJ;i@UCrVct@z5t?W(pB$~-^@wA z-&6tWUsa-#>GdA^?ZgwWT&Y@d5UxP(wzm-Z@aDFQ2N68x!fWS?Wh9`%!neNDfxD8Hix$Dm-79~LayJI9kIlB768?_EMH!>Y}ryRVUvx^U$TtsoRBq^({VhH#cYrchIIW| z=0KH2(d*$Em1g-FeyN4D{D%;JvCOeNCJ7M7F2tKH%9s`oth1P+W`SY-S_wK}EsN#u`gbnv5$b8Ba$>Ka>e7x49Cl zk~j?qf*3fBflpN<%_Z~zcb?3^Nkj#{&IMXruIfnQ;GL25bHht>TBx7agbD+lDs5v8 zRfQ+foT^Q*#Cu?b1~|hu1YWEHSbR!U9i-^@f}0`u;%u_0IozqysyecpAgmO^WMnV~ zY1;oB+g*u5+3u;C2Vh#CKq9_nU+XBC^2N}JWy+2N!p7aD)Mp{#`0nET<3%y!V`btD zJ#T4GoS8T)2^=Geooz4+Y%qZ1h1h(nFyy7I5#|EGhDb0N1rZqWAk67Vl*t!=rNqTT z^-CpLd%(mDZ$ZP{{SZ}0fl4$A)~xSfgntOnza%h0sW&R*y*vvtC!@k6FE5A8FHzyg zm%qiV@WKDirv@T|>Xj*g!kMqENck;{fzhMBW0wWNM^gCgl|1U1h;aFpV(Np4pxwjj zk4I`j*Sa@y_w#$7ujPieX0`6Jm>dq1#daY{dE#L@_bd0Y6MWk6b^XZVU4IzCw z*wHm{X>bxNp=1K-G9pd6Sw{Ys`fbAbD6101B z@Kj;a-dtRA`1ZXo;7rlwq4(s3$1&-ta7LMm8Y7S<*lEdY#u>*t|^mHx|K(xD0t$H!5KssTs9u=I13 z0ZkflK?kBGK5>*#N6;2T)!;d_kRQQq0rHpw=AxkVD$vpRuCVkq94w{)v`q#5;8^Lb zYR88A?Z)Qh9_>a5&0Vz#>_rU&`ymY0FWJLz@L6qhW5;puwIURe#MPaP47Dxfx7?(o zDyTO@IQY(p{QWRM0t~PqmHRWP z8zJG2{k8ZB;f?)wfp$u9pfqhmNZT}~Na-o6Pd63SVF>xHIq>p`+hFoqmkeYdHc9|4Tw-7v9VIq+V7=Zy zoTr`^VIWk)FHMde72-oRU$}C3)QFuj@+HF68<38KNMHo`NkWIFcJd}yC_R!%y%7{< z9ARfZ7A%KXk)Wm>zfI2Xb3sCRaThAM2F^PH>8TKD0)as6H(sWA@Ens!8oxAKJ^`M> zEj;|PS0_+@UiKP<_9J8R$Aqx~Vp_o&ISCxY0^p9ryW0G$DXASiZrc|_NS&!Y^&d?8m>Nym|KFj~eYQa`p)= zR{=`gp?bd8OFkIv^Xxf~4tQ4qYamOXLU83#7=R4&l<-B{J<8{zjjn*?l7$KHPbl9J z!+`>V8Uqp?4oKCZK}z;L#F@535Mm=ZV=5p%02R_*(_pP->6WNp+T<5re_x-q%?~UE zxE}|kRlq~yt_8XaUOXkQ^=I!9;fMFf;Ppb<2Za=npD7<`z)R%T4_4s&gp(iWvi;Jz zC?Y`=V8u`Qk0?4n5Dg*n!SKmDBST_N-LPZ*B>0U`sj;wm3Zt)rSckzgig?)hrJp_= z45Xt_W5<^;m4O^#*3ojuz2HF*y=;qF35RgoxNJTSPH?xb7T}*tVh(P4w#9?o7m&*Q zuqx@5-G;1E&51^I-N#NKK8Xk}gBrN@eFpatGoRF4d1`0cVA(%0dFnC~Fw zY}HD)rJDNIe61wyJul&INnC(Lx2d zcWz936sQUv_appIjQat0BiST9fJXA8IK(%5I;1y_BJdO+I~hcwVN=_|IsxcwZDlcv+nV;#DE6`Dbq&JhR}q69P6HNU8*b zXu&bA8qzwUYzRqz{_D{8kfeAnH%$ZE~WsJ6;KjxLe#xa1x}e_FGPf&pOT3Z}cT9 z629GM8S-t3mf}!Rt>-I#Ui;6wR`0%Q%eQazDXD6%A1r(*U-Ul5zhqB#eZ^n0Zvj0L z6{kO!#P8Oo8k6k!Y*4q;JGW}AUCEn4h3{yz*Fvx;1NvA@Ypq|&3>%W}4afPE3@R!2 zbj!)6B+wJ=h28MyRZl_ua$+A%tp>w7rpMY>+kbDVCN05FWD0i)qC}PKF8fdyX?x0E z#_y{(R+ZUv&+Y3|D14gKlIyd{?}O}FbsO|%b3n|%AhTHwfP|#NF!`SzK5m&lukz+N^P~;FMCNX3>2O`JHSVWm<#6|oWzk9vh+VevMAZG=x$hO zWm`nTvUvp&tw>bBmf*F1DyT+DcFH!wYDKKgPJV7O6{Q}@ZHwCvKjM&ux6%R@-woIUm;+Qv9J(#BJrgUaqJoTka*1_@vlLGRk+iSm$#*YqgYYXP%)gE(D_k( z{2BO>5#hQ!cZ8A1Jl$X_)&J(b6)4CZQ;92)a)#ZG#UF&y6J-^RZ3#2TFM#Nqs3J1T zt3e_!C_2dxevsP&iOS=RAaRh^s z(;AB(U-9_9$Klsa^Avxn>P1z*KpsJ`+ma}LanL*hG2l)Yxk)B|B`fVaxtvA}*}^{0g-OdT6x&|-ULmz+SL?#=g|Idh(K=FEBg&;Rj@^Nml5 zNqFZ|BGmnv2w$K2$sHdFSGGbE<1<*J!?nW|eNKcy_>J? z9EI4bd^@Qxv-AE8^NBj`SSxhS4K;k`X-5WHx4^@p8}`=(W8c;}e5E2wqx1$W;6V#0-2jb-oPZoWe{UY`w6pdfn4b zEt+@U!M;qO{K)(o5_iy$1N2HZN7#I0V?8_-yi0_;;n?hDb70A1F`7T&AvyMS;n_Bo zwQlx2FFtLiW%k+vIY zz`ikab>Mk9rNMNAs@l*IVaoFsqVD*So;| zrOtsLD=e2AsZ*5PVtw_DTtYNc=c&O5V{x&Z!>lNjbIg)+Y&NUjAA|XNc+kthYrSi| zF=lgFo$yUMR-oHloh27YM}g%wP1N*RO}nvds4w3{d9Zctl0eY9Bv2Z z!C;gL85Rw4zugKlVc8!sut&3jJv^xI4{W%Jzg}jd56|`hyc$$Jx1lH3ptW%sxGuJ}WLft&O%I zpMq_f0)tWUDbN&$82iEbp)lX`rWzx4?h$``T5I~|qi->EBVkoa5>zcAhOGyIgW?XG z<%N%Y&#g3M9SXr2jyk_{3x}{a03k3(%NW&$0Y&8K_TVSW4X~AT2KIAxV7x>1@>q3_ zQ&4c?psS{Dxq)aC@FZowU{Ik$Ds=rW;l$kTj!fl~?U<__nQe@WV$IiJ9({*~Fq1Uw z%X2i?$=k(+XS7^mpSbo+23;zCaAs=!E0~JBAqC8v0oMj;n0XU>jXI+}T@J=fs@4YQ zyTFb-#oK3BnI@qT zQ$Q4q1yauhL%HECDFhtVZcnr^3865YtM<%frv!%c!KlLJz!felujW~_dG zboVjItG2nbI4}!Tcd^e!>0m|tp-sjFhI#cGt&`R0wTEH<^P8rq?Sby?1HnzZ^1|#L zrq`pk`!oeN?En+$`bu^>+_|E5=D0>if`kt+LGWvM%%x_cc?(N6t420z_>acCj>~b| zmo9&_Y3DEWPe*M(+!s~M%*fx=M_K5VKQQHj^wT(l9VGp(x}jatI!z*YrgWMGcc47X zX(dUOZCD7^JIiZll7#nc=NVsy*c_tfQq*HQRzjeYky~IW21ojQh3IB>+F*w8F97hV zu#vo|YnFbK^!(3hp8ATDS2SxK=GGm|n1e))Sp^Zdq2ET9-Lh2*6(prHxe8A$Q zwdz6ez%KtKk0y!}&&8_MM@S?4mX#nqU9Q3bvB9R1KMmvg^6X$eg6u;&>%Fr;zKdvK z4Jd;3wq25`kW6~n&UYSDU6hXDBapyi#MVFo9BG=U#<|@;R6c@g#}8b_nSz}|yDEDf zA;ySprEfG#D$qA8C#Z7knhy7+st+{1u5W;7{Ova;X1h1LeGp8uzw<^Id@no8K%=l{ zOeM~l5<4ez;KdBOzIHFn)3h=6^A^u6kloCZPzhrhal1XvaMrOf?{-_L;hY1{5>`3G zlzVgEmsIs=tB~9nZBWfV1MYI4OE2{{vA&kUWnP6Ht@1AB2^*e2w-Z6kxR`3V1P+cx zGC?a8ptr|yr+K6~2Yb5)8nT-N2#ata1dP(qJqMX|$Nq3i^B{5;UdK*+-LdmxRIp~~ z0YZUUs!>Z2XNp(s#?(;vedr1SKF_>M+6W8JI}Q)b%XPg$LBB-*1%rvk9yE;6I`_C( zb>TVg+@N^j!efDiK@)fLA`?i85hnYvG9lV3F-*+U!Px94#>zKA) z)p?R8AnOH4;jTamCv8bY=xMjhaRMV!=M>FF?rohqyk$4wZccQX5x32pY}_NQ)l2|U z{VC#TpvjJ~K$ADv+oV=uUmgbyqJ4R*?Ifkj&dTNuAYH99;nog&ng$fA2`rNfk>rwp zE3^oO7TS}I;T1NACS`$r!CK991(fBOE<_L)pLL@1?ZEtz61jHoC{^cXyg)AuV!bsR zQLi>|s@*$v%1DmMc5Pz@aEUgPUf0ecQ=7CM)BFTf&!K7~XO14pIMMFoRQRy;t;QcI)i#n?WwXF0 zVU=tk+1j6>)bzMKL*mviBU63@+z@6cj-gf&kD=yWl8B-9xD*HRk)XOH`3EJ!e0&cX za;@tZFML_3e$Sn4B#C!z%$9t}HLG9DIG>8yP;!0(?Grbie;rqqEgjcsws7uppSakT zX*z$F2y96H_qhjnkW9NVCW;-Tl^`7lT>Am8r|`jFS^%h*`sH+O1j*pF^NZW6x-V|~ zPIbF(ft1f`W++GAjgJ*SP=m7_rn&bu$^yF7V>q zt{jiDvz|z1U-OkX}B86y$kgIYzzL^Aft1U&i$$oBV#hZ?r%xlWE7 z)2<`1qYz3fPSPgP_O~%pe4hN);q&BmxNDAkOQ1n2(Qr=UUKk!kSYBH`L+zz$RA_*I z0FLBW%xn__+Fmj-)Ug0Vq+yfotH>gKQ8r0=37S8X4RfK!$*=(K4w<9tD@ZW=em?%s zS8#FHFez_Ty0NsAlXIQQQN@)p+WnOl$>-$$s<_JNsui%x7z;APOLe1)AlC%kD^$_d z#nqbCrK>Gc@U`fd>R-D4l0^!;R%}}HpVhajJ63C7e*R_c8jBQZE=O_gHJaP8#v5Nx zqb@JENU=hR(?l&&wAmuXpR`C(Y8}!NU@{P+_QhSCdO1oZ30$s4N>N*+Ndm?=@+ZQO zz#^pz7AZ}bj=SVys8|e5HzZ*WOrcDJIcet54B0aOZ;?j5)Flw}@_46Sf6fMikgn5n; zVV>J{;vr$)&>dilHRox4QR*2n?VH#I3VfiS>Yj$W`F6TjYf$WgdWT#itL@&8wY~aK zZ49kqz*W!EWavC5_W=`5eD9ms$Ja^qdjEEAUwHFVkfrrP-k_*^wsEQP8E7h$7DpF* z?NLDru^(HV3a#er{F;9OHKwJ;y~Xz&L84E4;^el0K^Kgi4c%CSD4=IZOAy-1K$d~! z2@Bk5^1FXFkjd1uWo~wYSk|7+^?JmH_HfPt(R=%R?l@%bR|>gZoef{@D zx?UXmdqnJtV1I{DsNpFVS2TIp@emV@DlcbHw`qeSe|E zuOPbzT(^N+=+(}6)D+$O+K-(&UDRG(6i|o~tV{hdbJvTnT-B-$4nT6}Ixryq@#>?d z)ktQN4gz3_AcN`%z92;LJQO4tL#@Z<4Ji(TmZ+FnF_SnieN=tK4?}6}FkvX;IR@r) zMw-DDb4ITu&OUt4cNXe>VZhScM4S!%C84xdW9V^-ZboL&x@F1!EfBzIfCp|mz7a<$ zf9M!Iz_Mllst0?_t9G@_?KT$@D4ej+c2I^0FIb$T$lap{Zw~RWy`0Yr!FYI&jUBz@ zm_pLS6f^2S+TyLWBgaVi%13eul)`glAbJ8c{J;Vo!_tRZL&2x_6#{)s5d3o&SK%I5 zK!My8LC9EKtupMbt_OO#4(cVt+A7#4ptZtmZ%Dov*^vPijd>jtfe>EVF>(CV0W${H zsV2trV;$)Ci4wh?D!$hdYpMh)Ia#3Z;<+&6{>AL?ozycu*alN)r{y!lJ`$7q)G+$@ zjHr}?y;b2=ORBC^^|(y^NvLCEe}*x!V6R?hkH?y3uF@Lf5bKgMi(~VNGa1Ln82It- z7#y-k*<Bt9?aLw#0DiXoyP!Z;RS1Ag{JV8J>(tinV? zFe*GRr5FMWV78?l3!~>M4+oX1LD!2T;$LA1^9S&P*Sle!vU1g5>)ZOh@}6 zG|mYJl3`Rr^7fYc&Ugy_k*;)gdTzh#K>w1b0Ce5Cn({r{D<&IDi=p$<|22Ri78SJO z8kTNsmA(}gVm7x*-w994{vBa~>^lVpN!KcM3-e@O5(?pqTW>^0_u#A+UEV5@bjJ0Z zWzRzbKfP7r)4@R~Ma$B&#j`hx#uxQ%iO8}i&KU#t&(@D+Bot_&JSRT!?JrDMrPGdZ z;fx*d9QnLYA4ei(Tu4&&ZO0s!M@MvuX!!S(AQfT_=(04wZXSMbk)^BXL22@)8_Kvi~iCY<%pl+D$ zv$DK%yDe2i_^$Vx#ipAA4Hj?Q+&w4j$k+l62By;ZbK?$uxa}*@Zm;Rb*(v@6$g=w6 z{a1)y%lC7cw4dYl$t1!8DXP%R_Cx{?NEGnkhBS?LbC@n0i4t3HP2=u)b~^OSTL+<_ zWl(gg6exdcD z)=A+sR1sDmX3fUUbgz0ZIY;RKl3P`eKXkz_RL9Bw!x!IrU+boDia#(KT|e5o19$!; zqCSFU(V;H1C&YR@oQ@F%US+jExVae)B_9?eh0}4?aS?QkH3OGuFUxS&c zWdG?meXdcEW!#v5v?z~E0Qx=0qC^t@poT_d~O3^ z<<|ge9&QudZaDUox7HEi_c!moF=-ek85B zsx+-|ab{XoS;eaAw3Q|0FTPOzVp*D@ylUl|lB%+!#fh|@X1uYF2s_}0--M9eBllB& zk4L}Z_P-i`^Qc_M1-#z@n|?!HnfQdJx6aR(_GG1C@al)q~wvT zlBw1ysWknu17D*LFXA~Di17Mf(Nwr}I6F>Dcj113>$n6#&zHk>y*=Vjf{)QS#^*kc zQ|ux4kDf}Uqv^Cy*h0o4@JlnUT3MF%|9)#8m8=8Yead<&wBu|!K+1Jw}cdWl`nTOZG+VX9FDfwSM~*;;B{ zl1(!Mbglk6rqW4t5SUos%BB(YL+i)cbW#jopqvdnPp>&Gd;yQ0LH>6R&<~$r6$!`T vE}UqH)gR*FV5C7$pD$3gj5dVKWCViso}NaHK|2XsVsADjkov?c*S*% zm(qxuY&58Wcmqbhh=yPivx#PX)-k#eQ(^r_MQb>cPJ#=|0s|OZ(T-C;=gqP<7V2kA6u>B{W!n^czg$BP1v&KcGy?D(3jn zCR&(GrUylaPIWWd3{!>~>&Jd)Fjpg5SVp!7`i5KCgCBZxY*5-%i+LW`3t9Spw*R%dl7Vwt-f5X^Px_^NiMI{}?HDTPNKjz@{K zkV85{bAztJKUx^!mcRW-(ty?YEAsY$5AY>2Ic#>Gou7`X_-Lzal?=DTbm3(C!QP|6qi8>q8DefSpg|O*$}6Y=ie-kQn!A( zli{NjVYgmrt2XPJ^VefNWlJ&8LL_-QXhhIkAa+ADjz=0w*hxl2#ihO0o?t-2f{RG2 zYNdF*2WujDkXSE1jI>G(=9I$yUZll`l^P1_-;u3R-{WesF!~+KNwE^o+j9(~0wt*@B(3Cl zwGX4;9~i6uz@U=Y|G@BgfCkwblZCs;rI-`=Aej@JmAub`jxc;@%VyZe@@D^THCC;n zgoU03rj_P;lhu6R^p3q8=DkKbVw3PVVvn7Nt)wI_t6z+#t4&?h{!neCgz$F4MGp*B z6+LL71lF?!h=B^hunFXYxC~ht<9y1<6-S(2HtlYpWx6%eA%O>$D>VKY(7gl@YYPjGzIC>kTT2Fh{fnmPDDO%q!avrxNPDWLeTc z@>t8Jk`B~yT!|89s8E8~s^o)9@!mAEQuxh<4}lW#UhzdB07ILVf|qC#3h{4bQNmP8 z=^Qq`e}Y z=Ku__r<~g^n}hsizdjA#isGv^zdluOdiDR*fDAW1Ro4z$GOlgfk{8;(l8ysar%T<& z@r;n<`dxxmtz(ygF&VtA>9&kP3-?^)A3Dy`;>zHM@Jz9b3@8yd-U3Rx48=Z7?k}cDV9E7IbQThJxaKX1 z=lzT2-YbvPS$ZA`yId+z1DPX_ljCKRVlaBeKXn*Y&nF^(O`eO@BzZ`2K!Ed#v<2xv z2AjynA(2_Ly(oUaREvUnS&4haU)sEnvtc#L;vxJ2XzvvtfQgQ1lj|OFhF3N-rR3_6 zehWylVJd#(X56!e)6iDWxhTmar%t7(@5QnG+yx^-t*FW zL!C18_IYV7w^!N!wv6)@S)mWZ)5&)I@~KrG*aa@stQCUjP}41GKk|xaUALq6#FjT;f$-GnoFLK$>DNFXW;g)pN*C$JC9Q4U0B4sK1!cirM^B8agC@-hT zBPPLIGW}hEBh%jjWgq=5P}{@pm#WnjW^K>L3cu$39#m0b((!V8D)~4?gC~&tDH=;T zxUi{?D=-K2plUFZtidDx6SS`ZMOcwg;(&IaR1-3QH-rgjqJbiuRzdnbm+ToC2N~m& zdDZ}0S?&=(a${{guL4=i>pJCtV+L|YuOs8b0;-b!$eV!_7{%z(2-eaXP;8cMq=dA7 zrP2IkiHRE7JS*CeVdi&9eqhDt_GW;~W>dOt3@9P{K4J&FPj03T2jA^C^m=%pdmbF+ zPF34&%z4B?Zk+qfX0?Avei^z`@gW2;kIBZg49!ZA|AwjR%(}t>Qolft_{gmu`hyKz z$ad867^8&Oi7jpSbNmH{3ZUI)h>Cd~daBMBtc@Pb2r30VUg=U4JTM>Ut3EUpzD~Lg zp^-91{@Q2_IBtq6!7eHzYEeWX>UiB6lYWZAFIlflGF`i)EID9dU z>#UDP2H^C>9K_xO$O0JgVqbY1%E(cDpn)?_+3(#Hyh6)=kiJdvR$h=4Ij_D#j8Y-|F%W#tp$Y%@_qfi+b4jsc(<37_4K@o z!1uYu$?h%16i@SILUdrBWQxLko~bwflU3Ae6d&lK21IAfnjg7<>0YbYFRe2c2x?|Y z)vXphY_l}OIA5?Zsv(=DBIA;^%b#NCsh7r8-M1labdoXgZp&pU!7}HvWC)HnR7;$u zS_;&tTyzM|*e8t|qteSmHbL#E)NkTL8;YM-yqa^1@gAh3@3udbj9xLbWA^xJ?d;Ne z(|vQkV5IMxXux>Mp1kHw8haEowBV+I7C(y-wt@e`Q0O=K3eD&1IWa23&^!` zv%uRXmz)dR1`K4qrsI0%#w^SCE`sa^Wi0*Jam}E@~;80$& zc6>IzN1DgyO#i@r->wE*FWa148073!w==@F3&4N|Lcrg`7Q2t3TC z09mMkL5b`xjS4>R!3O%qeKUss>~^pCFLJ3g-EVs-Vl4nUM&T;? zvRtFcbXW6rq`N!`XOPH=JMaZ-{lsI~@4_j>HUXR`r4>nd6j@!79FuN)TS_o|qfEVh ztsD8LYV>9uUsq_*T^e$@|0`BC;k zJ!rPFn^Nk{13D@-YkgxM*vC9k(u01Y``;tiUry5g%|0)--}^fLCFkZR-?r$@AyNeF z=~a8*Uf~z(3P+RhDd|*hh>paKC`{-USgz+WaSrltDLa&*}_pgWDcH!WxS4{mIbaUx*vezxZ= z8rIz8}$Moo{yzml2Lqi`cxH+^yFL|4XItXJ5Q!5FkZtb(x@h&Vkp)#_jbi^D6f z_A|4UR0TczV0pu@No@HJ36*1x5&WG=&37SaM|vbI+=MuAmIhN6(C;zUw_YetmK)>Jth|$a~@`~PGc{oMivoo66MbCWSr|_Ls zB-o=9!ChoA0^?vb%00>kulTSxCAG))gB>Tzv_JFFzEVRUp#_?z^+t>EQ4Q8YU>87f zu(<|Cm;lmil`27cf0ZDNz2s|0jPQ~JL}RGW)7+ttK|e z`hDaDi*I5hUH79*{(x`5{%Tsd@dxqud>GaAb|1zTAI9ctW#a&j7C!YVct)exqX2Cp zo@8Fus@*bvPxZ>>KKvzszxW0hKdLx9QQ6QdUhD<@2E_rdxWR{S@rrAF1JKGTKh6gh zM#F%L&d*w6Q_JtjERBc%B{#}?ZdB32I`3w_tmh`wR(Xe%92uKyOD?I)d(n1JI^HB> zjQuGfU@GKhW_$ba=Xfi}=JxD43wjqS>s_DL<$6B)q3>wLdIU@J%IF}QteDCMO4Ems z=9$m+ms2@qUU7T7d>*3cD7~L8oky_dbg%r)^lr<$f8!>&nvjhDB^}~HTAJ+s!8dw$ zG-$;Q&YKblx_-gPp!;&&Wwd?UNCkUS`*mI4mU+Unlr>AI&geYw+eIMELbPj{Tl)e75c?4 z50i(>q^J^q9`g}^k#bRPk1eTc?c<=fi54C>ql%Tli{Mo7+17|+d38TI4OUv%4|mmk zIp7eEIq2BX&XCeYydIbhc2P$(yqVYbTzGk9zF?p!(kpg&UV->fXNF6M%fPd+eN}J) zZfGm(`94!o+6l+*dpJ6%LtdY}HUvlH-%$R(wsHTlHbmOz>LEw>Xl@34W9Dfi8{A08 z@NswN=k>AUZ0vGLT z&+8FTzXDhEY@X?kRtEDPu^s*yc)51rIZiC#w0MywTfYB!kj4OIlt;_!K=V3ZrHVl< z#$aK4M*_?#2fnf&9ok#JHm6w*QKM0P6?ipk`zt>)m?e$N3n`bAJXv0jw~_p+rH~MA zu6hqgk*O={aii6BW_^r(Fi>ZPu)q2DpBV$+EsoeF}p{sf^{+y(~wgyioCtfR~ za@Lb)uRXy2*3LCa6p*9W|B8o_r|TC|cYDc<4a0F3Ase(ff_wnqVA8o^xuwD_i>X)a z0^=#?gF&0b58Y?&GYUAkU!4MhH-JPY!Ah0@6aW}nw>E7x2aHo|4oDUQ1EaBEaGN1& zIo11oO!sl*6n8>i*)6{5R=^cn9#_>G$TK?q9oZp8>*$2RD6A9&<`LJB>#vuET?CXN z5Lq`t*$RM)stT`K(>I>Lm?vNVcQW2UuqCu`j%&Fv5czjakrI(xoaPejIIA_!{?$U$ z$tuK2?aPI5fQEWb_kTqB!$2PwM*Mc!y+VK+N-I5P^%>1nj0sGX}MR+9%+qMXg zCYEhc(0gQCDJ~_Cwl#*u!-c=9{ivCR1V<&rKPbT^Mv(Wm+i?roT^kOg->cPt1h3Z4 z$@s5chX2B<>Q3=5huuHnP{h(8L6x z@pf|cPZQzF9kp|8@Mb60B2Lb8D&cv=A#NZmcBX^lso&X%7n9OITVQ{#|2d0tdkC{@ zZr~6H(sI0ZzC*OT$g8__VNIUCqXsEqxUVVrKwc8}lXJWD_zlvzD@pSTBuJQej$Z_6 z5mdeloHnFNIZPxm2ol_q_zKa!v55LoB5%C$vM~-;^h?XpX37#+BBx(wnGvZUX**63lyqqmlL?;^c&H{xH~gUE5#M#%w?v2=Fgex0N zY|E!)$L`(m7!L#lo0RJ$F@)so9cB64t(7h1xFQIkzXOF=Y8)c%C<6Qe-u==HHPXf<*Ut~WlMOR2 zb5}P*n+c_UcH{n1y-B-lvFWm135#)vk0d+1()cR{_|nQ>>~iilH?KcJ*AC|xq0HJV zr+|^5fy_1A?tQFoWlPG0E+Xy?N)7H+Y5Q~9IdX6;inW)#FR9SPeR8^%;m1aBYuV=0 zdB~RCjx!zNA(Fl?NoBtn(&iFt$?SdMF*@hV68qMdV*~FnH>W{ZWd!9pDP=kiq1|@P9hwrmr05^Y-0n>}IKS*cMStCF{t@sIv}@Z@_RT-1&96J?3-iyo@8l znYd0$@g@?rKM{{4WA{=C$?1quYnMeNM7-t zQ@;O*;?OqKv3IAu{j&PI;0|XUeb}D~+u(r6cwQ2uysI-Mag`&Olf)Hd=3gRnK6EG{ zi?zP0(_ER4ghmIv89MszQXN1`4iRP1e+}&&kc33SarpN2gLn8#g+AL^CSX%v%dm?w z?uRaz%Y=l8|L6(1h=jk9w0GhL`rXk$T3A*WBossIFelPIvk}ufU*H0gd{hf(y!2=s zt{_W~#)Xe`R0|k=+@geM78VX!&ILu0Bn~C@N6Ru2q@hsP_`b0c=AMbfiMW)d&&1u% zAti6+<=Iez+*<1#49b$S;F-9YBpw?v(IzQ)Q`@X&mq>Z!{@Ko;lHhSE;4%jRPNfrT zLW^AD8aJg0fpR50n8=3jMUPAT$t^(yRhx+ie+-TY8Brzb>W<4KXO6{L27y3Q02p}N zsLY4cq2&aNv2sooWHM*KCQ`AA5=Bv92dlyGh{jNnCPwp29ClIeQ+J^**-hZ0XJYb2 z)FJ;z@mRwYv8~TU4z{sNi{cN@kCeRX zNoai{K21i}$Bk%nGqDV$@x0`XQ|xe&$)?hv>SpxmP?1SPCE3XI>q+ z^YdhP{c4b^;`j<|Bx{bZ!@rR3YZ{d;KBKpUjIe7_&a_l==hXNJLDHv_Sg0j>iq09XMaqs)Z9<}Aco z;r|(cnc0Zl4*#>P$?u0^tMQZ?N0e7)=8b$vA ze8dI=^i7CR*z&M1K`mHV17;C_yg;Fr2_pODr9ft0RNrPD|0cTiVQq6 zG(Fb>AsB$%l=i$#T$z@*5+)nD1F^TaBQ_L3?vJWPtVmX$nGSETwlfRaOvorga{|x} zBa_eS$(FOa=*JLivn;eTlu@p$<&l%9${wf_+u3?@w9zm1b}C|j8;aO50Db@?0c1S+ q_y6=+kDbfKif8h^o zs_N>hTInWr>u0KI6&?5U$(Ik=Hqy_jsonc*cLD~`xPgR(%L`?NE`YcP96&nk$o2+$+7HY`KkWm9xNpYn?%}5yHiG@}pH2C}Xyw}NC_`rpQ z#U7P#(M=wNn5g6XNJ5_^oJdCZiHPZ!H$#UuF~vx@B5^#`q_v~AGrJMXkk|U?aU|K$ z=ZJzCx(=5TM`#)zVDp5I#&|Os8TJlNB`3pju#t3yl?Da)i}{t(Dl;v3Nl|!a=uIEP zHx-odIJ<(Uh2vypcq;ym90^ZJZt>Ogcss`jbm0J6_^WShLA!IVFa>qMGYDO94r@d# zNr;Ok+K5U#i_D5BNt@zg`1PWMbcGAu2c1$??h7E+;JnkkftB@Huk7Zzk?b;`>Dz zt!}OrXLISIqg;@)IX>5(+rsduYpluuvwiNWXl1%4^z@s^w0!(SSz_+sL|p zIy{gx_shT$p>x5!j7*5KfjF={iqV%C*t`(2MRv|-&L(5UZByu3?75q7g zh(3v*CI5^bIe4&ychVMWXZ5?9Ci`7sT?Mb&NDI$OsvT+`86LF%v_`dYbT^v!)3VXP zGl`6d8ILKlE~X4`BG+REV>1cqKMHhJ)<4adCjEMJIdD^Uf!fR<){J{X{t7Ef)|QnE zQ~)=0H^02e1oI3cd-^A4(E=^uY&It-{TBz~R0{uP3YE6y>op7?tLl5{sn$BHp*eps zHd2ms6D_2WNBxI|d<3dCHRB|tqlC3&SZw0ph4y3<5@w!2dQA((=zjkyP$g!e1uuF?IZ&1Q4-%QJVYlFpRy=mFy ztN_0MAZ-b$cr0-yRO2>MnwZlk(bw6kEwmu z*i=|g_x%Oy2)_Tv$6jQ=(Qp;r~?eV&u-|R!Is+6kLwv3mC zXc^f4K`+wl-%^h5H~Yv1ZpyenyqKe#O!iP9{M~DQh$Ck4<&T4F4oS$gR-(*!Gb1=9 z3}>k%PXjpDy?2~yXs^JT`PqruI)hR2HqiV@fI9#wc7(+E{Ec|Elsd7x)A#1sskTH$wKtekBVuns)=z4}oHnG-%IqG0-*h8bw!gZ4{3j4$;tR&B)OCa`7| zwmC@H=c%5P#H&k`(Qoc)bBsI^4tO-6>Hjd-wiLX6Nos;^eD1j<9XFlo;?T0Z;Pyo0 zCFyTmbo&c*7p4N+kp3I#I0s+?yWzY}aye}}P9Y-(mIQI`Z=`pT0hFk*h=eB7D~0#la^l?~TpyU0p{#-Za}Ck`quVg2 zwQE~8O2n5lwv#Ml7H%T17~`XAT*suvrv7Sm$1!Q4DOOE&C>Vpu zPUGCki+vy;F2br8Lg)y~C213q#pA$Z8??uu{Q$AevUmh~2TkLfd*v|0-P`teE1PaI zU6OY9j47&~1Y=4YOsdn3Y5Ao)@)+>^C~tJJPs{{f%KTdaN12~M+dKdJAKp+W>BvR3Dqve4}PO)kH^AJKhi1fSwE~A)xijB@`=~IusRfNL&8{>qHUCd z_a|q;$`B@?BNIh9y^4fB(fMHo2bq)7c-92!s_=<+FV-jVELede;e#$XV@W+GfZj&t zy9HDw{iU3RR2T&q5nJ05RAL1mkw*4p#6%ACXTgokrgu3Qu-JFu@UGuae#jV#PZ8Ci z^HG7`YB;smG_4(&^NG=3JnFH-<~&924O*i*1u=?177fnQ%>x}TnXJv;Run1q3HFIj zuXfOF2iz7bQJa8KaveE8c-<5HD%1FQg;IMge_>oQEodmZl<`nmFG@`5PHS{g9dVdq z`_=&!j3>c3Jw6|gxmc-;;LIpoXN$=^Km}HSW768?2Q@9EE~=mH7VH8)BE}pY{@GTR zW5jr@ZPC!#G~QynJv<0!rj0=CO@QG5BcASUuRt3=vKLaI%?CLBR45X^e>e)SZ-SL1v7oqLIXybOFs)4@ijbBbYQ){YEtQhu}QNoXmAG} z;dam*O7V&#TO zlaag~w-66MIe5PZ8G^4F;9P&_CYGXPjBU${uHlfS;2o7Hlx;ym19`2aBdEZA{T|Zp zF7k>2q-@MgV%i)@j*fW=&m&=_M(# z`?j=lJ;swsS;f?#PwNAP8}xXiS@@RNDs(E7w~pUJu2iJr!32+6jgQ&ZjN5|)vJW6O z9l%6##;4*DR=oW~k8`*k!_d zop=X$z@cLb|Jv5)Gm~yiffDwwY73Vl;-x!lGL4;88{^2Nc_iju(D>U!#6}@por8 z$(*3qyydX{!OfjcrcM}@db*B17zo}H30W>C_SVsu?z&pM2?<}+r3pB&pfJ(>S9je* z8#z58QFW-U&u2-*IUx;yO~NK7MtyW?y6S@ty=r2c`O&FNfG~8_e3X!)iS>9kIXf|y ze&5?coD;JmPTpqqXPpInzEjVi<167giDXO~Rjz9{T1`D`?B88i9_qkDPxE^U4L>&C zXVC7#<86pj7ZjYtI}-{P-rmhWN0^`p9PZ+xvEep;oA@7i^-W-Pwq|DMc84a`|5d+ z%Tv6Ludza$PU5G;r@BR#{AgBb!K13*dJdtf)i17)6`n8)gd_R09>Ew}85;Y>>^hx{(2rBScjIbDVx z2~}W@5l*>Mo3BFHj*Li1Uy3+c94*u9>7B^<@R~Bd+ePoxjnEqJUdDT$lk@^=8}}k& zUjg_hz`tJj6KdJ2mwI1hXzkMwdmq4PLF^)cQUC?{CbX$AP5~o5I7TEm>#3dj0;VZ4 zt+Tv)ag8iuS(R|=;k9}NC#(mjqu!dp7|=sU{f)awpo98^MIuI5S1gP1vO-PKH=MPM z?w#VtPUZOso^KZm&bSn~0CE`Nvc%|A>s5`isFu?+x*fNj%G9^O^CF=U*h6AU)8MK0 z)?+7=EKcx)cDEtJsfX$H&~C>&u!Mu~ zkpFgGlaN+f)YDL?VT4f*2b3rFe{jopSm686_I+i2l}{J%PV?2C8)FZPcLcCE0j z2mOa0^o@YNRAUz2uVcZ2*3>~(^rtyo@hM9*(>w1d(|->5i`!|T@z1Hx_KerjYkI~% zh4EM0Rr@13TKGU#@r;gH&wx>V?n~np<2tHfch}9YedEpym~IiEkH2>2XhKHCWo7!6 z@Lt+p-rZh93$Mz{`10-x(3>e6N_Q5Hau`atE>WN%?GK6N?pw9`QZxgf#bPZ9_Sk8)t zbIL`KrMG}HYeO^{IDKIM!ET%s(xt&1cyiW_4ZlGgph3SnVfgjw{W28lgwmRpUdF4M zASQChmZ)I~cibvI*A`u(Y^T$0vO(34G*6Ezfmn5?j<@pq?&I_G1rxX!zli;>LcnIQ zLR{uH@hk|Z#_Sh6Tg$tD%2t(KgOl9Z0j`rsSalR;NLsZKo)fFH;JLb5 zAMWn^-2&u!!NRulD;ur z>5$e^Px{f2)_NfY&gGe|ICU8B6aRoW6R-3HxfeeHaDI`IE|>R<(Gt>`ppBIDyaBA} z+Fz&=Q1NIitZaMlpsmkrwF(E5zHn1zdB{sO75GbXq~g?YAn<_i5#VCVBN;uSZNb+z%atLzel%F7qxk(vt@t5;m&>4{a$ zE^$8jwl*HWV!K^y$J}o;6(bwO1YDw7AH2n`J@d&z}g+rk2IUF<(wGKW)!p4EEC^pUni4b{l z=`fs3HZOf1-z2{-U50OvdCRt{6a%d!A@A;jV)>zW?f7FddwD)oIgc!V1$UCD6|?XG zQV-8J$^8|v_%P9|EW_)_#FhK|PJ#To#=hIiLdClh;tG`P5i3ZWqNYVSLkVnsb zKSq-em10TUP1e0Xi^4AAet*(46Jfc(9^Ktc)drU;^-Pbr$)^;pk&fes0P;QGPir_Z zH5x0PKoUPZp^VNIC{$yIYUlgwo`Zzur*#q7L;hH|4$`~j>&N3_a%KGjJcE>P7@S7Q zCi67+DhaRO-HaP0aj6?aL??;q?)c_>tI@K|I@_XNB#Fgj--eMHcCVhteDs)Nh&iu= zU8{92ak#4(@W;rTq!+YEpP1G#BkXc6NVJKBZH%Q7U1ZS4gmGurD}_)bL_z(Qg-V6C zg@yaRGZ`gmN~)_uxxH1QSmf8}Lpgnw5-5t|mnY@tH0bsQrFhBkh0)wXw)tQla^%`^ zwo7!74>zWcNIV(d>Jd-5qdTdtC|WOs22CkM50BRE>0(tL(c+#Yu^)V27<`$zFojR! z&7km4rEF+D;+sU?xPi)Xla1u*sD5tcQ;_>u-p2O*T`ZLe5)j2|a+?f~z2nmL5WMb& zOxZB1+j=CES8zmeI2pdF44)t?H>E&QcxaOz+>K*XNxutj&Vo4QKLvDd$B0pRp~wtC z3N{a=f_>!e&FLwBcr`ol5G{{4dc+M7oLQPNk9V+*NRT9Y2UM~eJ>pGresd|lM`E_b zxUP-QRIfQqRHCqb<;P2`fC9bWng{OP4$t~u{ z46kj*+dU%kkcHb0QUM+^V7ouY>R}Sp*9P*LJl-aY>z*8WxA-qIa>w%n>%jG}Eh_kT zOcv`US-j^~G6PY3y%n{ktWlJqn6O90ZrhhT0-3%iT~H6KPK8owUA811bA@q|azs9g z8F9j;hHB5^nrqg|e5lR3knk^8ZZOVSK~8gm+}iaW82h2!di)7- z>`nw%)3rM>YKf~3>Tsuzs^RYk7S7B&$5q9WSVL0xlxMvx4T64k&(k7d?y=b6MqK)9 zk41-jVCe^Wc@C7Ud_CtL07jBN^Rak_?B6qNT!c%-TUuXg_K0JB%J?34NNL!ZbhzRA z1I`XN)UE0STH*7E***z^msQz#z-hQrkQr5?&aT8|H^zgFM3X>HCI;E6rnZ?d2Me@${QyvisS7>oytv%iyw=#Pk=Lqca(&6OflQ? zSe#A{?2SpC_~&=32e0hOJ7efoX~bn^-M7g7z3~Q63K%fN11692Z^~T+tHKZ~uq~7W zK`MC#T<~LYfRC6O#;Rt(0v3|`hQ9a#+1ikTe$X1{n8uv9%*XJiB1x2H(N#|!XWvijqB@Nbdl<3->G7kqLaH12#O@!6*tG!Pra>VMV66cT1-zdJI0JpC@bvtSKz}p9 zE`U8xpm_*lbyA*h0}mK?->0q@NKRk?^=1MkD3C_3@AnKs*JA(&CZ zO53ReT1@U9OwQa>jo42BdKn_L|4D!D%Ru%TOg96ueXYIYw_inU2^o1P>gkxjK(%!q zVl&@BtfvOCF#rJoHVACa0DKGZ&Jx7B-t47JgJ4JDPz^1acQ`UI5eAhH-_Iq74-Lw^ z_+JnZ0Vtooe$uAQADl8D$q&x2f=#YO?7kJf<42&shJ+lRs@nFeT#HH7k%46E;o)o( z+|EFr4D Date: Wed, 5 Jun 2024 09:57:11 -0300 Subject: [PATCH 321/652] arch.sh: Fix syntax error Fix error of script failing with following error: PX4-Autopilot/Tools/setup/arch.sh: line 99: syntax error near unexpected token `;' --- Tools/setup/arch.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/setup/arch.sh b/Tools/setup/arch.sh index 8e19ee51015d..1ab164b2aaf4 100755 --- a/Tools/setup/arch.sh +++ b/Tools/setup/arch.sh @@ -95,7 +95,7 @@ if [[ $INSTALL_SIM == "true" ]]; then # java (jmavsim) sudo pacman -S --noconfirm --needed \ - ant + ant \ ; # Gazebo setup From b53d2cdf39dd28de822e31260311b2ee8ed79827 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 7 Jun 2024 09:28:37 +0200 Subject: [PATCH 322/652] battery: reset current filter when transitioning to FW (#22256) VTOLs consume a lot more power in hover copared to fixed-wing fligt. The remaining flight time thus should reset if one switches from MC to FW, as otherwise it takes several minutes until the estimate goes down. --- src/lib/battery/battery.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index f3a66fc0ed3c..21c4b906f367 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -305,19 +305,27 @@ void Battery::computeScale() float Battery::computeRemainingTime(float current_a) { float time_remaining_s = NAN; + bool reset_current_avg_filter = false; if (_vehicle_status_sub.updated()) { vehicle_status_s vehicle_status; if (_vehicle_status_sub.copy(&vehicle_status)) { _armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED); + + if (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && !_vehicle_status_is_fw) { + reset_current_avg_filter = true; + } + _vehicle_status_is_fw = (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING); } } _flight_phase_estimation_sub.update(); - if (!PX4_ISFINITE(_current_average_filter_a.getState()) || _current_average_filter_a.getState() < FLT_EPSILON) { + // reset filter if not feasible, negative or we did a VTOL transition to FW mode + if (!PX4_ISFINITE(_current_average_filter_a.getState()) || _current_average_filter_a.getState() < FLT_EPSILON + || reset_current_avg_filter) { _current_average_filter_a.reset(_params.bat_avrg_current); } From b8998933c9f0caa90351e46dbd8298c566c11f20 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 22 Apr 2024 13:49:23 +0200 Subject: [PATCH 323/652] AttitudeSetpoint.msg: FRD instead of NED for body frame Signed-off-by: Silvan Fuhrer --- msg/VehicleAttitudeSetpoint.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/VehicleAttitudeSetpoint.msg b/msg/VehicleAttitudeSetpoint.msg index e4f66c446a05..f52025d2bb51 100644 --- a/msg/VehicleAttitudeSetpoint.msg +++ b/msg/VehicleAttitudeSetpoint.msg @@ -11,7 +11,7 @@ float32[4] q_d # Desired quaternion for quaternion control # For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. -float32[3] thrust_body # Normalized thrust command in body NED frame [-1,1] +float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) From 1f7b4843ddd936ecacf54372c1693f87d5e31044 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 24 May 2024 09:58:46 +0200 Subject: [PATCH 324/652] FW position control: specify modes where FW_PN_R_SLEW_MAX applies Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/fw_path_navigation_params.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/fw_pos_control/fw_path_navigation_params.c b/src/modules/fw_pos_control/fw_path_navigation_params.c index 33ee50a8df8a..7666167452de 100644 --- a/src/modules/fw_pos_control/fw_path_navigation_params.c +++ b/src/modules/fw_pos_control/fw_path_navigation_params.c @@ -35,6 +35,7 @@ * Path navigation roll slew rate limit. * * The maximum change in roll angle setpoint per second. + * This limit is applied in all Auto modes, plus manual Position and Altitude modes. * * @unit deg/s * @min 0 From a0813549335b178c7b084d0ec27b2a6cd4ee1ae7 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Apr 2024 17:18:21 +0200 Subject: [PATCH 325/652] VTOL tailsitter: fix motor spike to 0 when finishing front transition Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/tailsitter.cpp | 6 ++++++ src/modules/vtol_att_control/vtol_type.cpp | 2 ++ src/modules/vtol_att_control/vtol_type.h | 1 + 3 files changed, 9 insertions(+) diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index b16a344ca6e8..5693d516b343 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -281,6 +281,12 @@ void Tailsitter::fill_actuator_outputs() _thrust_setpoint_0->xyz[2] = -_vehicle_thrust_setpoint_virtual_fw->xyz[0]; + // for the short period after switching to FW where there is no thrust published yet from the FW controller, + // keep publishing the last MC thrust to keep the motors running + if (hrt_elapsed_time(&_trans_finished_ts) < 50_ms) { + _thrust_setpoint_0->xyz[2] = _last_thr_in_mc; + } + /* allow differential thrust if enabled */ if (_param_vt_fw_difthr_en.get() & static_cast(VtFwDifthrEnBits::YAW_BIT)) { _torque_setpoint_0->xyz[0] = _vehicle_torque_setpoint_virtual_fw->xyz[0] * _param_vt_fw_difthr_s_y.get(); diff --git a/src/modules/vtol_att_control/vtol_type.cpp b/src/modules/vtol_att_control/vtol_type.cpp index 1d6f5b667a5c..e43dd7c912ad 100644 --- a/src/modules/vtol_att_control/vtol_type.cpp +++ b/src/modules/vtol_att_control/vtol_type.cpp @@ -164,6 +164,8 @@ void VtolType::update_transition_state() _time_since_trans_start = (float)(t_now - _transition_start_timestamp) * 1e-6f; check_quadchute_condition(); + + _last_thr_in_mc = _vehicle_thrust_setpoint_virtual_mc->xyz[2]; } float VtolType::update_and_get_backtransition_pitch_sp() diff --git a/src/modules/vtol_att_control/vtol_type.h b/src/modules/vtol_att_control/vtol_type.h index 78d078b5c8d8..8f9ae9ef3861 100644 --- a/src/modules/vtol_att_control/vtol_type.h +++ b/src/modules/vtol_att_control/vtol_type.h @@ -299,6 +299,7 @@ class VtolType : public ModuleParams // motors spinning up or cutting too fast when doing transitions. float _thrust_transition = 0.0f; // thrust value applied during a front transition (tailsitter & tiltrotor only) float _last_thr_in_fw_mode = 0.0f; + float _last_thr_in_mc = 0.f; hrt_abstime _trans_finished_ts = 0; hrt_abstime _transition_start_timestamp{0}; From 3a2b973abad44c84970018b72b58091bdd306b9e Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Apr 2024 17:55:42 +0200 Subject: [PATCH 326/652] VTOL Tailsitter: add front transition throttle blending Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/tailsitter.cpp | 8 +++++++- src/modules/vtol_att_control/tailsitter.h | 1 + 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index 5693d516b343..c05b4199d72b 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -238,7 +238,7 @@ void Tailsitter::update_transition_state() void Tailsitter::waiting_on_tecs() { // copy the last trust value from the front transition - _v_att_sp->thrust_body[0] = _thrust_transition; + _v_att_sp->thrust_body[0] = -_last_thr_in_mc; } void Tailsitter::update_fw_state() @@ -336,3 +336,9 @@ bool Tailsitter::isFrontTransitionCompletedBase() return transition_to_fw; } + +void Tailsitter::blendThrottleAfterFrontTransition(float scale) +{ + // note: MC throttle is negative (as in negative z), while FW throttle is positive (positive x) + _v_att_sp->thrust_body[0] = scale * _v_att_sp->thrust_body[0] + (1.f - scale) * (-_last_thr_in_mc); +} diff --git a/src/modules/vtol_att_control/tailsitter.h b/src/modules/vtol_att_control/tailsitter.h index 93fa0b2491be..39265a2e971d 100644 --- a/src/modules/vtol_att_control/tailsitter.h +++ b/src/modules/vtol_att_control/tailsitter.h @@ -66,6 +66,7 @@ class Tailsitter : public VtolType void update_fw_state() override; void fill_actuator_outputs() override; void waiting_on_tecs() override; + void blendThrottleAfterFrontTransition(float scale) override; private: enum class vtol_mode { From 77a3099154ab5022e1cc3a6d98843c310716cdcc Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Apr 2024 18:13:31 +0200 Subject: [PATCH 327/652] VTOL Tailsitter: fix motor spikes to 0 when starting back transition Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/tailsitter.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index c05b4199d72b..a919e99da667 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -301,11 +301,17 @@ void Tailsitter::fill_actuator_outputs() } } else { + _thrust_setpoint_0->xyz[2] = _vehicle_thrust_setpoint_virtual_mc->xyz[2]; + + // for the short period after starting the backtransition where there is no thrust published yet from the MC controller, + // keep publishing the last FW thrust to keep the motors running + if (_vtol_mode == vtol_mode::TRANSITION_BACK && _time_since_trans_start < 0.05f) { + _thrust_setpoint_0->xyz[2] = -_last_thr_in_fw_mode; + } + _torque_setpoint_0->xyz[0] = _vehicle_torque_setpoint_virtual_mc->xyz[0]; _torque_setpoint_0->xyz[1] = _vehicle_torque_setpoint_virtual_mc->xyz[1]; _torque_setpoint_0->xyz[2] = _vehicle_torque_setpoint_virtual_mc->xyz[2]; - - _thrust_setpoint_0->xyz[2] = _vehicle_thrust_setpoint_virtual_mc->xyz[2]; } // Control surfaces From f119b15ff1865db5f6cef51525a4d7801c8fe4ca Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Apr 2024 19:24:22 +0200 Subject: [PATCH 328/652] VTOL Tailsitter: set differential thrust to 0 in first 50ms of front transition Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/tailsitter.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index a919e99da667..272ad4cb448f 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -281,12 +281,6 @@ void Tailsitter::fill_actuator_outputs() _thrust_setpoint_0->xyz[2] = -_vehicle_thrust_setpoint_virtual_fw->xyz[0]; - // for the short period after switching to FW where there is no thrust published yet from the FW controller, - // keep publishing the last MC thrust to keep the motors running - if (hrt_elapsed_time(&_trans_finished_ts) < 50_ms) { - _thrust_setpoint_0->xyz[2] = _last_thr_in_mc; - } - /* allow differential thrust if enabled */ if (_param_vt_fw_difthr_en.get() & static_cast(VtFwDifthrEnBits::YAW_BIT)) { _torque_setpoint_0->xyz[0] = _vehicle_torque_setpoint_virtual_fw->xyz[0] * _param_vt_fw_difthr_s_y.get(); @@ -300,6 +294,15 @@ void Tailsitter::fill_actuator_outputs() _torque_setpoint_0->xyz[2] = _vehicle_torque_setpoint_virtual_fw->xyz[2] * _param_vt_fw_difthr_s_r.get(); } + // for the short period after switching to FW where there is no thrust published yet from the FW controller, + // keep publishing the last MC thrust to keep the motors running + if (hrt_elapsed_time(&_trans_finished_ts) < 50_ms) { + _thrust_setpoint_0->xyz[2] = _last_thr_in_mc; + _torque_setpoint_0->xyz[0] = 0.f; + _torque_setpoint_0->xyz[1] = 0.f; + _torque_setpoint_0->xyz[2] = 0.f; + } + } else { _thrust_setpoint_0->xyz[2] = _vehicle_thrust_setpoint_virtual_mc->xyz[2]; From b5988ed38fc9d50ea722b2dcf33470a2f4bd4446 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Apr 2024 19:58:05 +0200 Subject: [PATCH 329/652] VTOL Tailsitter: add back transition throttle blending Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/tailsitter.cpp | 10 ++++++++++ src/modules/vtol_att_control/tailsitter.h | 4 ++++ 2 files changed, 14 insertions(+) diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index 272ad4cb448f..ea326b059a6f 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -225,6 +225,11 @@ void Tailsitter::update_transition_state() _v_att_sp->thrust_body[2] = _mc_virtual_att_sp->thrust_body[2]; + if (_vtol_mode == vtol_mode::TRANSITION_BACK) { + const float progress = math::constrain(_time_since_trans_start / B_TRANS_THRUST_BLENDING_DURATION, 0.f, 1.f); + blendThrottleBeginningBackTransition(progress); + } + _v_att_sp->timestamp = hrt_absolute_time(); const Eulerf euler_sp(_q_trans_sp); @@ -351,3 +356,8 @@ void Tailsitter::blendThrottleAfterFrontTransition(float scale) // note: MC throttle is negative (as in negative z), while FW throttle is positive (positive x) _v_att_sp->thrust_body[0] = scale * _v_att_sp->thrust_body[0] + (1.f - scale) * (-_last_thr_in_mc); } + +void Tailsitter::blendThrottleBeginningBackTransition(float scale) +{ + _v_att_sp->thrust_body[2] = scale * _v_att_sp->thrust_body[2] + (1.f - scale) * (-_last_thr_in_fw_mode); +} diff --git a/src/modules/vtol_att_control/tailsitter.h b/src/modules/vtol_att_control/tailsitter.h index 39265a2e971d..135acd6c92aa 100644 --- a/src/modules/vtol_att_control/tailsitter.h +++ b/src/modules/vtol_att_control/tailsitter.h @@ -54,6 +54,9 @@ static constexpr float PITCH_THRESHOLD_AUTO_TRANSITION_TO_FW = -1.05f; // -60° // [rad] Pitch threshold required for completing transition to hover in automatic transitions static constexpr float PITCH_THRESHOLD_AUTO_TRANSITION_TO_MC = -0.26f; // -15° +// [s] Thrust blending duration from fixed-wing to back transition throttle +static constexpr float B_TRANS_THRUST_BLENDING_DURATION = 0.5f; + class Tailsitter : public VtolType { @@ -67,6 +70,7 @@ class Tailsitter : public VtolType void fill_actuator_outputs() override; void waiting_on_tecs() override; void blendThrottleAfterFrontTransition(float scale) override; + void blendThrottleBeginningBackTransition(float scale); private: enum class vtol_mode { From 199a2f43be59918cdead845e144e1a83cdfbac5b Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Sun, 21 Apr 2024 23:37:00 +0200 Subject: [PATCH 330/652] VTOL Tailsitter: treat back transition abort like a front transition for throttle blending. Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/tailsitter.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index ea326b059a6f..cc6fd976f2d4 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -121,6 +121,7 @@ void Tailsitter::update_vtol_state() case vtol_mode::TRANSITION_BACK: // failsafe into fixed wing mode _vtol_mode = vtol_mode::FW_MODE; + _trans_finished_ts = hrt_absolute_time(); break; } } From 831160389e04df1372aea322e48237f4fdebed15 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Sun, 21 Apr 2024 23:57:21 +0200 Subject: [PATCH 331/652] VTOL Tailsitter: remove throttle spike also for quad-chute Signed-off-by: Silvan Fuhrer --- src/modules/vtol_att_control/tailsitter.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index cc6fd976f2d4..af95a05083c3 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -67,6 +67,10 @@ void Tailsitter::update_vtol_state() if (_vtol_vehicle_status->fixed_wing_system_failure) { // Failsafe event, switch to MC mode immediately + if (_vtol_mode != vtol_mode::MC_MODE) { + _transition_start_timestamp = hrt_absolute_time(); + } + _vtol_mode = vtol_mode::MC_MODE; } else if (!_attc->is_fixed_wing_requested()) { @@ -314,7 +318,7 @@ void Tailsitter::fill_actuator_outputs() // for the short period after starting the backtransition where there is no thrust published yet from the MC controller, // keep publishing the last FW thrust to keep the motors running - if (_vtol_mode == vtol_mode::TRANSITION_BACK && _time_since_trans_start < 0.05f) { + if (_vtol_mode != vtol_mode::TRANSITION_FRONT_P1 && hrt_elapsed_time(&_transition_start_timestamp) < 50_ms) { _thrust_setpoint_0->xyz[2] = -_last_thr_in_fw_mode; } From 5c64a3ed93eec536b8bad98824eab04a83eb30a5 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Fri, 7 Jun 2024 17:15:12 +0200 Subject: [PATCH 332/652] Rover Ackermann module (#23024) New module handling Ackermann rover guidance and control. Only enabled in SITL and in the rover builds for now. --- ROMFS/px4fmu_common/init.d/CMakeLists.txt | 7 + .../airframes/50010_ackermann_rover_generic | 12 + .../init.d/airframes/CMakeLists.txt | 6 + .../init.d/rc.rover_ackermann_apps | 11 + .../init.d/rc.rover_ackermann_defaults | 13 + ROMFS/px4fmu_common/init.d/rc.vehicle_setup | 9 + boards/px4/fmu-v5/rover.px4board | 1 + boards/px4/fmu-v5x/rover.px4board | 2 + boards/px4/fmu-v6c/rover.px4board | 1 + boards/px4/fmu-v6u/rover.px4board | 1 + boards/px4/fmu-v6x/rover.px4board | 1 + boards/px4/fmu-v6xrt/rover.px4board | 1 + boards/px4/sitl/default.px4board | 1 + msg/CMakeLists.txt | 1 + msg/RoverAckermannGuidanceStatus.msg | 10 + src/modules/logger/logged_topics.cpp | 1 + src/modules/rover_ackermann/CMakeLists.txt | 47 +++ src/modules/rover_ackermann/Kconfig | 6 + .../rover_ackermann/RoverAckermann.cpp | 162 +++++++++ .../rover_ackermann/RoverAckermann.hpp | 108 ++++++ .../RoverAckermannGuidance/CMakeLists.txt | 39 +++ .../RoverAckermannGuidance.cpp | 321 ++++++++++++++++++ .../RoverAckermannGuidance.hpp | 190 +++++++++++ src/modules/rover_ackermann/module.yaml | 177 ++++++++++ 24 files changed, 1128 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/airframes/50010_ackermann_rover_generic create mode 100644 ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps create mode 100644 ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults create mode 100644 msg/RoverAckermannGuidanceStatus.msg create mode 100644 src/modules/rover_ackermann/CMakeLists.txt create mode 100644 src/modules/rover_ackermann/Kconfig create mode 100644 src/modules/rover_ackermann/RoverAckermann.cpp create mode 100644 src/modules/rover_ackermann/RoverAckermann.hpp create mode 100644 src/modules/rover_ackermann/RoverAckermannGuidance/CMakeLists.txt create mode 100644 src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp create mode 100644 src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp create mode 100644 src/modules/rover_ackermann/module.yaml diff --git a/ROMFS/px4fmu_common/init.d/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/CMakeLists.txt index 34b255e2555f..90b14f812f02 100644 --- a/ROMFS/px4fmu_common/init.d/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/CMakeLists.txt @@ -84,6 +84,13 @@ if(CONFIG_MODULES_DIFFERENTIAL_DRIVE) ) endif() +if(CONFIG_MODULES_ROVER_ACKERMANN) + px4_add_romfs_files( + rc.rover_ackermann_apps + rc.rover_ackermann_defaults + ) +endif() + if(CONFIG_MODULES_UUV_ATT_CONTROL) px4_add_romfs_files( rc.uuv_apps diff --git a/ROMFS/px4fmu_common/init.d/airframes/50010_ackermann_rover_generic b/ROMFS/px4fmu_common/init.d/airframes/50010_ackermann_rover_generic new file mode 100644 index 000000000000..66b3dc0cabba --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/50010_ackermann_rover_generic @@ -0,0 +1,12 @@ +#!/bin/sh +# +# @name Generic ackermann rover +# +# @type Rover +# @class Rover +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# + +. ${R}etc/init.d/rc.rover_ackermann_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index 89498206c3e9..f763a4376606 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -149,6 +149,12 @@ if(CONFIG_MODULES_DIFFERENTIAL_DRIVE) ) endif() +if(CONFIG_MODULES_ROVER_ACKERMANN) + px4_add_romfs_files( + 50010_ackermann_rover_generic + ) +endif() + if(CONFIG_MODULES_UUV_ATT_CONTROL) px4_add_romfs_files( # [60000, 61000] (Unmanned) Underwater Robots diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps new file mode 100644 index 000000000000..0c77ab9aa6d0 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps @@ -0,0 +1,11 @@ +#!/bin/sh +# Standard apps for a ackermann drive rover. + +# Start the attitude and position estimator. +ekf2 start & + +# Start rover ackermann drive controller. +rover_ackermann start + +# Start Land Detector. +land_detector start rover diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults new file mode 100644 index 000000000000..27cf144a329a --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults @@ -0,0 +1,13 @@ +#!/bin/sh +# Ackermann rover parameters. + +set VEHICLE_TYPE rover_ackermann +param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER +param set-default CA_AIRFRAME 5 # Rover (Ackermann) +param set-default CA_R_REV 1 # Motor is assumed to be reversible +param set-default EKF2_MAG_TYPE 1 # make sure magnetometer is fused even when not flying +param set-default EKF2_GBIAS_INIT 0.01 +param set-default EKF2_ANGERR_INIT 0.01 +param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius +param set-default NAV_RCL_ACT 6 # Disarm on manual control loss +param set-default COM_FAIL_ACT_T 1 # Delay before failsafe after rc loss diff --git a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup index 42b9c7e876d7..ef455c2ff759 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup +++ b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup @@ -41,6 +41,15 @@ then . ${R}etc/init.d/rc.rover_differential_apps fi +# +# Ackermann Rover setup. +# +if [ $VEHICLE_TYPE = rover_ackermann ] +then + # Start ackermann drive rover apps. + . ${R}etc/init.d/rc.rover_ackermann_apps +fi + # # VTOL setup. # diff --git a/boards/px4/fmu-v5/rover.px4board b/boards/px4/fmu-v5/rover.px4board index 3284f0bb7a1b..a0d173f4918d 100644 --- a/boards/px4/fmu-v5/rover.px4board +++ b/boards/px4/fmu-v5/rover.px4board @@ -19,3 +19,4 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_ACKERMANN=y diff --git a/boards/px4/fmu-v5x/rover.px4board b/boards/px4/fmu-v5x/rover.px4board index b8a1597b30ea..3e2b69dfac1b 100644 --- a/boards/px4/fmu-v5x/rover.px4board +++ b/boards/px4/fmu-v5x/rover.px4board @@ -14,3 +14,5 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set +CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_ACKERMANN=y diff --git a/boards/px4/fmu-v6c/rover.px4board b/boards/px4/fmu-v6c/rover.px4board index f754c54e36f7..553bc76a52c7 100644 --- a/boards/px4/fmu-v6c/rover.px4board +++ b/boards/px4/fmu-v6c/rover.px4board @@ -14,3 +14,4 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_ACKERMANN=y diff --git a/boards/px4/fmu-v6u/rover.px4board b/boards/px4/fmu-v6u/rover.px4board index f754c54e36f7..553bc76a52c7 100644 --- a/boards/px4/fmu-v6u/rover.px4board +++ b/boards/px4/fmu-v6u/rover.px4board @@ -14,3 +14,4 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_ACKERMANN=y diff --git a/boards/px4/fmu-v6x/rover.px4board b/boards/px4/fmu-v6x/rover.px4board index f754c54e36f7..553bc76a52c7 100644 --- a/boards/px4/fmu-v6x/rover.px4board +++ b/boards/px4/fmu-v6x/rover.px4board @@ -14,3 +14,4 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_ACKERMANN=y diff --git a/boards/px4/fmu-v6xrt/rover.px4board b/boards/px4/fmu-v6xrt/rover.px4board index 2e75c9bdb47b..101555842444 100644 --- a/boards/px4/fmu-v6xrt/rover.px4board +++ b/boards/px4/fmu-v6xrt/rover.px4board @@ -15,3 +15,4 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_ACKERMANN=y diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index 7dd7ce481a3f..cfbaf4ddc998 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -45,6 +45,7 @@ CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y CONFIG_MODULES_PAYLOAD_DELIVERER=y CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_REPLAY=y +CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_COMMON_SIMULATION=y diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index c53402bd0f35..53ec65cf9a55 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -178,6 +178,7 @@ set(msg_files RcParameterMap.msg RegisterExtComponentReply.msg RegisterExtComponentRequest.msg + RoverAckermannGuidanceStatus.msg Rpm.msg RtlStatus.msg RtlTimeEstimate.msg diff --git a/msg/RoverAckermannGuidanceStatus.msg b/msg/RoverAckermannGuidanceStatus.msg new file mode 100644 index 000000000000..3c34b63c63f2 --- /dev/null +++ b/msg/RoverAckermannGuidanceStatus.msg @@ -0,0 +1,10 @@ +uint64 timestamp # time since system start (microseconds) + +float32 actual_speed # [m/s] Rover ground speed +float32 desired_speed # [m/s] Rover desired ground speed +float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller +float32 heading_error # [deg] Heading error of the pure pursuit controller +float32 pid_throttle_integral # [-1, 1] Integral of the PID for the normalized throttle to control the rover speed during missions +float32 crosstrack_error # [m] Shortest distance from the vehicle to the path + +# TOPICS rover_ackermann_guidance_status diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 731f087f7934..b1d5b20f93b6 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -102,6 +102,7 @@ void LoggedTopics::add_default_topics() add_topic("position_setpoint_triplet", 200); add_optional_topic("px4io_status"); add_topic("radio_status"); + add_topic("rover_ackermann_guidance_status", 100); add_topic("rtl_time_estimate", 1000); add_topic("rtl_status", 2000); add_optional_topic("sensor_airflow", 100); diff --git a/src/modules/rover_ackermann/CMakeLists.txt b/src/modules/rover_ackermann/CMakeLists.txt new file mode 100644 index 000000000000..249a4748768d --- /dev/null +++ b/src/modules/rover_ackermann/CMakeLists.txt @@ -0,0 +1,47 @@ +############################################################################ +# +# Copyright (c) 2024 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(RoverAckermannGuidance) + +px4_add_module( + MODULE modules__rover_ackermann + MAIN rover_ackermann + SRCS + RoverAckermann.cpp + RoverAckermann.hpp + DEPENDS + RoverAckermannGuidance + px4_work_queue + MODULE_CONFIG + module.yaml +) diff --git a/src/modules/rover_ackermann/Kconfig b/src/modules/rover_ackermann/Kconfig new file mode 100644 index 000000000000..3ba13506598a --- /dev/null +++ b/src/modules/rover_ackermann/Kconfig @@ -0,0 +1,6 @@ +menuconfig MODULES_ROVER_ACKERMANN + bool "rover_ackermann" + default n + depends on MODULES_CONTROL_ALLOCATOR + ---help--- + Enable support for control of ackermann drive rovers diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp new file mode 100644 index 000000000000..2c6b8c30d478 --- /dev/null +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -0,0 +1,162 @@ +/**************************************************************************** + * + * 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 "RoverAckermann.hpp" + +using namespace time_literals; +using namespace matrix; + +RoverAckermann::RoverAckermann() : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) +{ + updateParams(); +} + +bool RoverAckermann::init() +{ + ScheduleOnInterval(10_ms); // 100 Hz + return true; +} + +void RoverAckermann::updateParams() +{ + ModuleParams::updateParams(); +} + +void RoverAckermann::Run() +{ + if (should_exit()) { + ScheduleClear(); + exit_and_cleanup(); + } + + // uORB subscriber updates + if (_parameter_update_sub.updated()) { + updateParams(); + } + + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status; + _vehicle_status_sub.copy(&vehicle_status); + _nav_state = vehicle_status.nav_state; + } + + // 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)) { + _motor_setpoint.steering = manual_control_setpoint.roll; + _motor_setpoint.throttle = manual_control_setpoint.throttle; + } + + } break; + + case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: + _motor_setpoint = _ackermann_guidance.purePursuit(); + break; + + default: // Unimplemented nav states will stop the rover + _motor_setpoint.steering = 0.f; + _motor_setpoint.throttle = 0.f; + break; + } + + hrt_abstime now = hrt_absolute_time(); + + // Publish to wheel motors + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + actuator_motors.control[0] = _motor_setpoint.throttle; + actuator_motors.timestamp = now; + _actuator_motors_pub.publish(actuator_motors); + + // Publish to servo + actuator_servos_s actuator_servos{}; + actuator_servos.control[0] = _motor_setpoint.steering; + actuator_servos.timestamp = now; + _actuator_servos_pub.publish(actuator_servos); +} + +int RoverAckermann::task_spawn(int argc, char *argv[]) +{ + RoverAckermann *instance = new RoverAckermann(); + + if (instance) { + _object.store(instance); + _task_id = task_id_is_work_queue; + + if (instance->init()) { + return PX4_OK; + } + + } else { + PX4_ERR("alloc failed"); + } + + delete instance; + _object.store(nullptr); + _task_id = -1; + + return PX4_ERROR; +} + +int RoverAckermann::custom_command(int argc, char *argv[]) +{ + return print_usage("unknown command"); +} + +int RoverAckermann::print_usage(const char *reason) +{ + if (reason) { + PX4_ERR("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +Rover state machine. +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("rover_ackermann", "controller"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + return 0; +} + +extern "C" __EXPORT int rover_ackermann_main(int argc, char *argv[]) +{ + return RoverAckermann::main(argc, argv); +} diff --git a/src/modules/rover_ackermann/RoverAckermann.hpp b/src/modules/rover_ackermann/RoverAckermann.hpp new file mode 100644 index 000000000000..101647dd4e20 --- /dev/null +++ b/src/modules/rover_ackermann/RoverAckermann.hpp @@ -0,0 +1,108 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include +#include +#include +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include +#include +#include + +// Standard library includes +#include + +// Local includes +#include "RoverAckermannGuidance/RoverAckermannGuidance.hpp" + +using namespace time_literals; + +class RoverAckermann : public ModuleBase, public ModuleParams, + public px4::ScheduledWorkItem +{ +public: + /** + * @brief Constructor for RoverAckermann + */ + RoverAckermann(); + ~RoverAckermann() override = default; + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + bool init(); + +protected: + void updateParams() override; + +private: + void Run() override; + + // uORB subscriptions + uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; + uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; + + // uORB publications + uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _actuator_servos_pub{ORB_ID(actuator_servos)}; + + // Instances + RoverAckermannGuidance _ackermann_guidance{this}; + + // Variables + int _nav_state{0}; + RoverAckermannGuidance::motor_setpoint _motor_setpoint; + + // Parameters + DEFINE_PARAMETERS( + (ParamInt) _param_r_rev + ) +}; diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/CMakeLists.txt b/src/modules/rover_ackermann/RoverAckermannGuidance/CMakeLists.txt new file mode 100644 index 000000000000..72928c7e25be --- /dev/null +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/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(RoverAckermannGuidance + RoverAckermannGuidance.cpp +) + +target_link_libraries(RoverAckermannGuidance PUBLIC pid) +target_include_directories(RoverAckermannGuidance PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp new file mode 100644 index 000000000000..d718df0ad49e --- /dev/null +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -0,0 +1,321 @@ +/**************************************************************************** + * + * 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 "RoverAckermannGuidance.hpp" + +#include + +using namespace matrix; +using namespace time_literals; + +RoverAckermannGuidance::RoverAckermannGuidance(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + pid_init(&_pid_throttle, PID_MODE_DERIVATIV_NONE, 0.001f); +} + +void RoverAckermannGuidance::updateParams() +{ + ModuleParams::updateParams(); + pid_set_parameters(&_pid_throttle, + _param_ra_p_speed.get(), // Proportional gain + _param_ra_i_speed.get(), // Integral gain + 0, // Derivative gain + 1, // Integral limit + 1); // Output limit +} + +RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit() +{ + // Initializations + float desired_speed{0.f}; + float desired_steering{0.f}; + float vehicle_yaw{0.f}; + float actual_speed{0.f}; + + // 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); + } + + if (_local_position_sub.updated()) { + vehicle_local_position_s local_position{}; + _local_position_sub.copy(&local_position); + + if (!_global_local_proj_ref.isInitialized() + || (_global_local_proj_ref.getProjectionReferenceTimestamp() != local_position.ref_timestamp)) { + _global_local_proj_ref.initReference(local_position.ref_lat, local_position.ref_lon, local_position.ref_timestamp); + } + + _curr_pos_local = Vector2f(local_position.x, local_position.y); + const Vector3f rover_velocity = {local_position.vx, local_position.vy, local_position.vz}; + actual_speed = rover_velocity.norm(); + } + + if (_position_setpoint_triplet_sub.updated()) { + updateWaypoints(); + } + + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + matrix::Quatf vehicle_attitude_quaternion = Quatf(vehicle_attitude.q); + vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); + } + + if (_mission_result_sub.updated()) { + mission_result_s mission_result{}; + _mission_result_sub.copy(&mission_result); + _mission_finished = mission_result.finished; + } + + // Guidance logic + if (!_mission_finished) { + // Calculate desired speed + const float distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _prev_wp(0), + _prev_wp(1)); + + if (distance_to_prev_wp <= _prev_acc_rad) { // Cornering speed + const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acc_rad; + desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); + + } else { // Default mission speed + desired_speed = _param_ra_miss_vel_def.get(); + } + + // Calculate desired steering + desired_steering = calcDesiredSteering(_curr_wp_local, _prev_wp_local, _curr_pos_local, _param_ra_lookahd_gain.get(), + _param_ra_lookahd_min.get(), _param_ra_lookahd_max.get(), _param_ra_wheel_base.get(), desired_speed, vehicle_yaw); + desired_steering = math::constrain(desired_steering, -_param_ra_max_steer_angle.get(), + _param_ra_max_steer_angle.get()); + } + + // Throttle PID + hrt_abstime now = hrt_absolute_time(); + const float dt = math::min((now - _time_stamp_last), 5000_ms) / 1e6f; + _time_stamp_last = now; + float throttle = 0.f; + + if (desired_speed < FLT_EPSILON) { + pid_reset_integral(&_pid_throttle); + + } else { + throttle = pid_calculate(&_pid_throttle, desired_speed, actual_speed, 0, + dt); + } + + if (_param_ra_max_speed.get() > 0.f) { // Feed-forward term + throttle += math::interpolate(desired_speed, + 0.f, _param_ra_max_speed.get(), + 0.f, 1.f); + } + + // Publish ackermann controller status (logging) + _rover_ackermann_guidance_status.timestamp = now; + _rover_ackermann_guidance_status.actual_speed = actual_speed; + _rover_ackermann_guidance_status.desired_speed = desired_speed; + _rover_ackermann_guidance_status.pid_throttle_integral = _pid_throttle.integral; + _rover_ackermann_guidance_status_pub.publish(_rover_ackermann_guidance_status); + + // Return motor setpoints + motor_setpoint motor_setpoint_temp; + motor_setpoint_temp.steering = math::interpolate(desired_steering, -_param_ra_max_steer_angle.get(), + _param_ra_max_steer_angle.get(), + -1.f, 1.f); + motor_setpoint_temp.throttle = math::constrain(throttle, 0.f, 1.f); + return motor_setpoint_temp; +} + +void RoverAckermannGuidance::updateWaypoints() +{ + position_setpoint_triplet_s position_setpoint_triplet{}; + _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); + + // Global waypoint coordinates + _curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon); + + if (position_setpoint_triplet.previous.valid) { + _prev_wp = Vector2d(position_setpoint_triplet.previous.lat, position_setpoint_triplet.previous.lon); + + } else { + _prev_wp = _curr_pos; + } + + if (position_setpoint_triplet.next.valid) { + _next_wp = Vector2d(position_setpoint_triplet.next.lat, position_setpoint_triplet.next.lon); + + } else { + _next_wp = _curr_wp; + } + + // Local waypoint coordinates + _curr_wp_local = _global_local_proj_ref.project(_curr_wp(0), _curr_wp(1)); + _prev_wp_local = _global_local_proj_ref.project(_prev_wp(0), _prev_wp(1)); + _next_wp_local = _global_local_proj_ref.project(_next_wp(0), _next_wp(1)); + + // Update acceptance radius + _prev_acc_rad = _acceptance_radius; + _acceptance_radius = updateAcceptanceRadius(_curr_wp_local, _prev_wp_local, _next_wp_local, _param_ra_acc_rad_def.get(), + _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_steer_angle.get()); +} + +float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, + const Vector2f &next_wp_local, const float &default_acceptance_radius, const float &acceptance_radius_gain, + const float &acceptance_radius_max, const float &wheel_base, const float &max_steer_angle) +{ + // Setup variables + const Vector2f curr_to_prev_wp_local = prev_wp_local - curr_wp_local; + const Vector2f curr_to_next_wp_local = next_wp_local - curr_wp_local; + float acceptance_radius = default_acceptance_radius; + + // Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment + if (curr_to_next_wp_local.norm() > FLT_EPSILON && curr_to_prev_wp_local.norm() > FLT_EPSILON) { + const float theta = acosf((curr_to_prev_wp_local * curr_to_next_wp_local) / (curr_to_prev_wp_local.norm() * + curr_to_next_wp_local.norm())) / 2.f; + const float min_turning_radius = wheel_base / sinf(max_steer_angle); + const float acceptance_radius_temp = min_turning_radius / tanf(theta); + const float acceptance_radius_temp_scaled = acceptance_radius_gain * + acceptance_radius_temp; // Scale geometric ideal acceptance radius to account for kinematic and dynamic effects + acceptance_radius = math::constrain(acceptance_radius_temp_scaled, default_acceptance_radius, + acceptance_radius_max); + } + + // Publish updated acceptance radius + position_controller_status_s pos_ctrl_status{}; + pos_ctrl_status.acceptance_radius = acceptance_radius; + pos_ctrl_status.timestamp = hrt_absolute_time(); + _position_controller_status_pub.publish(pos_ctrl_status); + return acceptance_radius; +} + +float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, + const Vector2f &curr_pos_local, const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, + const float &wheel_base, const float &desired_speed, const float &vehicle_yaw) +{ + // Calculate crosstrack error + const Vector2f prev_wp_to_curr_wp_local = curr_wp_local - prev_wp_local; + + if (prev_wp_to_curr_wp_local.norm() < FLT_EPSILON) { // Avoid division by 0 (this case should not happen) + return 0.f; + } + + const Vector2f prev_wp_to_curr_pos_local = curr_pos_local - prev_wp_local; + const Vector2f distance_on_line_segment = ((prev_wp_to_curr_pos_local * prev_wp_to_curr_wp_local) / + prev_wp_to_curr_wp_local.norm()) * prev_wp_to_curr_wp_local.normalized(); + const Vector2f crosstrack_error = (prev_wp_local + distance_on_line_segment) - curr_pos_local; + + // Calculate desired heading towards lookahead point + float desired_heading{0.f}; + float lookahead_distance = math::constrain(lookahead_gain * desired_speed, + lookahead_min, lookahead_max); + + if (crosstrack_error.longerThan(lookahead_distance)) { + if (crosstrack_error.norm() < lookahead_max) { + lookahead_distance = crosstrack_error.norm(); // Scale lookahead radius + desired_heading = calcDesiredHeading(curr_wp_local, prev_wp_local, curr_pos_local, lookahead_distance); + + } else { // Excessively large crosstrack error + desired_heading = calcDesiredHeading(curr_wp_local, curr_pos_local, curr_pos_local, lookahead_distance); + } + + } else { // Crosstrack error smaller than lookahead + desired_heading = calcDesiredHeading(curr_wp_local, prev_wp_local, curr_pos_local, lookahead_distance); + } + + // Calculate desired steering to reach lookahead point + const float heading_error = matrix::wrap_pi(desired_heading - vehicle_yaw); + + // For logging + _rover_ackermann_guidance_status.lookahead_distance = lookahead_distance; + _rover_ackermann_guidance_status.heading_error = (heading_error * 180.f) / (M_PI_F); + _rover_ackermann_guidance_status.crosstrack_error = crosstrack_error.norm(); + + // Calculate desired steering + if (math::abs_t(heading_error) <= M_PI_2_F) { + return atanf(2 * wheel_base * sinf(heading_error) / lookahead_distance); + + } else if (heading_error > FLT_EPSILON) { + return atanf(2 * wheel_base * (1.0f + sinf(heading_error - M_PI_2_F)) / + lookahead_distance); + + } else { + return atanf(2 * wheel_base * (-1.0f + sinf(heading_error + M_PI_2_F)) / + lookahead_distance); + } +} + +float RoverAckermannGuidance::calcDesiredHeading(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, + const Vector2f &curr_pos_local, + const float &lookahead_distance) +{ + // Setup variables + const float line_segment_slope = (curr_wp_local(1) - prev_wp_local(1)) / (curr_wp_local(0) - prev_wp_local(0)); + const float line_segment_rover_offset = prev_wp_local(1) - curr_pos_local(1) + line_segment_slope * (curr_pos_local( + 0) - prev_wp_local(0)); + const float a = -line_segment_slope; + const float c = -line_segment_rover_offset; + const float r = lookahead_distance; + const float x0 = -a * c / (a * a + 1.0f); + const float y0 = -c / (a * a + 1.0f); + + // Calculate intersection points + if (c * c > r * r * (a * a + 1.0f) + FLT_EPSILON) { // No intersection points exist + return 0.f; + + } else if (abs(c * c - r * r * (a * a + 1.0f)) < FLT_EPSILON) { // One intersection point exists + return atan2f(y0, x0); + + } else { // Two intersetion points exist + const float d = r * r - c * c / (a * a + 1.0f); + const float mult = sqrt(d / (a * a + 1.0f)); + const float ax = x0 + mult; + const float bx = x0 - mult; + const float ay = y0 - a * mult; + const float by = y0 + a * mult; + const Vector2f point1(ax, ay); + const Vector2f point2(bx, by); + const Vector2f distance1 = (curr_wp_local - curr_pos_local) - point1; + const Vector2f distance2 = (curr_wp_local - curr_pos_local) - point2; + + // Return intersection point closer to current waypoint + if (distance1.norm_squared() < distance2.norm_squared()) { + return atan2f(ay, ax); + + } else { + return atan2f(by, bx); + } + } +} diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp new file mode 100644 index 000000000000..f6446cdacb8a --- /dev/null +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -0,0 +1,190 @@ +/**************************************************************************** + * + * 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 +#include +#include +#include +#include + +// Standard library includes +#include +#include +#include +#include +#include +#include + +using namespace matrix; + +/** + * @brief Class for ackermann drive guidance. + */ +class RoverAckermannGuidance : public ModuleParams +{ +public: + /** + * @brief Constructor for RoverAckermannGuidance. + * @param parent The parent ModuleParams object. + */ + RoverAckermannGuidance(ModuleParams *parent); + ~RoverAckermannGuidance() = default; + + struct motor_setpoint { + float steering{0.f}; + float throttle{0.f}; + }; + + /** + * @brief Compute guidance for ackermann rover and return motor_setpoint for throttle and steering. + */ + motor_setpoint purePursuit(); + + /** + * @brief Update global/local waypoint coordinates and acceptance radius + */ + void updateWaypoints(); + + /** + * @brief Returns and publishes the acceptance radius for current waypoint based on the angle between a line segment + * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of + * the vehicle. + * @param curr_wp_local Current waypoint in local frame. + * @param prev_wp_local Previous waypoint in local frame. + * @param next_wp_local Next waypoint in local frame. + * @param default_acceptance_radius Default acceptance radius for waypoints. + * @param acceptance_radius_gain Scaling of the geometric optimal acceptance radius for the rover to cut corners. + * @param acceptance_radius_max Maximum value for the acceptance radius. + * @param wheel_base Rover wheelbase. + * @param max_steer_angle Rover maximum steer angle. + */ + float updateAcceptanceRadius(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, + const Vector2f &next_wp_local, const float &default_acceptance_radius, const float &acceptance_radius_gain, + const float &acceptance_radius_max, const float &wheel_base, const float &max_steer_angle); + + /** + * @brief Calculate and return desired steering input + * @param curr_wp_local Current waypoint in local frame. + * @param prev_wp_local Previous waypoint in local frame. + * @param curr_pos_local Current position of the vehicle in local frame. + * @param lookahead_gain Tuning parameter for the lookahead distance pure pursuit controller. + * @param lookahead_min Minimum lookahead distance. + * @param lookahead_max Maximum lookahead distance. + * @param wheel_base Rover wheelbase. + * @param desired_speed Desired speed for the rover. + * @param vehicle_yaw Current yaw of the rover. + */ + float calcDesiredSteering(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, const Vector2f &curr_pos_local, + const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, const float &wheel_base, + const float &desired_speed, const float &vehicle_yaw); + + /** + * @brief Return desired heading to the intersection point between a circle with a radius of + * lookahead_distance around the vehicle and a line segment from the previous to the current waypoint. + * @param curr_wp_local Current waypoint in local frame. + * @param prev_wp_local Previous waypoint in local frame. + * @param curr_pos_local Current position of the vehicle in local frame. + * @param lookahead_distance Radius of circle around vehicle. + */ + float calcDesiredHeading(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, const Vector2f &curr_pos_local, + const float &lookahead_distance); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + // uORB subscriptions + uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; + uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; + uORB::Subscription _local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _mission_result_sub{ORB_ID(mission_result)}; + + // uORB publications + uORB::Publication _rover_ackermann_guidance_status_pub{ORB_ID(rover_ackermann_guidance_status)}; + uORB::Publication _position_controller_status_pub{ORB_ID(position_controller_status)}; + rover_ackermann_guidance_status_s _rover_ackermann_guidance_status{}; + + + MapProjection _global_local_proj_ref{}; // Transform global to local coordinates. + + // Rover variables + Vector2d _curr_pos{}; + Vector2f _curr_pos_local{}; + PID_t _pid_throttle; + hrt_abstime _time_stamp_last{0}; + + // Waypoint variables + Vector2d _curr_wp{}; + Vector2d _next_wp{}; + Vector2d _prev_wp{}; + Vector2f _curr_wp_local{}; + Vector2f _prev_wp_local{}; + Vector2f _next_wp_local{}; + float _acceptance_radius{0.5f}; + float _prev_acc_rad{0.f}; + bool _mission_finished{false}; + + // Parameters + DEFINE_PARAMETERS( + (ParamFloat) _param_ra_wheel_base, + (ParamFloat) _param_ra_max_steer_angle, + (ParamFloat) _param_ra_lookahd_gain, + (ParamFloat) _param_ra_lookahd_max, + (ParamFloat) _param_ra_lookahd_min, + (ParamFloat) _param_ra_acc_rad_max, + (ParamFloat) _param_ra_acc_rad_def, + (ParamFloat) _param_ra_acc_rad_gain, + (ParamFloat) _param_ra_miss_vel_def, + (ParamFloat) _param_ra_miss_vel_min, + (ParamFloat) _param_ra_miss_vel_gain, + (ParamFloat) _param_ra_p_speed, + (ParamFloat) _param_ra_i_speed, + (ParamFloat) _param_ra_max_speed, + (ParamFloat) _param_nav_acc_rad + ) +}; diff --git a/src/modules/rover_ackermann/module.yaml b/src/modules/rover_ackermann/module.yaml new file mode 100644 index 000000000000..a3152b9e77be --- /dev/null +++ b/src/modules/rover_ackermann/module.yaml @@ -0,0 +1,177 @@ +module_name: Rover Ackermann + +parameters: + - group: Rover Ackermann + definitions: + RA_WHEEL_BASE: + description: + short: Wheel base + long: Distance from the front to the rear axle + type: float + unit: m + min: 0.001 + max: 100 + increment: 0.001 + decimal: 3 + default: 0.5 + + RA_MAX_STR_ANG: + description: + short: Maximum steering angle + long: The maximum angle that the rover can steer + type: float + unit: rad + min: 0.1 + max: 1.5708 + increment: 0.01 + decimal: 2 + default: 0.5236 + + RA_LOOKAHD_GAIN: + description: + short: Tuning parameter for the pure pursuit controller + long: Lower value -> More aggressive controller (beware overshoot/oscillations) + type: float + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + RA_LOOKAHD_MAX: + description: + short: Maximum lookahead distance for the pure pursuit controller + long: | + This is the maximum crosstrack error before the controller starts + targeting the current waypoint rather then the path between the previous + and next waypoint. + type: float + unit: m + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 10 + + RA_LOOKAHD_MIN: + description: + short: Minimum lookahead distance for the pure pursuit controller + type: float + unit: m + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + RA_ACC_RAD_MAX: + description: + short: Maximum acceptance radius + long: | + The controller scales the acceptance radius based on the angle between + the previous, current and next waypoint. Used as tuning parameter. + Higher value -> smoother trajectory at the cost of how close the rover gets + to the waypoint (Set equal to RA_ACC_RAD_DEF to disable corner cutting). + type: float + unit: m + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 3 + + RA_ACC_RAD_DEF: + description: + short: Default acceptance radius + type: float + unit: m + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 0.5 + + RA_ACC_RAD_GAIN: + description: + short: Tuning parameter for corner cutting + long: | + The geometric ideal acceptance radius is multiplied by this factor + to account for kinematic and dynamic effects. + Higher value -> The rover starts to cut the corner earlier. + type: float + min: 1 + max: 100 + increment: 0.01 + decimal: 2 + default: 2 + + RA_MISS_VEL_DEF: + description: + short: Default rover velocity during a mission + type: float + unit: m/s + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 3 + + RA_MISS_VEL_MIN: + description: + short: Minimum rover velocity during a mission + long: | + The velocity off the rover is reduced based on the corner it has to take + to smooth the trajectory (To disable this feature set it equal to RA_MISSION_VEL_DEF) + type: float + unit: m/s + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + RA_MISS_VEL_GAIN: + description: + short: Tuning parameter for the velocity reduction during cornering + long: Lower value -> More velocity reduction during cornering + type: float + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 5 + + RA_SPEED_P: + description: + short: Proportional gain for ground speed controller + type: float + min: 0 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + RA_SPEED_I: + description: + short: Integral gain for ground speed controller + type: float + min: 0 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + RA_MAX_SPEED: + description: + short: Speed the rover drives at maximum throttle + long: | + This is used for the feed-forward term of the speed controller. + A value of -1 disables the feed-forward term in which case the + Integrator (RA_SPEED_I) becomes necessary to track speed setpoints. + type: float + unit: m/s + min: -1 + max: 100 + increment: 0.01 + decimal: 2 + default: -1 From 2882e5c4e1da9860c38ea908587f55d2bc56cf25 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Fri, 7 Jun 2024 20:08:21 -0800 Subject: [PATCH 333/652] platforms: nuttx: SerialImpl: fix hang if baudrate is 0 (#23238) --- platforms/nuttx/src/px4/common/SerialImpl.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index dd1ce6a3b8b8..3131435a0f5c 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -74,6 +74,11 @@ bool SerialImpl::configure() int speed; switch (_baudrate) { + case 0: + // special case, if baudrate is 0 it hangs entire system + PX4_ERR("baudrate not specified"); + return false; + case 9600: speed = B9600; break; case 19200: speed = B19200; break; From 746322d6d2ab94b04681d6e88c64ac69082b9d87 Mon Sep 17 00:00:00 2001 From: asifpatankar Date: Thu, 30 May 2024 11:33:56 +0900 Subject: [PATCH 334/652] Update ubuntu.sh with Linux Mint 21.3 version --- Tools/setup/ubuntu.sh | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh index f509ced4eb1a..077cfda56bf1 100755 --- a/Tools/setup/ubuntu.sh +++ b/Tools/setup/ubuntu.sh @@ -66,6 +66,8 @@ elif [[ "${UBUNTU_RELEASE}" == "20.04" ]]; then echo "Ubuntu 20.04" elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then echo "Ubuntu 22.04" +elif [[ "${UBUNTU_RELEASE}" == "21.3" ]]; then + echo "Linux Mint 21.3" fi @@ -146,7 +148,7 @@ if [[ $INSTALL_NUTTX == "true" ]]; then util-linux \ vim-common \ ; - if [[ "${UBUNTU_RELEASE}" == "20.04" || "${UBUNTU_RELEASE}" == "22.04" ]]; then + if [[ "${UBUNTU_RELEASE}" == "20.04" || "${UBUNTU_RELEASE}" == "22.04" || "${UBUNTU_RELEASE}" == "21.3" ]]; then sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \ kconfig-frontends \ ; @@ -205,6 +207,8 @@ if [[ $INSTALL_SIM == "true" ]]; then java_version=13 elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then java_version=11 + elif [[ "${UBUNTU_RELEASE}" == "21.3" ]]; then + java_version=11 else java_version=14 fi @@ -228,6 +232,17 @@ if [[ $INSTALL_SIM == "true" ]]; then echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null sudo apt-get update -y --quiet + # Install Gazebo + gazebo_packages="gz-garden" + elif [[ "${UBUNTU_RELEASE}" == "21.3" ]]; then + echo "Gazebo (Garden) 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 + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable jammy main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null + + sudo apt-get update -y --quiet + # Install Gazebo gazebo_packages="gz-garden" else From 2524ac8c2bd832738b4c300dfa0434c5821e3c0c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 8 Dec 2023 14:24:37 +0100 Subject: [PATCH 335/652] boards/px4/fmu-v{5,6}x: do not enable mavlink on ethernet for skynode --- boards/px4/fmu-v5x/init/rc.board_defaults | 18 +++++++++--------- boards/px4/fmu-v6x/init/rc.board_defaults | 18 +++++++++--------- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/boards/px4/fmu-v5x/init/rc.board_defaults b/boards/px4/fmu-v5x/init/rc.board_defaults index 30ff624b2f63..b85ca2d318e7 100644 --- a/boards/px4/fmu-v5x/init/rc.board_defaults +++ b/boards/px4/fmu-v5x/init/rc.board_defaults @@ -3,15 +3,6 @@ # board specific defaults #------------------------------------------------------------------------------ -# Mavlink ethernet (CFG 1000) -param set-default MAV_2_CONFIG 1000 -param set-default MAV_2_BROADCAST 1 -param set-default MAV_2_MODE 0 -param set-default MAV_2_RADIO_CTL 0 -param set-default MAV_2_RATE 100000 -param set-default MAV_2_REMOTE_PRT 14550 -param set-default MAV_2_UDP_PRT 14550 - param set-default SENS_EN_INA238 0 param set-default SENS_EN_INA228 0 param set-default SENS_EN_INA226 1 @@ -20,6 +11,15 @@ if ver hwbasecmp 008 009 00a 010 011 then # Skynode: use the "custom participant" config for uxrce_dds_client param set-default UXRCE_DDS_PTCFG 2 +else + # Mavlink ethernet (CFG 1000) + param set-default MAV_2_CONFIG 1000 + param set-default MAV_2_BROADCAST 1 + param set-default MAV_2_MODE 0 + param set-default MAV_2_RADIO_CTL 0 + param set-default MAV_2_RATE 100000 + param set-default MAV_2_REMOTE_PRT 14550 + param set-default MAV_2_UDP_PRT 14550 fi safety_button start diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index 95d873475b15..8aca92787108 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -3,15 +3,6 @@ # board specific defaults #------------------------------------------------------------------------------ -# Mavlink ethernet (CFG 1000) -param set-default MAV_2_CONFIG 1000 -param set-default MAV_2_BROADCAST 1 -param set-default MAV_2_MODE 0 -param set-default MAV_2_RADIO_CTL 0 -param set-default MAV_2_RATE 100000 -param set-default MAV_2_REMOTE_PRT 14550 -param set-default MAV_2_UDP_PRT 14550 - # By disabling all 3 INA modules, we use the # i2c_launcher instead. param set-default SENS_EN_INA238 0 @@ -22,6 +13,15 @@ if ver hwbasecmp 009 010 011 then # Skynode: use the "custom participant" config for uxrce_dds_client param set-default UXRCE_DDS_PTCFG 2 +else + # Mavlink ethernet (CFG 1000) + param set-default MAV_2_CONFIG 1000 + param set-default MAV_2_BROADCAST 1 + param set-default MAV_2_MODE 0 + param set-default MAV_2_RADIO_CTL 0 + param set-default MAV_2_RATE 100000 + param set-default MAV_2_REMOTE_PRT 14550 + param set-default MAV_2_UDP_PRT 14550 fi safety_button start From a90cdcfe80448e3d87c9075af4555691bafe256f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 8 Dec 2023 14:25:30 +0100 Subject: [PATCH 336/652] boards/px4/fmu-v{5,6}x: enable uxrce_dds_client on ethernet by default --- boards/px4/fmu-v5x/init/rc.board_defaults | 4 +++- boards/px4/fmu-v6x/init/rc.board_defaults | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/boards/px4/fmu-v5x/init/rc.board_defaults b/boards/px4/fmu-v5x/init/rc.board_defaults index b85ca2d318e7..e0381e98867a 100644 --- a/boards/px4/fmu-v5x/init/rc.board_defaults +++ b/boards/px4/fmu-v5x/init/rc.board_defaults @@ -9,8 +9,10 @@ param set-default SENS_EN_INA226 1 if ver hwbasecmp 008 009 00a 010 011 then - # Skynode: use the "custom participant" config for uxrce_dds_client + # Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client param set-default UXRCE_DDS_PTCFG 2 + param set-default UXRCE_DDS_AG_IP 170461697 + param set-default UXRCE_DDS_CFG 1000 else # Mavlink ethernet (CFG 1000) param set-default MAV_2_CONFIG 1000 diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index 8aca92787108..cb1eb580a429 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -11,8 +11,10 @@ param set-default SENS_EN_INA226 0 if ver hwbasecmp 009 010 011 then - # Skynode: use the "custom participant" config for uxrce_dds_client + # Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client param set-default UXRCE_DDS_PTCFG 2 + param set-default UXRCE_DDS_AG_IP 170461697 + param set-default UXRCE_DDS_CFG 1000 else # Mavlink ethernet (CFG 1000) param set-default MAV_2_CONFIG 1000 From 52ac9336c4ec61e963b79e13e5c721838e46464e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 8 Dec 2023 14:29:50 +0100 Subject: [PATCH 337/652] boards: change default IP from 192.168.0.3 to 10.41.10.2 192.168.0.x is often used by routers for WIFI/ethernet networks, and thus can create conflicts. This can happen for example if a companion is connected to the FMU via ethernet and at the same time connects to a WIFI network as DHCP client. --- boards/ark/fmu-v6x/nuttx-config/nsh/defconfig | 4 ++-- boards/av/x-v1/nuttx-config/nsh/defconfig | 4 ++-- boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig | 4 ++-- boards/nxp/mr-canhubk3/nuttx-config/sysview/defconfig | 4 ++-- boards/px4/fmu-v5x/nuttx-config/nsh/defconfig | 4 ++-- boards/px4/fmu-v5x/nuttx-config/test/defconfig | 4 ++-- boards/px4/fmu-v6x/nuttx-config/nsh/defconfig | 4 ++-- boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig | 4 ++-- boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig | 4 ++-- src/systemcmds/netman/Kconfig | 4 ++-- 10 files changed, 20 insertions(+), 20 deletions(-) diff --git a/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig index 17da75424e9f..f5e59d2c3781 100644 --- a/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig @@ -147,8 +147,8 @@ CONFIG_NETDB_DNSSERVER_NOADDR=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_MONITOR=y CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 diff --git a/boards/av/x-v1/nuttx-config/nsh/defconfig b/boards/av/x-v1/nuttx-config/nsh/defconfig index d5e403904764..1a2237008684 100644 --- a/boards/av/x-v1/nuttx-config/nsh/defconfig +++ b/boards/av/x-v1/nuttx-config/nsh/defconfig @@ -139,8 +139,8 @@ CONFIG_NETDB_DNSSERVER_NOADDR=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 CONFIG_NETUTILS_TELNETD=y diff --git a/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig b/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig index 77861ee5976b..3d9767bc9220 100644 --- a/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig +++ b/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig @@ -158,8 +158,8 @@ CONFIG_NETDEV_LATEINIT=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_MONITOR=y CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 diff --git a/boards/nxp/mr-canhubk3/nuttx-config/sysview/defconfig b/boards/nxp/mr-canhubk3/nuttx-config/sysview/defconfig index e9d287c2cd1e..88758c3d5852 100644 --- a/boards/nxp/mr-canhubk3/nuttx-config/sysview/defconfig +++ b/boards/nxp/mr-canhubk3/nuttx-config/sysview/defconfig @@ -158,8 +158,8 @@ CONFIG_NETDEV_LATEINIT=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_MONITOR=y CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 diff --git a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig index 8c21923c6441..cfb7af2bd252 100644 --- a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig @@ -143,8 +143,8 @@ CONFIG_NETDB_DNSSERVER_NOADDR=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_MONITOR=y CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 diff --git a/boards/px4/fmu-v5x/nuttx-config/test/defconfig b/boards/px4/fmu-v5x/nuttx-config/test/defconfig index 12333125f90b..3261d4700c33 100644 --- a/boards/px4/fmu-v5x/nuttx-config/test/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/test/defconfig @@ -143,8 +143,8 @@ CONFIG_NETDB_DNSSERVER_NOADDR=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 CONFIG_NETUTILS_TELNETD=y diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index 87c8a46f04d1..333609282e00 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -147,8 +147,8 @@ CONFIG_NETDB_DNSSERVER_NOADDR=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_MONITOR=y CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index 28df156d1bb2..e58939226d33 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -202,8 +202,8 @@ CONFIG_NETDEV_LATEINIT=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_MONITOR=y CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 diff --git a/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig b/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig index 25c5120d5740..b28719b13e93 100644 --- a/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig +++ b/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig @@ -141,8 +141,8 @@ CONFIG_NETDB_DNSCLIENT_ENTRIES=8 CONFIG_NETDB_DNSSERVER_NOADDR=y CONFIG_NETDEV_PHY_IOCTL=y CONFIG_NETINIT_DNS=y -CONFIG_NETINIT_DNSIPADDR=0XC0A800FE -CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 CONFIG_NETUTILS_TELNETD=y diff --git a/src/systemcmds/netman/Kconfig b/src/systemcmds/netman/Kconfig index 60fa395f45ac..6502969ddf8a 100644 --- a/src/systemcmds/netman/Kconfig +++ b/src/systemcmds/netman/Kconfig @@ -14,8 +14,8 @@ menuconfig USER_NETMAN config NETMAN_FALLBACK_IPADDR hex "Fallback IPv4 address" - default 0XC0A80003 + default 0xA290A02 depends on SYSTEMCMDS_NETMAN ---help--- If NETINIT_DHCPC is set, getting an IP from DHCP server is first attempted. - If this fails, this IP address is used as a static fallback. + If this fails, this IP address is used as a static fallback (default=10.41.10.2). From b9aa8818a44ad3267dc398a4df5094f2434ffa15 Mon Sep 17 00:00:00 2001 From: Ruoyu Wang Date: Mon, 10 Jun 2024 15:10:19 +0800 Subject: [PATCH 338/652] kakute f7/h7/h7mini/h7v2: fix EKF2_IMU_CTRL typo --- boards/holybro/kakutef7/init/rc.board_defaults | 2 +- boards/holybro/kakuteh7/init/rc.board_defaults | 2 +- boards/holybro/kakuteh7mini/init/rc.board_defaults | 2 +- boards/holybro/kakuteh7v2/init/rc.board_defaults | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/boards/holybro/kakutef7/init/rc.board_defaults b/boards/holybro/kakutef7/init/rc.board_defaults index 7a3bc92e844a..2ad7443124e6 100644 --- a/boards/holybro/kakutef7/init/rc.board_defaults +++ b/boards/holybro/kakutef7/init/rc.board_defaults @@ -15,7 +15,7 @@ param set-default SYS_AUTOSTART 4050 param set-default SYS_HAS_MAG 0 # enable gravity fusion -param set-default EKF2_IMU_CONTROL 7 +param set-default EKF2_IMU_CTRL 7 # the startup tune is not great on a binary output buzzer, so disable it param set-default CBRK_BUZZER 782090 diff --git a/boards/holybro/kakuteh7/init/rc.board_defaults b/boards/holybro/kakuteh7/init/rc.board_defaults index 47dea71be617..4ca8626ebe61 100644 --- a/boards/holybro/kakuteh7/init/rc.board_defaults +++ b/boards/holybro/kakuteh7/init/rc.board_defaults @@ -25,7 +25,7 @@ param set-default SYS_AUTOSTART 4050 # use EKF2 without mag param set-default SYS_HAS_MAG 0 # and enable gravity fusion -param set-default EKF2_IMU_CONTROL 7 +param set-default EKF2_IMU_CTRL 7 # the startup tune is not great on a binary output buzzer, so disable it param set-default CBRK_BUZZER 782090 diff --git a/boards/holybro/kakuteh7mini/init/rc.board_defaults b/boards/holybro/kakuteh7mini/init/rc.board_defaults index 4503905262e8..a0ccc7e101e5 100644 --- a/boards/holybro/kakuteh7mini/init/rc.board_defaults +++ b/boards/holybro/kakuteh7mini/init/rc.board_defaults @@ -25,7 +25,7 @@ param set-default SYS_AUTOSTART 4050 # use EKF2 without mag param set-default SYS_HAS_MAG 0 # and enable gravity fusion -param set-default EKF2_IMU_CONTROL 7 +param set-default EKF2_IMU_CTRL 7 # the startup tune is not great on a binary output buzzer, so disable it param set-default CBRK_BUZZER 782090 diff --git a/boards/holybro/kakuteh7v2/init/rc.board_defaults b/boards/holybro/kakuteh7v2/init/rc.board_defaults index 4503905262e8..a0ccc7e101e5 100644 --- a/boards/holybro/kakuteh7v2/init/rc.board_defaults +++ b/boards/holybro/kakuteh7v2/init/rc.board_defaults @@ -25,7 +25,7 @@ param set-default SYS_AUTOSTART 4050 # use EKF2 without mag param set-default SYS_HAS_MAG 0 # and enable gravity fusion -param set-default EKF2_IMU_CONTROL 7 +param set-default EKF2_IMU_CTRL 7 # the startup tune is not great on a binary output buzzer, so disable it param set-default CBRK_BUZZER 782090 From 3710a9ef6ea236ac90510f0cb074f640ef2f6b08 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 6 Jun 2024 15:32:50 +1200 Subject: [PATCH 339/652] gimbal: fix auto RC and MAVLink mode This fixes various edge cases when input is set to both: RC and MAVLink gimbal protocol v2. Specifically: - We no longer immediately reset primary control if there is no update, otherwise this will reset immediately after an commands. - Talking of commands: GIMBAL_MANAGER_CONFIGURE no longer switches control to MAVLink but only an actual incoming setpoint command does. - And incoming setpoint command only triggers UpdatedActiveOnce which means we will check RC again afterwards and if there is big movement switch back to RC. That's the intuitive thing to do until we have better reporting about who/what is in control. - Also, with RC we no longer always set us to be in control but only on major movement. --- src/modules/gimbal/gimbal.cpp | 10 ---------- src/modules/gimbal/input_mavlink.cpp | 6 ++++-- src/modules/gimbal/input_rc.cpp | 5 ++++- src/modules/gimbal/output_rc.cpp | 3 ++- 4 files changed, 10 insertions(+), 14 deletions(-) diff --git a/src/modules/gimbal/gimbal.cpp b/src/modules/gimbal/gimbal.cpp index 5893d29738f2..804f792fc65e 100644 --- a/src/modules/gimbal/gimbal.cpp +++ b/src/modules/gimbal/gimbal.cpp @@ -207,16 +207,6 @@ static int gimbal_thread_main(int argc, char *argv[]) update_params(param_handles, params); } - if (thread_data.last_input_active == -1) { - // Reset control as no one is active anymore, or yet. - thread_data.control_data.sysid_primary_control = 0; - thread_data.control_data.compid_primary_control = 0; - // If the output is set to AUX we still want the input to be able to control the gimbal - // via mavlink, so we set the device_compid to 1. This follows the mavlink spec which states - // that the gimbal_device_id should be between 1 and 6. - thread_data.control_data.device_compid = params.mnt_mode_out == 0 ? 1 : 0; - } - InputBase::UpdateResult update_result = InputBase::UpdateResult::NoUpdate; if (thread_data.input_objs_len > 0) { diff --git a/src/modules/gimbal/input_mavlink.cpp b/src/modules/gimbal/input_mavlink.cpp index ac7cbc4e7fd3..101ebf1e2716 100644 --- a/src/modules/gimbal/input_mavlink.cpp +++ b/src/modules/gimbal/input_mavlink.cpp @@ -856,7 +856,9 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_ control_data.compid_primary_control = new_compid_primary_control; } - return UpdateResult::UpdatedActive; + // Just doing the configuration doesn't mean there is actually an update to use yet. + // After that we still need to have an actual setpoint. + return UpdateResult::NoUpdate; // TODO: support secondary control // TODO: support gimbal device id for multiple gimbals @@ -880,7 +882,7 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_ _ack_vehicle_command(vehicle_command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED); - return UpdateResult::UpdatedActive; + return UpdateResult::UpdatedActiveOnce; } else { PX4_INFO("GIMBAL_MANAGER_PITCHYAW from %d/%d denied, in control: %d/%d", diff --git a/src/modules/gimbal/input_rc.cpp b/src/modules/gimbal/input_rc.cpp index c512cda254ee..c15f916ab9a4 100644 --- a/src/modules/gimbal/input_rc.cpp +++ b/src/modules/gimbal/input_rc.cpp @@ -120,9 +120,12 @@ InputRC::UpdateResult InputRC::_read_control_data_from_subscription(ControlData return false; }(); - if (already_active || major_movement) { + if (major_movement) { control_data.sysid_primary_control = _parameters.mav_sysid; control_data.compid_primary_control = _parameters.mav_compid; + } + + if (already_active || major_movement) { if (_parameters.mnt_rc_in_mode == 0) { // We scale manual input from roll -180..180, pitch -90..90, yaw, -180..180 degrees. diff --git a/src/modules/gimbal/output_rc.cpp b/src/modules/gimbal/output_rc.cpp index a5878b3801aa..4b48349a4dfb 100644 --- a/src/modules/gimbal/output_rc.cpp +++ b/src/modules/gimbal/output_rc.cpp @@ -61,7 +61,8 @@ void OutputRC::update(const ControlData &control_data, bool new_setpoints, uint8 _stream_device_attitude_status(); - // If the output is RC, then it means we are also the gimbal device. gimbal_device_id = (uint8_t)_parameters.mnt_mav_compid_v1; + // If the output is RC, then we signal this by referring to compid 1. + gimbal_device_id = 1; // _angle_outputs are in radians, gimbal_controls are in [-1, 1] gimbal_controls_s gimbal_controls{}; From 0932f50d79ebeb00b71832260aa042921ef1667a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 6 Jun 2024 15:45:12 +1200 Subject: [PATCH 340/652] mavlink: enable gimbal controls in QGC over USB --- src/modules/mavlink/mavlink_main.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index aaae2464eeb5..989cccdb7acf 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1647,6 +1647,8 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); configure_stream_local("GPS_RAW_INT", unlimited_rate); configure_stream_local("GPS_STATUS", 1.0f); + configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 0.5f); + configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); configure_stream_local("HIGHRES_IMU", 50.0f); configure_stream_local("HOME_POSITION", 0.5f); configure_stream_local("HYGROMETER_SENSOR", 1.0f); From 5513dfa95d850338d3e738e130f0beb049da5842 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 31 Jan 2024 12:41:02 +0100 Subject: [PATCH 341/652] AirspeedSelector: define start/stop delay params as floats Signed-off-by: Silvan Fuhrer --- src/modules/airspeed_selector/AirspeedValidator.hpp | 4 ++-- src/modules/airspeed_selector/airspeed_selector_main.cpp | 4 ++-- src/modules/airspeed_selector/airspeed_selector_params.c | 6 ++++-- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/modules/airspeed_selector/AirspeedValidator.hpp b/src/modules/airspeed_selector/AirspeedValidator.hpp index ba8f5c1a305a..4ce2949623a5 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.hpp +++ b/src/modules/airspeed_selector/AirspeedValidator.hpp @@ -162,8 +162,8 @@ class AirspeedValidator // states of airspeed valid declaration bool _airspeed_valid{true}; ///< airspeed valid (pitot or groundspeed-windspeed) - int _checks_fail_delay{3}; ///< delay for airspeed invalid declaration after single check failure (Sec) - int _checks_clear_delay{-1}; ///< delay for airspeed valid declaration after all checks passed again (Sec) + float _checks_fail_delay{2.f}; ///< delay for airspeed invalid declaration after single check failure (Sec) + float _checks_clear_delay{-1.f}; ///< delay for airspeed valid declaration after all checks passed again (Sec) uint64_t _time_checks_passed{0}; ///< time the checks have last passed (uSec) uint64_t _time_checks_failed{0}; ///< time the checks have last not passed (uSec) diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index 4877ee94b620..a25e2d4768c7 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -182,8 +182,8 @@ class AirspeedModule : public ModuleBase, public ModuleParams, (ParamFloat) _tas_innov_threshold, /**< innovation check threshold */ (ParamFloat) _tas_innov_integ_threshold, /**< innovation check integrator threshold */ - (ParamInt) _checks_fail_delay, /**< delay to declare airspeed invalid */ - (ParamInt) _checks_clear_delay, /**< delay to declare airspeed valid again */ + (ParamFloat) _checks_fail_delay, /**< delay to declare airspeed invalid */ + (ParamFloat) _checks_clear_delay, /**< delay to declare airspeed valid again */ (ParamFloat) _param_fw_airspd_stall, (ParamFloat) _param_wind_sigma_max_synth_tas diff --git a/src/modules/airspeed_selector/airspeed_selector_params.c b/src/modules/airspeed_selector/airspeed_selector_params.c index 0b54d3b29760..eb6ebf1d4da8 100644 --- a/src/modules/airspeed_selector/airspeed_selector_params.c +++ b/src/modules/airspeed_selector/airspeed_selector_params.c @@ -210,8 +210,9 @@ PARAM_DEFINE_FLOAT(ASPD_FS_INTEG, 10.f); * @group Airspeed Validator * @min 1 * @max 10 + * @decimal 1 */ -PARAM_DEFINE_INT32(ASPD_FS_T_STOP, 2); +PARAM_DEFINE_FLOAT(ASPD_FS_T_STOP, 2.f); /** * Airspeed failsafe start delay @@ -223,8 +224,9 @@ PARAM_DEFINE_INT32(ASPD_FS_T_STOP, 2); * @group Airspeed Validator * @min -1 * @max 1000 + * @decimal 1 */ -PARAM_DEFINE_INT32(ASPD_FS_T_START, -1); +PARAM_DEFINE_FLOAT(ASPD_FS_T_START, -1.f); /** * Horizontal wind uncertainty threshold for synthetic airspeed. From 30b63f6a8252202d9bd17ceea1508a514ff8fee2 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 31 Jan 2024 12:43:32 +0100 Subject: [PATCH 342/652] AirspeedSelector: set default of ASPD_FS_T_STOP to 1 and clean up meta data Signed-off-by: Silvan Fuhrer --- src/modules/airspeed_selector/airspeed_selector_params.c | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/src/modules/airspeed_selector/airspeed_selector_params.c b/src/modules/airspeed_selector/airspeed_selector_params.c index eb6ebf1d4da8..9ef58a78c8bd 100644 --- a/src/modules/airspeed_selector/airspeed_selector_params.c +++ b/src/modules/airspeed_selector/airspeed_selector_params.c @@ -208,11 +208,10 @@ PARAM_DEFINE_FLOAT(ASPD_FS_INTEG, 10.f); * * @unit s * @group Airspeed Validator - * @min 1 - * @max 10 + * @min 0.0 * @decimal 1 */ -PARAM_DEFINE_FLOAT(ASPD_FS_T_STOP, 2.f); +PARAM_DEFINE_FLOAT(ASPD_FS_T_STOP, 1.f); /** * Airspeed failsafe start delay @@ -222,8 +221,7 @@ PARAM_DEFINE_FLOAT(ASPD_FS_T_STOP, 2.f); * * @unit s * @group Airspeed Validator - * @min -1 - * @max 1000 + * @min -1.0 * @decimal 1 */ PARAM_DEFINE_FLOAT(ASPD_FS_T_START, -1.f); From 1d8e8a1d8bdd69e97c59967dbb07bfc17140d09f Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Mon, 10 Jun 2024 13:04:55 -0600 Subject: [PATCH 343/652] boards: ark septentrio change safety led to open drain (#23247) --- boards/ark/septentrio-gps/src/board_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/ark/septentrio-gps/src/board_config.h b/boards/ark/septentrio-gps/src/board_config.h index 2263956bae0f..2d5f582075f1 100644 --- a/boards/ark/septentrio-gps/src/board_config.h +++ b/boards/ark/septentrio-gps/src/board_config.h @@ -47,7 +47,7 @@ #define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15) /* Safety LED */ -#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1) +#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1) /* Tone alarm output. */ #define TONE_ALARM_TIMER 2 /* timer 2 */ From 9ececfdd6514f4f39be531e29b25ed43eabac815 Mon Sep 17 00:00:00 2001 From: Frederik Markus <80588263+frede791@users.noreply.github.com> Date: Tue, 11 Jun 2024 09:50:55 +0200 Subject: [PATCH 344/652] update GCS connection loss failsafe in all gazebo models (#22299) * update GCS connection loss failsafe in all gazebo models Signed-off-by: frederik * cleanup and return of old parameter Signed-off-by: frederik --------- Signed-off-by: frederik Co-authored-by: Silvan Fuhrer --- ROMFS/px4fmu_common/init.d-posix/airframes/4001_gz_x500 | 1 + .../px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol | 1 + ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision | 2 ++ 3 files changed, 4 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4001_gz_x500 b/ROMFS/px4fmu_common/init.d-posix/airframes/4001_gz_x500 index bb6bedd386d1..bca3feddfb8b 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4001_gz_x500 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4001_gz_x500 @@ -52,3 +52,4 @@ param set-default SIM_GZ_EC_MAX3 1000 param set-default SIM_GZ_EC_MAX4 1000 param set-default MPC_THR_HOVER 0.60 +param set-default NAV_DLL_ACT 2 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 3390ee525cc4..dcd7c81d62ab 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -101,6 +101,7 @@ param set-default MPC_XY_VEL_I_ACC 4 param set-default MPC_XY_VEL_D_ACC 0.1 param set-default NAV_ACC_RAD 5 +param set-default NAV_DLL_ACT 2 param set-default VT_FWD_THRUST_EN 4 param set-default VT_F_TRANS_THR 0.75 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision b/ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision index 92560eb160df..acfcef896069 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision @@ -132,3 +132,5 @@ param set-default SIM_GZ_EC_MAX1 1100 param set-default SIM_GZ_EC_MAX2 1100 param set-default SIM_GZ_EC_MAX3 1100 param set-default SIM_GZ_EC_MAX4 1100 + +param set-default NAV_DLL_ACT 2 From 8ad93464c70c2330e92d21681b1f427922394fff Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 11 Jun 2024 14:09:36 +0200 Subject: [PATCH 345/652] AirspeedValidator: Remove extra delay from airspeed innovation check (#23244) * AirspeedValidator: remove additional one second of hysteresis for triggering innovation checks - this check already uses an integrator and so adding more delay just makes log analysis more difficult and does not really add any value Signed-off-by: RomanBapst * removed unnecessary conditions Signed-off-by: RomanBapst * AirspeedValidator: only disable innov checks if ASPD_FS_INTEG is negative Signed-off-by: Silvan Fuhrer * get rid of unnecessary check on innovation threshold parameter Signed-off-by: RomanBapst --------- Signed-off-by: RomanBapst Signed-off-by: Silvan Fuhrer Co-authored-by: Silvan Fuhrer --- src/modules/airspeed_selector/AirspeedValidator.cpp | 11 ++--------- src/modules/airspeed_selector/AirspeedValidator.hpp | 2 -- 2 files changed, 2 insertions(+), 11 deletions(-) diff --git a/src/modules/airspeed_selector/AirspeedValidator.cpp b/src/modules/airspeed_selector/AirspeedValidator.cpp index 4707774eb0c3..63343b402322 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.cpp +++ b/src/modules/airspeed_selector/AirspeedValidator.cpp @@ -222,16 +222,13 @@ AirspeedValidator::check_airspeed_innovation(uint64_t time_now, float estimator_ } // reset states if check is disabled, we are not flying or wind estimator was just initialized/reset - if (!_innovation_check_enabled || !_in_fixed_wing_flight || (time_now - _time_wind_estimator_initialized) < 5_s - || _tas_innov_integ_threshold <= 0.f) { + if (!_innovation_check_enabled || !_in_fixed_wing_flight || (time_now - _time_wind_estimator_initialized) < 5_s) { _innovations_check_failed = false; - _time_last_tas_pass = time_now; _aspd_innov_integ_state = 0.f; } else if (!lpos_valid || estimator_status_vel_test_ratio > 1.f || estimator_status_mag_test_ratio > 1.f) { //nav velocity data is likely not good //don't run the test but don't reset the check if it had previously failed when nav velocity data was still likely good - _time_last_tas_pass = time_now; _aspd_innov_integ_state = 0.f; } else { @@ -249,11 +246,7 @@ AirspeedValidator::check_airspeed_innovation(uint64_t time_now, float estimator_ _aspd_innov_integ_state = 0.f; } - if (_tas_innov_integ_threshold > 0.f && _aspd_innov_integ_state < _tas_innov_integ_threshold) { - _time_last_tas_pass = time_now; - } - - _innovations_check_failed = (time_now - _time_last_tas_pass) > TAS_INNOV_FAIL_DELAY; + _innovations_check_failed = _aspd_innov_integ_state > _tas_innov_integ_threshold; } _time_last_aspd_innov_check = time_now; diff --git a/src/modules/airspeed_selector/AirspeedValidator.hpp b/src/modules/airspeed_selector/AirspeedValidator.hpp index 4ce2949623a5..ed7008a5c621 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.hpp +++ b/src/modules/airspeed_selector/AirspeedValidator.hpp @@ -150,9 +150,7 @@ class AirspeedValidator float _tas_innov_threshold{1.0}; ///< innovation error threshold for triggering innovation check failure float _tas_innov_integ_threshold{-1.0}; ///< integrator innovation error threshold for triggering innovation check failure uint64_t _time_last_aspd_innov_check{0}; ///< time airspeed innovation was last checked (uSec) - uint64_t _time_last_tas_pass{0}; ///< last time innovation checks passed float _aspd_innov_integ_state{0.0f}; ///< integral of excess normalised airspeed innovation (sec) - static constexpr uint64_t TAS_INNOV_FAIL_DELAY{1_s}; ///< time required for innovation levels to pass or fail (usec) uint64_t _time_wind_estimator_initialized{0}; ///< time last time wind estimator was initialized (uSec) // states of load factor check From 5dd76332ba935295bdb55211d4997c5a435057f4 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 11 Jun 2024 10:46:04 +0200 Subject: [PATCH 346/652] Matrix: print full matrix already if only one element is not symmetric Signed-off-by: Silvan Fuhrer --- src/lib/matrix/matrix/Matrix.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/lib/matrix/matrix/Matrix.hpp b/src/lib/matrix/matrix/Matrix.hpp index 14400683f0ef..9e60b9ebef38 100644 --- a/src/lib/matrix/matrix/Matrix.hpp +++ b/src/lib/matrix/matrix/Matrix.hpp @@ -402,6 +402,7 @@ class Matrix } const Matrix &self = *this; + bool is_prev_symmetric = true; // assume symmetric until one element is not for (unsigned i = 0; i < M; i++) { printf("%2u|", i); // print row numbering @@ -410,7 +411,7 @@ class Matrix double d = static_cast(self(i, j)); // if symmetric don't print upper triangular elements - if ((M == N) && (j > i) && (i < N) && (j < M) + if (is_prev_symmetric && (M == N) && (j > i) && (i < N) && (j < M) && (fabs(d - static_cast(self(j, i))) < (double)eps) ) { // print empty space @@ -428,6 +429,8 @@ class Matrix } else { printf("% 6.5f ", d); } + + is_prev_symmetric = false; // not symmetric if once inside here } } From 0ce64e1b92945186c6cdba519a972fd064435fde Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Wed, 12 Jun 2024 03:20:40 +0200 Subject: [PATCH 347/652] ekf2: don't fuse optical flow samples when the current distance to the ground is larger than the reported maximum flow sensor distance Signed-off-by: RomanBapst --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) 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 f8218e883b24..160b0b24308e 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 @@ -55,9 +55,13 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && !_flow_sample_delayed.flow_rate.longerThan(_flow_max_rate); const bool is_tilt_good = (_R_to_earth(2, 2) > _params.range_cos_max_tilt); + // don't enforce this condition if terrain estimate is not valid as we have logic below to coast through bad range finder data + const bool is_within_max_sensor_dist = isTerrainEstimateValid() ? (_terrain_vpos - _state.pos(2) <= _flow_max_distance) : true; + if (is_quality_good && is_magnitude_good - && is_tilt_good) { + && is_tilt_good + && is_within_max_sensor_dist) { // compensate for body motion to give a LOS rate calcOptFlowBodyRateComp(imu_delayed); _flow_rate_compensated = _flow_sample_delayed.flow_rate - _flow_sample_delayed.gyro_rate.xy(); From db2f616400fd936066849f290812cb9cd92af6e3 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Wed, 12 Jun 2024 18:10:50 +0200 Subject: [PATCH 348/652] reduce transition pusher throttle (#23262) --- .../px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index dcd7c81d62ab..96bb25d69a52 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -104,6 +104,6 @@ param set-default NAV_ACC_RAD 5 param set-default NAV_DLL_ACT 2 param set-default VT_FWD_THRUST_EN 4 -param set-default VT_F_TRANS_THR 0.75 +param set-default VT_F_TRANS_THR 0.3 param set-default VT_TYPE 2 param set-default FD_ESCS_EN 0 From f8a42bcd5830777886e4ff088fb912f78495c87d Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Mon, 3 Jun 2024 13:06:47 +0800 Subject: [PATCH 349/652] boards: add new board micoair h743 --- boards/micoair/h743/bootloader.px4board | 3 + boards/micoair/h743/default.px4board | 85 ++++ .../h743/extras/micoair_h743_bootloader.bin | Bin 0 -> 41020 bytes boards/micoair/h743/firmware.prototype | 13 + boards/micoair/h743/init/rc.board_defaults | 24 + boards/micoair/h743/init/rc.board_extras | 7 + boards/micoair/h743/init/rc.board_sensors | 18 + .../h743/nuttx-config/bootloader/defconfig | 89 ++++ .../micoair/h743/nuttx-config/include/board.h | 426 ++++++++++++++++++ .../h743/nuttx-config/include/board_dma_map.h | 36 ++ .../micoair/h743/nuttx-config/nsh/defconfig | 245 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 +++++++++ .../h743/nuttx-config/scripts/script.ld | 228 ++++++++++ boards/micoair/h743/src/CMakeLists.txt | 68 +++ boards/micoair/h743/src/board_config.h | 197 ++++++++ boards/micoair/h743/src/bootloader_main.c | 75 +++ boards/micoair/h743/src/hw_config.h | 135 ++++++ boards/micoair/h743/src/i2c.cpp | 39 ++ boards/micoair/h743/src/init.c | 203 +++++++++ boards/micoair/h743/src/led.c | 114 +++++ boards/micoair/h743/src/sdio.c | 177 ++++++++ boards/micoair/h743/src/spi.cpp | 50 ++ boards/micoair/h743/src/timer_config.cpp | 56 +++ boards/micoair/h743/src/usb.c | 78 ++++ 24 files changed, 2579 insertions(+) create mode 100644 boards/micoair/h743/bootloader.px4board create mode 100644 boards/micoair/h743/default.px4board create mode 100644 boards/micoair/h743/extras/micoair_h743_bootloader.bin create mode 100644 boards/micoair/h743/firmware.prototype create mode 100644 boards/micoair/h743/init/rc.board_defaults create mode 100644 boards/micoair/h743/init/rc.board_extras create mode 100644 boards/micoair/h743/init/rc.board_sensors create mode 100644 boards/micoair/h743/nuttx-config/bootloader/defconfig create mode 100644 boards/micoair/h743/nuttx-config/include/board.h create mode 100644 boards/micoair/h743/nuttx-config/include/board_dma_map.h create mode 100644 boards/micoair/h743/nuttx-config/nsh/defconfig create mode 100644 boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/micoair/h743/nuttx-config/scripts/script.ld create mode 100644 boards/micoair/h743/src/CMakeLists.txt create mode 100644 boards/micoair/h743/src/board_config.h create mode 100644 boards/micoair/h743/src/bootloader_main.c create mode 100644 boards/micoair/h743/src/hw_config.h create mode 100644 boards/micoair/h743/src/i2c.cpp create mode 100644 boards/micoair/h743/src/init.c create mode 100644 boards/micoair/h743/src/led.c create mode 100644 boards/micoair/h743/src/sdio.c create mode 100644 boards/micoair/h743/src/spi.cpp create mode 100644 boards/micoair/h743/src/timer_config.cpp create mode 100644 boards/micoair/h743/src/usb.c diff --git a/boards/micoair/h743/bootloader.px4board b/boards/micoair/h743/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/micoair/h743/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/micoair/h743/default.px4board b/boards/micoair/h743/default.px4board new file mode 100644 index 000000000000..98d8f08aaf05 --- /dev/null +++ b/boards/micoair/h743/default.px4board @@ -0,0 +1,85 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_URT6="/dev/ttyS5" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_BOSCH_BMI270=y +CONFIG_COMMON_INS=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_ATXXXX=y +CONFIG_DRIVERS_PPS_CAPTURE=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_TAP_ESC=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_PAYLOAD_DELIVERER=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_FAILURE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +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_SERIAL_PASSTHRU=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/micoair/h743/extras/micoair_h743_bootloader.bin b/boards/micoair/h743/extras/micoair_h743_bootloader.bin new file mode 100644 index 0000000000000000000000000000000000000000..ca8c511279669e21033c2c92bded52ffc0e6e2d3 GIT binary patch literal 41020 zcmeFZdwdkt89#jHvb&QDWOG55B*0#RZn8lZf*8chvb#(!i-wD~T&ykxaUu#4P*Evt z2x+@A)mqzKAZ;KZ5s-ldb(REna^3fPc8P5*ec#XTzxR*d zem=8jX3lf&&-0w;c4k5v$TmAZtHKQ-~mXwL7RcnAKk95~u=q-um)?CuB zci3t9#719-Q0420tE%ist|~9s$dN3eZiHt<;fc(TMx>;h6^`BJtZF1?Vj{|KdWU(^ z|10N)BBDIoLzE$1L@DVe%41!P9VNeN>{#-v5~bC0RNXkntT5~$q({{)*Y3BB8Gs?m z{$8T!Q10_y(pZ>GvNjTu^&&0|IjiP1B0N^SrsjxB##=gl7FVY)?_=DTd6>;iHL;P7 zLq3{1IvRYXo};QE%iLK$->f9DPDMbQhODD%Cf>EqcPb7%Xa4KC(>Fi%j510&;AuXE zH~!nRF>6}!A=R2yf`5DTKR=7TLdG3Z9a&THE*J15%c<;|aR@2B-^lbd(KH$9UFZ?X z+C=D^M5|NLqJ=~&dTDibI-F=NdcTqHX&Mhm-ue>mj;ftmB}&a?r@{idGb@NToS46l zqHP(hn*cMW*lbGn9#!?|sSZ8o0IAQipbmW&tK_qWoUY(e^w@JdcY#171PCLh~tnw7wLSPl?rs@`@u`maQo-pet0( z-E}2@H&e|_8Y7cN;$UZ~V_qUDMk9HO<#c0MhN%)72{Dox`nv3?#K@SBp_EHuxWh9DHjvpjg8mFjRQ`e=^Hb6CwCPhlwzP}sw&mnX_IY9y@mA5)uA2Puu!(+s$i z$Ulkn7}8@%TaoXZ=~7-pZLN5|fcF=WUP5{ase)8NdJgG1q@74R$LkwnV<0{<{o(KX z+X#s;8f~pq$DMeHF#%8$3gcvF7>7Ra~dIwhHeqy2d=W5pi`hcG|+CL!5J^QBnnTg-ZBjbYB##=BTAEn{zpTv}5@%$Y?sSDsm&&`iwE%Q@2*Sd(!VZ#CdwI6zmO z*~CVxrV{e&L3-Z6Y_U>x*-JUCpS2Hc~`KSH^@&Oxjipl@S z50LLIW5@t^pd5slfsf!FX`_LAz|FML1G(h|x7NkqohaI*g!)V|+skYu$`v(RVzv@x zZBJS~vE)iNuTkV`>{!b!(YZ^jbSXSn*^yQi<4)tjkti*WM+;SGp&YbSHJYw-l2uR7WcF3#oG-PUd^y!lPaxQzkM2Xn-4arkCM&F&0^&Z}u;N^lP;BKkjBeKTI;-2KG zvNn3>vvkNw*0VvKhqexUY2?2qtpct@TzXtt-y&_ryE-~5V-am(uEZ%x+?-4tXELe9v2iYNIaNMmGobYzV%8TW7}LE( zsqH4_!9|>rDDQQn7V{A`^A3x$+T~JOT_59Ku~6KZ|3{(0hdzOS3*;PWrStxE91;Au zQtNyc=It_(7bD@4h_OB?_tZr)mOVAh%hu={(j{{n!=`&xIkk@b05|D6aPh8mZIBkcQYZpW|&I3O9ION9EvWJV!4KR_ObID_LbG5nOMC81{eNkG`mkwC3nq{1?=b zJ8-=bva;5k@QKsvt6!J2ZA$p+LV_|~*>t+YREw9V5k(wxI=5$H;<` zHbY@q$H>BxwqZq&bc`%2X-h9&)G@NSq%FhqXvato?SDyI=2X=AMQqN#JVD39=lr^b z&euR&G<_q)v-{nTx?(piPuC57wG7k~TSuM+JraF95sbKmI!4*q!+=77 z6GowqC`6_Il|3ZK70@e85+_a!Ft>3klfmTVA6M!ow=tuBt9!537GQ6)sO(%W$8h|9 z-IO+sctc~_$TZQV@{7zO*Ul&Ea#EYm2ul>5PS?XaZ+CDx7Wdjl{x%B1`A4%NGdZ6Hhm|v}B&R1>UVz<1iQ7kvNKJysC_VMO^49*y zC8m&33igvmA(17N2i`uFvD|+5i)KDluCeTa;TLk z2UV?7)0OE-@Po#CGLUMOFCyvD=kf@nyx7Gki+gxwNI!3hE2JgTdo@byJ1HtF;dG76)nnggCv=gZE-Z8VFvh)p#-_n_p9$BBj))zsQVBUmL}%Mp_T$p{X8yUApwKKLv2_)KmH6$0Mrk zGTMnP?j*6Ku8jxO%=(y|M2z|dW>R%+>RMvE68v6fl-IgL@<6=~)L&lre2qqY(KuNA z@*+QuRi5tW#ekofKCR?lO5Dc2l(3C?DSq22vt7KC=>SM+e%P?U3mk}OoII>RnD!WDd>X#SE_*5}oWKEIq z!Dvou9e?dDF-OAf5xU}|FLo3>zq(4)h%bp_#gXDE)w+WyuXgbxZfili3a2GXGoBJ# zUhvNlCyG|k;A`Fd2n})}*CHqN#83V7{`Xy`)^XzWD8y%Y|J{jq77<%0FgE&TZ1*KO zp}I(nF9z%@L`hZo5ocNww@*ecQFh>|C0gUpyC^1t8@@mq2c;5W^u=%qFAf%&P1{7Q z$P53yYo1nnci{4!P{}l6Y*vY#xh20iS*mglYSBvvLA8ha#usZuVx1C<)V=`R!~Btn zt<30TX|iaYSmr@%{xhQh28NYVB`SyK%P28E;%p zcb$dH!AT~b-C$8lxl|V)aW!k_gI1&3jk`@lskPesCk{#lUk zFtT4Uw=nkiG>MNZLm@nVg;NMy!O z!_!IiUU&19j36-4@|bZ){AC%Z%YZ6{@f`5a5(cDr0|kk=FfN=M6`g@$M<1 z;1WekF3KL2FS$?UM}m{T#DVKnh|D&l7#CvVIOTnHsyhJOodBPOZr~J-V{L4}2#l%*2WE`uRdS0oN1CA;?VkFx8{RC7!3e=* zaaTbk{CqECuX27LWQ?lJ025i|*ZpdgZg~-!L*2Pr&SMe{pu6fGBQSrBN@-eOXE5=2 z0@w8Klv*SX61E=PECJlCybkl(`O9)vsp{p$jo|e=do&~XC?zlHwTk5pd?<_T^=g!s ze)Mw`t1OCiL@8R40~gtG>0ZV>XK8sse%)G0BaZi%KEv4fPpC>zih zDksvKG|BMI)?J`lS4iM$}1CdL_!WZ*JPBl-@kH zBH_V(k3LHI$+_NhF5bay$-)klhSD17RopJ3l&h{xM$`wGjodC)Y42mUQE2cY(e7u4 z)B9?Sizqj%9Beh;V8*WWGRD)_+R3l0lrV@(IgkX)fRX*)C)Kj>n zJ(uN3_}7t68FKREL1NqrUd-O(wzJATeT-EnuA=>?lEIJ0X<2=>R%=TMX0PBwh2YS) z_Idp_$ta$EXpv-DNGv-Sz~&H%$_Y2_ZKdh&r0f-_i()FBdss8*+*51D&aza$;pr-; z5Ij;#EgX6N9BGdC5ox=(RnCwU`6t+?d;Iqmg3@}8_4guuxR+Ru1Z`TneCq3CKc7T8U zsYi<)C^z7c3ilA@;~rx51eT!(wbB}Ihg7ZQk7ci5EE^oDu1c>>I)t8a^RC|}ADYV0 zR?qdAvA_Ilo+9DbdQhV3db6#y3Be!F?{E7b?5-OC2LS1Tni)bPNM7kfDDZoWA5 zHJ;fFEED#2neFUm^skb84eR&9(m$?4%P(O4&TQa*eY!RU*1q@v-ECRru^y(H^Rm^Y zYjx56a+;{wMC;USr*n8I@bw1GrpcY;@vkcc+-Nh23`$$zU-A!ux&TepZ zlG3x4dhkeaD#eIgI>SWSwU2VPe9+g)7`KL@%LnacM>E^$=a ztoUzEA78AOynbRE+!6;pg1If-F%1%#!T+(e-D$uYe-YicpsgCaWGa`@J(2Rz>#qQ} znxDkkV6{}{cJme;XsvWDQ6_iCRwchd2Vch3p0NDCq#&Xk_+huO`?;zNo;e22nsPV*9MtK6RMcJjM@Yrv2Y7wJ3p04 zP-ZRWgvtt_CdwJ3JNRl%PFzs)XigO~E~PfdN6eGgvf$v4UF%yuY_ux$NvkLO9JXE{y)V%eP)#N5sg^rCn2vc_X(?LxMeKxs=RBrGaU398Ref5UYtd9HSA48 z@44v-qi7gUAs*~{6A%tSe0mMSp&>Wv@40E2QPf8v?)d?t?gt3=CgI;8?ubID4Lh)h z?!r}rYk;@?ui58{D76{8D78`DnUGZP4F`zvvP^89!35YDLV-y5yFOz5Hh5m1D9!>+oa(cK3ozzSE)ok13Glp} z>o0|^c&D_;dsezCds)SR@y$H z+_@@NrV4k0_)$~_r}IfHx7MwZ7`k&j_hW5*OIdDxj8d4b)N*cmn%TuF9cq?z8FI@Y z*lr#ENSIf%%F_InmG3w?$a8}*5BUvQ(iJ&!DFwVdLvs0(G18x@t@ZlCm^}5mtihT7M<~_eIQPg=f;!Jg{o@+nMWjx)Y+tIoZ2IEr1|v+FOqSyyn;8iH3MrzpY+~BXitf) zvHMxDs258lClthU-bWV+VW3&jefQS7l)H1K+~`_m!(vI-I|=J%QK93dmWd@-6U*O& z?*9vwbuce;%EVp;B ztNAp-z>ao3NtexbD6jg`I?GEAcX0Nh0gJ9gNs99{LTBe(Vu_NKSfUsctI7SUwl%Js z>muD;$IWeVgI#Tdxv8qwUeZ<=$65ZNl2$I8>yASnH+V@Km&o9r!sK}u2l!4$9{O|F zq5yh%S7IY;At;g9O5qdR21o1a@cQbbZO0F^on6aTW2o9aHZePrYLuJM=><7trGcS#iG)hM=vyF#r6$$6}52E$?HA-Kv(RH|X zygwdR(HwvG!W`+yVpy1Klm?rm3q4AXFOKdqkeJ@wN9&`uN6MR^yDmzEl`mPWuBZC@ z*xp^GyB5{>nPC@7O^S|*OD`)W%3sv>4a5i!@67hf{07&eoz6=EqRdpOB~K2Xk*T-t zvK%*6sIyQ__&WAhjdG^XA~i3D&JeYgFd}>mb>uXas)RaS@j;8Oh?zuvc0EB2Y~R!$ zLuY|ep4m_1DZc;ky{`y<`E~JAM_~@0>$Up@jMeOKTWF4sHNU|kX`&--xR8%=j*X6! zj*-fYzC}j=*$pi`)5JjMf`txafo;xm_~PKa(o$+G(v7WL#ETfS=2^dM(L2t;#}6&a z5eX#2{%}RlnMItK<33Y5f6oiAGZOy1 z(Xr^5Ia}NjI>xmwGPqk8_J^-_pItO>(V4{w?o@AS*_p)_#6f(luC+sMSbBCbywJua z$_?z<#oOmAX8QcsX=fMDfmBZUr@qd$m>0PN8Cb(L&f&rIsTL`&U2GI%n&E%zM8skhOBY7MJNsj{ zCE%gRl)Y?a! ze#5Q6$AeP5=<{>ZUiASzdC4UHM&d)mxm^Xs%AK&Rq>&(&<#aDwqVVJ@WD=#0U*+DD zDlTA#lzcP$W`4-A_qo)23LB>=zK3phF|LRU=~>1SR5J@VJ1nk`)XaRP!6aJ5W55TJAUKHH5rNCw(OS1rH5^R4r=)G_ z(1zJIe(14xxMWYPEgLKmKeW~MB4Scv?H%}!_Q)#6qAjj;5F!81$ z%C%HiLPQI-JkiqB^5j_+2P`0|1~;|be6%vbb!d4^SJF4Ih;b5xgB^qDE`fRAR?h2~ z%yG-+`7OG{rei8UOJke@{2Qe(n!{)heoqzYtgE#H{yExS zd7Wn!_3_QsB_1=E&8fGnN-vzt44XAsA@hb!D_u3eV-0Y>ydhXM4EstX{BVD}e6}j( zo;f3u-R4#Po{rEA#^c&J+tv1wD*^F$UI*veJl(QtE;DDAQ{kO+PzQ~3DSgtiir7vB z7p>Hq=XdB*7cB?2V!ibgU#)9uw5Onn7V&xU(pD$4srw|2=^=W-VXx!Bhtr2=q;GSQ zlXmdjLmj$Ntjgccs@(m!pMtBDRoVMlmAO3?>x_9sIgLk)s5re1F;F(z4@AY;P-AqC zVaoFAEt=xgc^Xf0+2>m9C6l^?oUt$bmj*f~jzJu8C`O_w)_U~wlFQcp8$>;1-vOBX zIu4v;km&NeR<&rgO=Oi1oc>J2QkDVhDfQQNK{BDU_Se47|Ec3IQ66K?)keb25sG)z z(@V`hR^3@Nmzg_jI6uA#>wY~O&#D>B%vlz23YW6cHFH{CF}G?q!?wFp z4U$jS+q7ZUx3v_%HcT@{d$&1aTxBa_%-|mRYaB+=(#CR>gV0_?!mmWA&QEux>tosQ zyPJSX;7iLsK}zp4bUjVxRq@85MOSP8vnPFFOP^&`N-=Ai%NWIN(_$rkrL?4ZRTJ7| zp>Hzg^$yxL?Z+p07YW}RwF`eh*AaY1pu7faLUBdFrPOIwjVyVLX`jt0#IB zXRF?E>P{Mhc~Q-cQker(W?D7OQ_LKh)tYrVyiBjmZ%g3$js2bvaul611Efw!Jm#&(l{ll?8 zURxK#wehEWSh2kBptNDY&i*4FI&)R3B5=clX=R>yx7X7rUi(Lb2#XrOEN%0No8_X?{@bLbv z>eF^@=rD<5p)!>--kLd~3hyG}B;?&ORyW#$w^g`16&&KBUKC;)Qb=QFOB4nXsF~IT zGhzX);5LY&C0281|9o&8tHW$rZ|N*AwSfCs*02`K(nxqhuLIm%R~QNR^gw@shw`0k z{NxyP*75PMF=Jj;r1{W?dGUWyTVfHVHQ=ucw3s?`T3`6F9ts03R9x?hy$W^-OHts}3#Ss}9reRWpo9-7oZSQExaX z)ZS40K`1fl#^$8Uf-pFGV~JoJM}!KbmDf^J9uXe8c0Go41Fksa(`y|r<4RG- zH?cWvaDWkk_Abw7H1)sUfY9c{r`@ljcM47bIz6 zmuE}bD!HkR-aIO^Sln}|EXtKW1;5!-kS?S1aj4HPKm62NPhFL1&);eyId2AOYpiW( zkc?T~S-Kmw60P;Fs}Jlx*nW@n-A!^RhwTvSzj1f;tj*e|g@tvIMnicYlRvZubMQ z8LaM%yw70Vz3+c`-n?=;a>MV_7CYaMwWz#5fR}w;#Jalk()*_Mky>4Gykn%_*~u<7 zuQ_ub@#{;w<$-;oM~NUrJQ4x#DtWHvv|3Z!qNX`oRD%%__<6wjWfn)8!=hX)wRE;x zES*1JM(N=TH4XlacYLF`q$a>hE!ZJPI3^@Ily`l2&X1V37H1^l)PeFF-$E{>=@m$& zhFLgiU>)LkyO!BRavVx-1>OO2V{vsYg-od+xhW?$6f>q5@1|VTDh_bbzHo8x19v`I5gYC4sa z+NkC0m5SP^C;-3G9I{tA2o7kfjuc)`bz8_IJ z4rPADKUDkU&teS~PLF=hsc?*bN7RLelUo8}yN8EsIR`8lNY9{U}mfnEAf-HV_hP`THjut{8iwd54j8Vrh% zln_`H9kmgjGs-c4+9z1d(cC8mU5L^BDX5pHix%t}yHr}I5mBdWxYt3)v=!`O-Ji=b z%nt-Jjie`D(X^BJ6X;L;l~eJagkw$j<5@i7zv zF%ezw%BOUsDK;bL&QrOI?jdws?UeiAu;B;YJ54{9d~)0lig&XG8Z?}F%-DXZO#v{)em;ByPRpdv5nLI%)|7s z(-HqJF&6Jwj~b8JB{}y*=XaWIP;_SI^t=pyJ20n%ewfpol`ld2nOeA{V@k?9E1_o@ zFdu^{?_iX2W^&u$WN2K5oaOH!3N>))=J@`${`!Rimo(Lkg zUFV10EtoW+A;9)$yI$@Zg4jf%rB2PT+x&}GQqD>7>E-i_R$Sp8_5}2!6)FQCW+ePemC7?6kjZG-@@xK2-;Kl))1aw_Ni}H5W!F5=gYSl} zA!UnmQ7d!{#Jv0`mv=C__QVFSqvpJ})FZ$bD(J#^cJwWw1uVZHQoMRu`>Y0Bl>doQ`~;&vb5oRjk$> zQ4{km3Rwo+#|k8ZE)w%+Gd)e~3LQ7~hmZAC750aN(f_~oyl_t>ye{$rB6B;JQk!L8 z_@=J4MXbod{-2rXRJ|FD==AoRKVHs0LClFgY+7dC0}F;d#D`XBAd@)Ukf0weKUT|( zt5olIEKpYSx|~Y2(DCSsB^?ZMcB;kYXM@C&d6Q$*iQ0o|*1UtNJvr0vQ;jB{nrPDX za4AgQCiRZVIvXvq26sEu!P74UiMh0h;y@>MJPz^fR3{nV_~2BZ<-xmm!dFRg?W~tG z_Cgl7lo1=#!rT!KTFP9Yb<4b;cPaiy zK9Azw9PjM1^kS2;da|i=C4+0SNr^CshBM8XH>7y`ybAMnZ-4mfe%Q~to-oq+?F}FN zke;ZBBj@15p!Dz=(&La}DUMNlMJv_E=mlQgiYvai1{^q%(6dua-|8-J|J5F#$ifq1o?X*)TXqldOf;Cj+3h7CK87hldcto@`l2?iFK?2D_^h-2W z^3U*R{QGl8{eM1}Uwc-gKH3}L3!kHELL<3((%Zv?Q5MK(%#HM9-6Zr68H2y<{Z(zngCX~dz zapjGrwAS*vdkqFeXTAZ-87`hn=dQf*WN-L|2#1(BBTKIAc>Il!o@}3|AE(c2p0^$` z1vDa1r&_@!#)9j-6`}E)3^X*NY^#r4(tB=2ERaT=>PJ+J@^%-qbs)}%T6B4(0+f)5 zsAgUPkF^5dsi$A*S2>B;I!=aVqu3UWp=o_*y7F<*^F6r@D7Jw$b8YTDTp z?AJryDYN*8Ny&brRN>Sd-QqorXi?685_a}_Y>7InOe!q8}5Y-?RS`KD*d@} ze=lbEFNSH-r@GW*U(7mkk=3TUYrKO0AJV7Z6bZSBdbb<@b0ik0Kv~xuZ@Nh9_#%Cl zbWo>1cJv~vukgnCo2AdZ!=mtl+u)rpF$%*luIb)k(Y>|;bKG!&`b(C>E}|8aXynXw zqDF~1fS$I1Lpe;eza)1ebdOsCy3kO~C?!d=+c~D0dd@~i>M$?kj?i6WaYWlr^lQs{ z{bp&W^tLnm=ox9VH^F~KI^nfQvoeybiN`JOdBeQZ@Ai)J4vfPt&hbXVw?s-MA$kIo z&IPSG3$d?i!zfr3>|!pSr$#=&Y=0?dihskYFe-_@hFBAWAF)QJ-tfINN*D3=lyaWz z7W`>;P)=d5d=PX4%ceI0UJ(Jl@bUtWWbk&&@SKYq{62pr;u_PXcyBS{i{ikSJ%F(J zspo#PvpYzX1mFyZQw`}7>t*YmUSdx78pQH~c!`r{_&t7F4l)=!q;Z&3=w-aDH!TLzSS*rI_n+?t*g&6(+<=~d|JlQ` z)o(%!6Rc~s)c+nUL*th^uEj4!!rsWg;+IBdzt$MD^K(*yYkMQ-CB|5pf6v+QA31c? zbaqB&|E7^hpMgU#u^0cakd^zy4R$+{pfQ3U>Pvb}B{;y4FUUcU=kqVg#? zDp8iJ*&?%@#!WBJC*v|83Pd6qTh(bz>!`LG|)w!xrTlqQxnv_;52ih#B>m?vrj zR&i>`vIb{|Or$Il?){LCdXQ);qieRYkFj%svl4?+)LU?-kG81m?~CAsgoNEj^Lr^LjUO^!ryVZN{HYbLC+Av2XYs&b>UncC+h1q`QzOJ zqNEu6M#M%Dvr$Yhk89Pd%v7BE^N`$7(2>sMgJ+3&H;LGKg0Q`a=^~Styn6Y%CB(Rirjcg^={k@i!QYw5T(6xe`r(^Vx9BY%{D1|Qfa~$ z@C1+gdb7&x*q%vq*-fDU_@xkUE)d<~UAa@6_lImrcLq|C8k24h>$xdR(w3$qq|ktx<52J$p$!kQhU&?Fg#n0d3lH3O#ASU;M<`ous|(s zjt?2*-JRs#2fNpIr(p#JNRe7$f9RnkL}iDljg%Sd?)14ouO;TnR=2|PZiVNYWjE-v z3IBTjh`jd-SzUj0f9RQ{9JIGQ=_dR?l4J^Ib@~?kuGZaYTyRj{AIeEe3btxyV=mby zOWWBMu+ZDyYNY)gDL&|QD^>h^fVw&91fWQ0b|qR}{yV&RG$}5)Q&ZT8UM?7@ku3i; zawOzycBQ#5QK3UHXPBuae&mJ%rKz^7#HxDdzw874gbxZYFFuf3EmK z{EcU>%2(H8R)ofFBAtUmF|Bbj^q9z4oNnp$iLZRUKeRAub?2(x@gnMTCz;|xy11ll zVOO@IORzR3nGRfH6A%H?^BXnG&M9#$lj97$p>rKei+(W#>ljy}7~@iv#3WaMwv^V$ zTR6)BXW|Ky?yYuC7k6wQ&g2`xmA4k`3o(Kkywgo?qL4h!2NXdfVJ2)XptbW@tH+Ds zt4Mm>li0XX+$#RQU5JZo7qkXod|CbNBFS|qd)M6QJ}$D=htHQNqvJkCyo@cbQBL$5 zCw^XQlV~g7$cJiAsm2}5X0M0Yp6Sd8ri#KJ_`C!+vu&6km@>?sof}9G@kuwgY?_jL zf?^FFJKMrkZ=Yg45szLn)jQh-!2)X?xA~8aIc;srG!`b0_L=~<_aPk`5O8ig)qTLZ zw=t4VZc0<)k}`vnMA(wI6^{6*mU-#Vkn6cnB)v!}CQ&QQ)`H10O*Nag7SPg~?YiKeOj?6x6Rj6EitWre?zbOe zoMVNv@*wCc8eDO>$iYYi_3N$T*z6IFw0;Y|csBn>6VZI{|*2xLBV)n_`np zC(=5}gLF018mE{ZGHorOYs9yViT3cg*4Ffw5Q!gcimkWZv_BM=WH}jo;?e8)kezu$ zX0}t@DxR{waq!!AQ?Z-cjj9?`)YME^yt=j)d@i@b6T?jSOr|Zfz`{ea&2&s=#=aej zkN>>(sQd*eg%JjYjB%i&Nx#4eH?uCO2^h&woiZpWy6es}cm06dQ-0U3(_TILz1%rW zm1$pw0c&Bc9djYT+;tw5yC8}0G?ud9AZ1BU1@~MrE}0*s)CNk6`$9af^7^^3ihvKy zCfV7FK2CeW;Vi<_y!Oe=Nc4CZ=vNz{bH)XywJ{t~KJp3g##_wb%XwXV#<^Mw!EC`v z7+w?8y1iH>jzxc(CEL~UG7L35mK z3Valta?dC?enZ^u39oD7LVUt;oZ@7fi0O|Pt4 zDNS^ySUOW|Za{cc$%K-nNYheOMjL|x+Cn?BG_(*(x ziuL5KcAo5*vJYn;v~KqSrh0^X#Wy>|JJA|>P#a>kHYu%fmT5(lroW+Wa_MbcQfnX` zc5ZEmiRRl(MiXj%(9k&A)P|nWb|}BtTJWV@I%4qKR&hpm<>iy$p((JgY%Tc9KyPo~ zTHyS~E+$3K35~v}x>7sI)0raG8#5a%*n=qT4#5f6b1UqKjW>%fXycq3m$O%#6oraA zX&?8yDH=$?%i0C*67)n^Rw^kkV*ARDIrnaw_YV39s-K%@T_eaR61H*_J+T-K5KYoWd7W=>V8Z`S)x{rS= z*L-*I+1I{xE!z8?_$;l3JwQ8n(VBnONuwC!Yv10!=%sJ<&lhbwSr$8aBZc0+xO}3R{eq__@<8d z3spy`%seQhBaot@j}a?>5;6qNDN-v;d~SD;YDIH(SEJe&JjJleC?^mv0KF7vg53JL z_0Ckp6lAVo#*th#Xh^50;#HRqICO*P#0k<-Dy=ULx+6VTq*m5OH8d^!9dY5rWmymUJ>EsnkKKcQ4LU&~sqNsqE|S}P;+1RK+Ve<*@;@$W zr;ScGj%I=*$7D7)II*iW-XZ3QZ?$XUdcq_7I?8Ixgmw*Yb8mKb%;S&Lhejr)9WN1e zt;9s@JcSlIPkafQzYRJe?Zp&G+@G}Y?%!cgI3!b??h2U1Vo^aoI^gJ)-i|VlyJOyW zQ7y?{-yg1tTpN#F-{30ifW_#UF5@Hf%QiX@e_ggkEzoB``#gM6XC~&^>1)*jBdlSF ztEbu%wfnE>YK2t`F|l35cuF>iEwFcyeN>wogt?4_zlabkOJ~7Ozh{7GYLpDO5X(3* zTl7k(59h+Z=w=XE8nM&URPC~}Y@9!)5wlpoNcfR`(RIsaVEdSNfQhCb9iZRWq2Df{ z+9y#WIQyJmmxTBT+lo}B57O$#(7g%H#i5@q@gCNkUe34LR^TLB^b1G%4Lfz+$p0Ss zS6g7kG=C?54qYRlCt3PBVX7Be+b`grZ9?z)7Q}@?CrkC}8%iM`g@WDkF~I#5@B(ZV za%4xy$jx%jnk+Od!?>CE$*2X!NVo-MbuG*-T9rxQM_&mt)x>D=!rmH<*^9e}&QRV8 z)<(xQy(bTS(*$X37`25FW#0knGoXFa*Ciu@mdP6)m@g%HwmXL%Px4eFYL=AZ+(O=V zXYvtF`E`U-O3~jZkUoZMEG$)=@_YPKt&>+C-iH$!gcTwYM#x9ZwI1IvN|<^t&Ni6+ z^q;xSP5<+FoJ!JqGFIf(@02X{tdUo8)p3@c7&&|{81rZ759?|6p1_HXUg(tc9o46UN zk8e1@heec!*AUFvJ>PX75yH4e{RFWcxMW-};QAA;=|9CcQGQhJ-|P7Qy5~@qMISX-SA0Wf4OdP5 z7~JN0ttFk$lt;p6`!ypDUREn8Ob0Z6qFk;5EK_u&ez znts`UgKqU<1!I9spTHV1v(Sph0Ry(tZ%-(1JCPc^`nv#b9mnc(ciEYNI1h`}DQw*T*- zdQN$zpRqfX=@tC=pgazJn-`sfCo6{Fiy01OX@zYVTGVfFlFN@)z$&|%T$U>Et*DyW z;@i%&;AbfDKy)-etH`Q1MI)(3Na@~Dh|L@2e%Co9NM}jlrpk1Nah@zC61MjPL$(s@ z!ON}+q}!P74Csp)_Yb*6C3@N?5q4KjDe8v=Xxr#?C@gx{EYq2@M%%inf{Yp?I$9}h zIevp!anQrra;{3mt1$WB2bpnGA)h1CVYM8@ESjk;g&Fs(gU@NHosRP*m2E?B>J0L? z(A9Xy`PXKw^DgbLBjL_II$k|@?7S5txX`EFcnJ1c%`VO6NcafO2s)I{eRLd$aZi*( zKFwB6Io&saB~5*qKR_RdLf1y2--|-O3+OdEhqB8j03+Y@amvsi@M~YRT?e=IJgxoZ zDEt;c?ERtcx1ta}?u97C+9*V&Py2^7%*9(cdB~eI8#Tbx&3)M-#n@j_czBnWMByI= z{Gx!-d`HpHQQBSo;jhp#M)fj$*w^5nio%m+KRr)5=beC`+44#4h|$xUX^*Dj*%K(~ z43tCq=&OW3=Lqg*_2qb~r`#3H_H1?D9z3o7u7*NPX-i1JS6dWUUkrXq->fNjb#8ng zIGsvyI)>4A^?mqFjA}>pDgI@dgMt+2wYykTEPqVj0%KIdEQy3)XrPpq!DZOuf@5(G zh*O62(SJkV^Ukw@Bam-X^8QtGN*^rFn}799Og;?&$E?7yfp4P{$d%ZqJV{fDRlunt zoM-A9RAls`wk~{s!*8IH#khpKT_%H+<7L1hVL5EEdW{mblJ!Gra0a8ZFKKg!yr@SsUimDn;*`;O_X)&I? zD$Z>0F%;1mdSA8gVU=0%iMXhq0m+gZk=l}ScbRCzh_9$@H7wbprE?$r;C7CM4gL%D z5!jEdux_`*iY`FLFUP3=T3^!n^?1$Quv{Q*hMkkn0UbY&euzj1#&7?(@zcCGkFE~i zaHH?mrjxJ_7q;f}>Okq{*-J$_l@kCt7Uie^OsWqF#e9XvpS|-5ULFg_% zUZLFRiSB3__~5VdO9gSWQ(u=Fz=_1An_)XHxym5DG1wD+6_O_}j>Jjq{%}us%#&eg z<&<@Om*s@$jz4t;ldB1^xk6xpAASk`qFf~TRuJXIzOQ8uPUX`t(GYMn`n4GYe?q2G z&&_H~>cKidqSeE@A=DN7J<@v2n+9Je+Tcy~3uUbGOPrOb-ybOHY+1?{v4yO141U`C zF<;Yh33WU@x8~<0NE0-U3$Tfp2U;hr#fvtph1i)B8XwQ?&0;jPBgoAvEJPuexbW?&la`F{<@jHiJ7z(cax7Kb3cQmS9#hfOP%d&lM zr8KL|ah0FB%{l0#|H`x_^xwI&3X*jM{BZ;iT)uiWf6#<7(%o$4;kwC0D#S1-Ug{H`+(n7G+$PuU`kV;n4b6 z9o)%7>zNH1wI^j}!zXxG)0K{rU;mGCAFby$#L8(;a2q~aA8VVL)F^+nUW1%i>7tBI z_>6{-=j8IJH-DCYx?eyXPG4A!(0CprR-4kTp@8~D=z8a`H5O?ueC0Uh zh{*U@%hc1bRvH8wZ4u(iBjNp#afno@h?o{<0TJkVyCI?g4^^2+EbzVdSfm`>XW$&e)&gn`h+M+=?k2~uaIm-mCngEx z>*)995b?RYpWJ*E-=UfeUlr+nz6~;n znOhsBhh+6nQT_Rm{ymhcG&M3E8^zuvF?mG*@qo#SH}T%8X7$l&8>{|N^=xqF3hg9~ zja>e#?=SCrboV$eRzJ}2m85NXiP6>jDMGz?4JkmWM^zo2bG zr9qNg9;D?u`jD@ucXoWA;E!@e_JU{$V)On-iJzdvy}*Uc@+0yG@WxFK&RAi*jmxqrJ}e%x3#HVw9=yqx+CX!b>9q-^jqTUZr0lTSRy4 zE$TgbPGL1`)oI3%{~7-jzXf`;QKY&z-Nz&0uX`BFTFew?i{v-p&Ui~bjRK?;M)QNw zQw>gFDj9t#`0qJ~djLJ{49*ngHPWx|31#T(bz~5KSG+wnv^Xg-u%Vu-z-lmk;SrF@ zBH^KtfiG)N3a6aA*p6?EV-KV{z5*Ujzh#M9=@(bPgNN}9A# zdZC3DsUn&t?X*yQL2$K-t|_HDrCh>AEvx&{+WJ~9s|c>k#S4hKDDEx+x(^Yt2;zEq z-AzEg1xk0jbTvYeO}Wh^X`Ao&pA__cm-ox_OwL@+%sF$;nREWv-#>jnJX~JfYgsoW zw7xHK?<-{*FWa`yo^t9RYb{uz6ZgK18SdOdhWTaV!VTroK2GQ-y$B&;edc*x5ejIQ zjY_A-t~*zE``(R@+V8il+aClHA<%qYwOg7skf$=<+RRP-%#XR6^~;~ZPiH#tFl{1t zC(YEHWw)Ypex;aP>lA@7IL(Q58!&^s?)}#+7+L8TOMg+$@ey55GCx5BFC5LWewT-ELZG6>0=UfPpkA!)647fTNT1&xra z1js=6ILvIZj>|L6Un`~!x=ml7H+=Z@`Pgm!^4_o@7JIOQX!Y*9ux>{AGvW8Mu1=o= zMEc$h+K~JV#zSS}kUtMOM%%03^X!Nv42CFGu!kDTmn058G6&PE4x?8YD zV(;vT`904|aWhQmzg8+iPf5T) zTB1n!(&8|>`{nYWw%5hN@_FD*!e%;5=!bM4QBy)z4rWUhNX_Ci#WQ%F0pu?kmt04bMcYD@HLvc`C&gLl8VApntVDY{M7!d{ozQx{1qm@h7SY`!c61Ka#m$Af<_1$G%u2}(- z@!jQGbBn^d=DRG*s+U=pweJZx3B!}$rdFA$9iMeQ!Pqbqjg2~ zinmsrTamu9W~CpVggc%b_tgBS#ywsA^iteuK0KtfMM-D=rgqGUOj;I8a~1l*N_y5u6qcxQ`}hujmeC z5cB`b9Sb*?!_qBF_R{gZg+vdTK(W(&b!@F55~bfN=IzC-6^DoklXu%swX;ksIEmf% zSa0{*yuIh@$Z8KB*Nxvk7oAHW-_9vO%$K2SqqH8ON)fFWy(`Uku0a!s#GLbR>E}>p zwTtE_p*Mj6qbPK4p$^!!8*zR^IoZe1{Mg-4<6#p%1xg{$zV@@Rgjcj$_b>d%vSYN* zj;Ql%v(%`f1wT?JKr>FO&wqu8DkEP{NCvmPZWoSsH*~n;@%69Pb}uB_Ya6JY`RjLL zU8EUG=j&cLYT+n1!`e6$bR#_@5P}R&)iLf|KY#s5%&cqe@!q!yurT5&3IkS5G zTj1$v=FY^-O||>)XEk1GjjjH34I5z%XF}g9kx|Gw0-HeiEbCWPYrCEV z#*LsosZt|U$AiIQw3pJn0v;0Ay`!B^R$oE?D6?o>lRom%y1QX5ZguxG?1qGBwUF7x z1;#Mo?!>Wgsgr`h5h<8z>>YJ38 za#oE{xOIi@1HG}Z=7Sjmczv1D(0A zNKEKb??3pJ$1Xmk-qX=9q>Vn~F5`~B+Y=*PSer9Q3kcpGjL0l;8|ELX=d|F*{(~s< zoX;*sOZ^ykcAWW#pKJmCtlG*G&CGg}41@_z?bQjK^wAv{moNM~mPa3&qIDd^mBA3Xn`Fd)rR_YkJ7ymHiYThFb{zn%KLlAxwY28 zn)`jHU{A!wV#bQOqUs~K!0g~uX=hIizYkbvG>?v|Cmt%`{R-oGh4w3~ivh?@iI*d( zEMYNmmUT{yIz|*ng1%o~5G3CMj4e=DKOfvTV!tZL;KhiqT{je~^?f)hz|7Py&m7E? zh&*DDr5B^tbNfge3~Z1-E80FP>%;q%ut4X>!W%?`LnjG6>g<7?4O87@n`&Y^T{Pcw zfnP!|NY@2iw+++`UQb{(gVz`1ImJ|{&kD{e(Y`C8SA=pkbhD6+|)zdVPipK1rc`IX(VXX z+0_W!Xcnl5SRupK0ju2VqT>g^%exM-bov(3U9`sLNb`Vm40(AqaYQKtc!yi?SCpS5 z#MV`#JSshc{U~2WcfF}{TJJ=@hRs3}WId43Ac6-;#0}V6;9&u~M`>#Y4mHVltjE7% zksQmZHOvOd@-KsWQF6c2&XVy*GEP2OA$jVdKQPzW z8tK$S1*N9DSs*QRTdxV0k#wd{Ufln!I-gUVg;sHdI2u++EO5NP3ID$x5Yq1MAZx<= z#4YgsJkB-3&EeMK<;-3vbxT|zA_fLV6e|S46J^>s{IlB zBcK{*U04T<7a?(zWadtI;C<96^n69R%yX;w(#M?GE0~A9H*W4#h@DOrcowaTw|MCU zEH}6!(6rGTCD2~9 z1lsF#?u4HMG?-Y&;!svqzfKIeS>BkA=7zSOqeDiWVS%w|fgv3$qzfi3@Y&`n7RGwC z!>2iSONH(nXbz_0zHHQy`obVw#}^SRP&^ESaMd3GS45b>xzIquuLIiMqz;xF-?6)4 zKb{_Q=A5Zs63|xBrwU0sr9uzc*=q)HKhuI{u!>7)menUqhC+CPq)rkK+W8~5iPwE5 z^to9K%FDn}vB3F$;@2hx|A{dek&g~~r}W7~2Y&QUflnKJ7@*k;dE!vPH* z+QcTB4IF5Pf8u`fBQU@Z@EiCM@J-~4NB01K6r4}82y5b;Y!4fiTF@t#0I}V4C_noO zZ1`DkGSA%wuaEph5B!B(m;L$KAunwHbFM<8#8*V*zeR5N_K|MwBGxTtrIqV8ahOxn z(7K0ZmwA7sq!s`Jn&)^#rkUyL@oUEv!V#bWUUEQ$6< zDnN6`3A)V&cb|M7oGNMb0!`E0^%8uF9Fnt~__fS){+;Uab|>)AND`mb?VWrx4$2dw#`{W{_Qbi< zEQ6kD5l{GQq;X=Z2;>X#Yi!K=CEg&8|1WwE{tG{~c`?>%YInqqLB0Qvy9n~{1(MOd z9TG#DUCYDFinvD?(Hp$}5O*pn30h-(EKXTbg?hXps0b@LJ4+UNJA$n@M^_ zAkEE}hLy4$rK85_l!%LZkX=MX8KcO*$8C(rIrw^n4sL6@$Zsb3H^r5qv3}|1Sl`z7 z<5)ksW*FXjh?lQ>#{DHcc(+Q+-9rN!7VquA8kPjz;L?DRxyq>@mIk!giyjj#rxjcG zY=kvE8$ZvR7|;!Yq)Er^;$BW_H*Ev;vP$=Aayxw9H(<0mzdo;d9MN+gXMr|wC?h*G zZ{CNoMRIo`ExrTxrc2Qx?^17>yxJ}FrGBVtT!%uAT`ca#H}gSAw^_pIdp{K06&~y> zlW%HWs#N6BZQkx7-GVwQUl@PEz|RrsDcj4TFN3y!YTYQjO^=ss&QJLJut%fWU}vx~hNk=LPqMp(JQLS>V7TjzNVELZwrA*eZ{fptUz z?6N4nPs08YZQA$2lZ>JsICZn7zYE`JY2rXlHXeRxrv1FsB6Yy3?Gd-NuF}0tn(Bs6 zO=Ys$vb0BSY+%8k^l1s^iy!;+Z@1`E_sx>f+xrFSZN1@Svoy~=3MF*>e@oytKIG=# zgV*$bE2C2_gT`A(ohdKee5YrBQj+^x$!bH}QAz82NHSp+ejoM}2F<YBZH&&?g&3 zXdlKu;7!lI|MbzpUW@bbb+NEOnx|6PrC2j8m|Isk?OpF7@7>;XOY%f#YM;Cg78q97 zZYc$JgdOU=gn*+{&ux`rJ)`R2d5a_11NDC()kwRcE#JC^o3s`Bpc1U!T8I~~+H>Bwo6R>MNHPj-TeaUI$Y-6_^a?6ZtM`GMdi_>-#AEQd~9w`UC~ z29{mn^FpIkN-=|G-*~Rsw*y`+Id$9Wb1=(3FPOzRnq8ak5{YlyTs}_plnH0aOQpAC zrSo6@oI37(x>sxOPD&CXx0oG~xA(=nca#kwDTeEFoEh%ky@o5? zjdp44WBF&iG`|Z$%(_L3fg;Ui8{11I`Vu|?=l(o;ZHRcIZX@x|)_rFeCheP7&+p@4 z&5cC)B!S9P=aXb09d#H2zriV4Y`+ZDUWmZI5D!8L-I&y67H(`D>Y7wzz!f&P9J7=N}Zv&_O^L_f>TyWPw z)eUMvf0@x=t;*m0e}!ivzc1A}8@OS~;IYo4-}>aggb|sCr>IbmJ8P<~^WRoVH+*_t zXEj1IAr?@nNnVzTQf-5}#~1#jB$b@?&&&|Qx|Ib*f5*ESw11#C)PCSE0~#CAHe`7| z8gZ~NABTms#18&_ZVSzRlQ5ISbdU|-nKjXP!kp&ld7<_Uda4VnEKxQTI|2TXxKFD_ z*{a7oMRg(3m@u=kKJQXnXD9l2C+<8NCQJ`4R+Z?zTX1hI?nP`1l((aOp|lA(HzDWm zQ3l1dK`Y@Y&qGHT?${qRQoN-#9lE%a5&3oGpqUGPqX)RDqu{r+vnkL?XJ8w4Fv@eb z?(w==24_W#hF!W>qO^sk6tg{$sM7nk+w~ooH|;g>X`Tx&$4{~H5giehk74#SV099< zZgO5$XPHwG$-O6Nv=zCJtg#17nj=kw4`)KO8ZAav2(8L7894=vEE~p6D6$>@@}PAr ztaREbZy9WeHG`JEuJS1FPJa5ECFag3aFr9b@(>k2UJ&;M&1RMz+nMq#|Lj(9|FP3U za#N7A!ov4y(;*$Aw1nhUL53ulTJ`N8`g0K65d=e+6-#hnIK@mznak zSrn%C$)!QUqO}5Ton>BA@oWQa!|r9~VKX&jvn76q2aYn(^xnR%zP7&AMEnVp_j+;$sqd2h`Ho}y?L;2X7_ z%xqq8L&L_b<^@{NT!zG(SN18Z6FA-5(T?7iU6ZM+0u zeaUT@!P57HFJIAwhcUJZy!eVL2e*OvnM;G-v#i}_9|HXCA;90J`}e5W<8k=5+Xpgm zMo70pw`^?z!ViKGB9=<}_pl8Zsqi?)m8sSi!W5+brLm>Om_cNc)wFUR#^_lJy70yr zazVm->lP2n_w)Gy_NIYz z49nI?ZdZX=h)8i;q&dml$&u1T&s+ASvm>SPp0`tmO}_{ah&VCeZP zWa^^+Pwd(vyqY-xW2;3Iu4?gX5q6rE@A2_4(N)^ez>2qMZ0LL2kn-0Wu zV42*VTb)*E7$`s3%Xbn-8J5EXm=kcdNsaj6kjk8gAv@{u)4kB;IG`cL`%d-Rr7`dv zm~skje+wDX-<1Uz57+m?m#r}@KOP}$bQ&MUim5klh#=~Gq>Cj=S=ER%zW_Nr)i@Ny z9l#2^Lxgv#W`lig`{5L3ww1EL--C1qN%x0Cy3g7pUu>O9vQW)xU3RR`b~$3%t~_F1 zX=zk`Ze|wE;~{yrhcL_UKup6c<$6fFHj3&zaSPpp4z@i(`C@;8jdT#)hV5={S5SU7 zNLu%xJT^Gm?Lf4YW<*QTtqRKaAZZ#9t%zu&7a*@)K+={%?-|G~@WsZY{m1DM@Ig5I z#>mu)(KATvUDC_Ai(v-qK^E{srV5+a86^McgcL#tZSy##0_79|Yw{5jvyK_RbHUJ4 z#psJa4>Y=Q&dKtQdAk?qIITa9b})@oWs75SqNBXjf&IQME? zzp`X=gTeiQo%s-{qX-^Ik?Z~&_PUUF93X5S(kV28Qc4ihJwr+6Gb=2YA4>FuRFuJmaS)CG@4M?er>QLb9xTu1bHHDAIEkxiB;l zR~*3Jc+?-*Z-=$=hzCL>f za9m2IZB+u^Kh;s{ED!@9h2?Vx2{U=UJ?6xgroSMoi2gPi0l}FbJ z2at-il3~W_5#NS26O$1&22mc8Z+tr}&=)czw~8~1@lE5L?lXuJ-P|3T@kOvGexA{6 z=qgXx&$sb|95CUjXjI%4;&+YvV-b5{&7Ng$j(F;TB^dX9>=q5MNy75LK#ZD?u&d}= zZZH5|{KY*Y|b$PP?_bOfBp#tr*8$r7vLtY-|&B;rIS1q?GUF0^i zK&FzHH^jH6m(7Yf4g0M=izZ-JdnIF1;AT9v;P!rCGZKFi#uPQL(Y78@V- z8O4902jWGew83L-D9B0o)igYw3hxxYDrdA$Bbw5;qnriG0k@{eWX^TE4wA=aTB9chMhfKJPDrzs+|lM{-!IuN#%J32`un0W~L8jP1;+vxv#1 zio90ok+SPpy0x^&>4OCgqNo9h27aO@@@W816uA-OO;^d?$vbtG_G*VyTiHB_o)YIG z`Xp}+GxWDcu~Ux1-|i@VCBR+b)qHfs+7}}aVXMTBk3E~8mDZU*vB^HFV>_@xIJ3q* z40$rf4?9c8F*#RGJF~Q%41 z9$8t6Z!B5}h*BHEvJIFpVR{iIlII5Eq0fL%8SMG5VqGQrrWN!Ja(TXV zCrKZ93KDgxoOrOj;CHn?9F_Xa))}xNN2pvI@Ogg>fBRQKi5E$5!@2+UK)~t z__7vOn=D)Lk$*t~knIZEPMl}=W2W&Pt8NBjWaC^ySR3hR!na;<=sml}_epiS*z4ye z84AZ_e~+VCR~zp;?{`A387op;Ug)G$&(PcOo!$YNhegrk0fh!DBnymCCSk^%b+t*= zh#{ii0Yh7u5LqR|A#;}28&fP~t%qEZI1}1pk$3Gf7I^#sv)C>V$Fr*s1lnFeOjy

      Zh>akspFMJ(V{cVsrC3L)Vt>np=yjbWfwSnvy^>>?PtnKoUxv$%ERV}5y zYaS%T-QG!%phUHms-8f)-8~5rX&gW_1dr#u>bGJq=m%|fwXxI2m}kH_-{crh-i+!;6q!qv5W->-?fQk=stwL%VsBh36?VoSLXlZO7#33drgmn zca=v|_|5)Xjvuc%esb-`eRDlCP`_xcP@{>_TD|&XtpZs;xrt++0X=9@$OZ(2~QDYjkE+5S0-jUDa&#-{2N91}sy1zuQZk2%fq;1%7- z#zL+R3;pQ%eWB*-Y{CrRI=kk?bMWO1HnyZxqaK|34Uy$_d6D-&I{g|?lbT|x8kW^H9Eu?ya#dy z^kLJ`(hFQ^LYNJ_TSht6_n4?T{x0a#gN+99?Vbd|c7eCO=KrkMtlwv|g!Fwg5lze- z(qH95x+|%UAhqOlhJAN92&7J`NlZ9dt$`t&fEs8*y328DEeySpI~xP7jjd>-=NotR zY7Et-(Ygc!G10n|uyDe_i)vjs4sBYr==h6e3r}l`t4nPc47TlI%_}>461W}q&&7Ae z2TsiOKI+~FuBaO4xR749pdP)pF%GoVGB!5auIPLIl#O~m9Wm5iwsDRdEw(S(2Dir< z9T#*ClzjaSyAaY`rIz4%lwO>F{0(~^O0Oy1Hfjy}UcRmm-&Tl`QlbkdTv<2Rx)>?N zw;f++Pdcr+ySns?6!8KRi~SQI1=a$EuKPRaxW20_d+)dh9xDraj0s%vPQM6@O0)P1 zs92xhD?a1bOsy`Rouij;JOtB<);+U9F$i; z3PQ)9DyNDdZD}XWQuv#hDT=TTNVdOlbx2hXL`n~`zzIauB_DndFhYwV+a-F{hw~mF z3Lq{u{-f7_1^mq+Kr?3(Kf4}pjGA^0&XaDwBp8p8W+ z)>ZheqZJ%!@i`=QiaC`IdwSx{Siph&xrhl3E%G7Oi>F;f-oQHtoAp}XkH?*e1Bx19 z!&*KlXJaPzh_y1%mICRZrSiy?I9;M~Oly_&v3>L}a=dS@`55vj&TP!ohFM{iH2N1M zmwA4x-R!kr=8&c#rQ=j@iF#~ke>ih~TAWy#77GN45yzqbU0Rj;e>}Mv&)HL5-097! zkGgCr0Z7A6`X9`R!m< zmS4x&+*(=Q63nPzf!MHCv?A4oE$}l=@MQ)fnsmrgVjvex%hR2rvCPJnIX{!)94e2E{%dc6o6$#1J1G(ydR)wZf? z`bM3&SCgi#)K(bV4e79c4hWi&P9a^EXL#tEsf%@yWeZm!%O&{s=$Ki!bOBhuvRoXb zr!mXcYSqR7*EEB9b8hB^cNFfm4jv0xQR-mWDQepf6+SNpG7QFy?HRC3Wa)EZ{XEj4 ztsIF~*bRHaVwKwp`(Hu*>0RMtD`G@|9whmN89fmSv%r}kIBRgYkO1iWzBz+`?MZ&d z!%j_a>m&!FzPrk;+!JL6#GKgzl-!t8+%+~7Xt}4g6;0C1_Ez{@8NEgOm02(8XV$}OXBcd3^j>VD z(5*-R3nc+wb9l2Niun`I$ZkP^-2%z7NZ&XdPvKApviU#K*evY>9r1DF`y=^ljl;HL z|3KpaXjPU~+d*1^#7HA@+5+!4nnm*z_>c}1STh4-;*9Ajq6gP659}+oi+ev6nuOGVG#ROYG_~Ny zbLh!m4;T*CNHMS}rV(~{=?HLQ8nhu@`@;aJ(n4lQQjd0Feo*}s^Gd*h56EwaRlKT~ z483Lp=?ewzCF1RG=HD<#x_#-4yZ6Rg*H-!zW1i+}*Zg6KNNAi!?>~TfO<*BymL-CD=qRGvX=l>=$*?rcVubsvsjP9D z4k_Si8SrWt(5TH8LmO%BruCVDnLyIf$i>k!%!q7bYP(;04PM#bEZm9r;jCHErowOK z%5%an&s_(HS9<4f2QIrqF`LHtu6ls4mOaY1bs=OyUcNUA`tpeUm&k0a+ISzxOxrN$ zV7;~i!3cVOZ3VQ)7+GW+wJXx=Pj#}4OMa@Cc__6+-eGiMkalYpKR& zN2w#f#Br|~*XpVlnHMatd#ZN%k68yFCRW!is$F1Sxzt>Pr>?9uuas*4?bh0->S}85 zG-odO@%Fh-*3{IlSn>Fiix#aiFCQ$H9(0S_2TR7dtzrT;12!Wz6Sf<_R83Vdiy7+1 zGs6ySBeR*ojr0&U%JLqr_2&RD1jj*a?@eHa6F6=vV1}P9u3gOPmORduR4-v!OHiZn z7zsx~X7BOW?kfE4u9Md5)9;w}+pDGhL*AM6`ft|%#qi<0 zOvlm>7G&u@r(uF0!SK-UA)A`C9#zwpzy78q`kp0@5lggfZ3i}q*Mj$)=Vuk)J85)5 zu;S_G9=@x6#p=#k!=Id8Rb-#})WiuBCr>DNqNaM{#7U3WRu@+@`aW`5{({=4@>i~0 zHMbzTOYO)aYFYRj4&U;T*lrw;9^Aii7Y1790h=0%^?Hb0vFYcSmn-*qbE1?00oxu~AqTUWERq;C0*bV^YnOXQeFgHD`3 zv62BVUxS#z7w=t&XSg-}rxG6R^FCjoR{aY&vYY$V}gS6*5!7dypvx zDNO{_sZJcwH-9)0v>?*POvdP&rvefv#RH)UW9%O&7sjmY2wt4h7M}5x;z0sZ^A0`J z((#uDrlZu9!1PE}-2xrIGL*$2b#}v|8!5&xi$l6Sb1X9=J^Wc7i$~h^#AKF$l*LSA zLy+eGWK85voH%(>!QjxqC_#T0u(|i&TR7>S=r4LuF=bxSvy&eMHHjb5qI<^P z8MDW9DYBZ{FN$jziDW?jiFQ%vVLGSY^piizYeSwJr(UE+9{hFDMf_HQM!pB>Y+U=# b!F{@ + * + * 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 NuttX 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 __NUTTX_CONFIG_MICOAIR743_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MICOAIR743_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The MicoAir743 board provides the following clock sources: + * + * X1: 8 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 64 MHz RC factory-trimmed + * HSE: 8 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 8000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 8,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (8,000,000 / 1) * 120 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 480kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 20 MHz Max for now - more reliable on some boards than 25 MHz + * 20 MHz = PLL1Q/(2*div), div = PLL1Q/(2*freq), div = 6 = 240 / 40 + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED, + * that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */ +#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ + + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_2 /* PB8 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_2 /* PB9 */ + +/* SPI + * + + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */ + + + +/* I2C + * + + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) + +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) + +#endif /*__NUTTX_CONFIG_MICOAIR743_INCLUDE_BOARD_H */ diff --git a/boards/micoair/h743/nuttx-config/include/board_dma_map.h b/boards/micoair/h743/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..ba3f15eb9701 --- /dev/null +++ b/boards/micoair/h743/nuttx-config/include/board_dma_map.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2021 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 +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */ diff --git a/boards/micoair/h743/nuttx-config/nsh/defconfig b/boards/micoair/h743/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..9e4db72b9044 --- /dev/null +++ b/boards/micoair/h743/nuttx-config/nsh/defconfig @@ -0,0 +1,245 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PRINTF is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/micoair/h743/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="MicoAir743" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="MicoAir" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_IOB=y +CONFIG_MM_REGIONS=4 +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld b/boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..511ef2624248 --- /dev/null +++ b/boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/micoair/h743/nuttx-config/scripts/script.ld b/boards/micoair/h743/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..1dc1a0ef97eb --- /dev/null +++ b/boards/micoair/h743/nuttx-config/scripts/script.ld @@ -0,0 +1,228 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The board uses an STM32H743II and has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/micoair/h743/src/CMakeLists.txt b/boards/micoair/h743/src/CMakeLists.txt new file mode 100644 index 000000000000..c47215375d08 --- /dev/null +++ b/boards/micoair/h743/src/CMakeLists.txt @@ -0,0 +1,68 @@ +############################################################################ +# +# Copyright (c) 2021 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/micoair/h743/src/board_config.h b/boards/micoair/h743/src/board_config.h new file mode 100644 index 000000000000..48ff3ff203ee --- /dev/null +++ b/boards/micoair/h743/src/board_config.h @@ -0,0 +1,197 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +// #define FLASH_BASED_PARAMS + + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +# define GPIO_nLED_RED /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) +# define GPIO_nLED_GREEN /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN6) +# define GPIO_nLED_BLUE /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ +#define SYSTEM_ADC_BASE STM32_ADC1_BASE +#define ADC1_CH(n) (n) + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +#define PX4_ADC_GPIO \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* PC1 */ GPIO_ADC123_INP11 + + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11) + + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL)) + + +/* Define Battery 1 Voltage Divider and A per V + */ + +// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +// #define BOARD_BATTERY1_A_PER_V (40.0f) +// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 10 +#define DIRECT_INPUT_TIMER_CHANNELS 10 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + + +/* USB OTG FS + * + * PA8 OTG_FS_VBUS VBUS sensing + */ + +#define GPIO_OTGFS_VBUS /* PA8 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN8) + + +/* High-resolution timer */ +#define HRT_TIMER 2 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */ + + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS4" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +/* SD Card */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define FLASH_BASED_PARAMS + +#define BOARD_NUM_IO_TIMERS 4 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/micoair/h743/src/bootloader_main.c b/boards/micoair/h743/src/bootloader_main.c new file mode 100644 index 000000000000..5670308a29d8 --- /dev/null +++ b/boards/micoair/h743/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/micoair/h743/src/hw_config.h b/boards/micoair/h743/src/hw_config.h new file mode 100644 index 000000000000..a428dd53592d --- /dev/null +++ b/boards/micoair/h743/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1166 +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (16 * 128 * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) + +#define OSC_FREQ 8 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/micoair/h743/src/i2c.cpp b/boards/micoair/h743/src/i2c.cpp new file mode 100644 index 000000000000..1444ea117204 --- /dev/null +++ b/boards/micoair/h743/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusInternal(2), +}; diff --git a/boards/micoair/h743/src/init.c b/boards/micoair/h743/src/init.c new file mode 100644 index 000000000000..43f86f902d24 --- /dev/null +++ b/boards/micoair/h743/src/init.c @@ -0,0 +1,203 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + UNUSED(ms); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* configure USB interfaces */ + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + return ret; + } + +#endif + +// TODO:internal flash store parameters +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {15, 128 * 1024, 0x081E0000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + led_on(LED_RED); + } + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/micoair/h743/src/led.c b/boards/micoair/h743/src/led.c new file mode 100644 index 000000000000..d7794392dbb3 --- /dev/null +++ b/boards/micoair/h743/src/led.c @@ -0,0 +1,114 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/micoair/h743/src/sdio.c b/boards/micoair/h743/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/micoair/h743/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/micoair/h743/src/spi.cpp b/boards/micoair/h743/src/spi.cpp new file mode 100644 index 000000000000..81fdd03f282d --- /dev/null +++ b/boards/micoair/h743/src/spi.cpp @@ -0,0 +1,50 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortD, GPIO::Pin5}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortD, GPIO::Pin4}), + initSPIDevice(DRV_IMU_DEVTYPE_BMI270, SPI::CS{GPIO::PortA, GPIO::Pin15}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/micoair/h743/src/timer_config.cpp b/boards/micoair/h743/src/timer_config.cpp new file mode 100644 index 000000000000..515a56928cad --- /dev/null +++ b/boards/micoair/h743/src/timer_config.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer3, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/micoair/h743/src/usb.c b/boards/micoair/h743/src/usb.c new file mode 100644 index 000000000000..9591784866a6 --- /dev/null +++ b/boards/micoair/h743/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} From f4e76cd3920b0cb1bc85f8ea7cf6fd54d9f4d963 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 14 Jun 2024 14:42:32 +0200 Subject: [PATCH 350/652] remove deprecated BAT_ params (#22872) Signed-off-by: Silvan Fuhrer --- .../airframes/10041_sihsim_airplane | 2 - .../init.d-posix/airframes/10042_sihsim_xvert | 2 - .../init.d/airframes/1101_rc_plane_sih.hil | 2 - .../airframes/1102_tailsitter_duo_sih.hil | 2 - .../smartap-airlink/init/rc.board_defaults | 1 - src/drivers/smart_battery/batmon/batmon.cpp | 2 +- src/lib/battery/battery_params_deprecated.c | 70 ------------------- src/modules/mavlink/mavlink_parameters.cpp | 4 -- 8 files changed, 1 insertion(+), 84 deletions(-) delete mode 100644 src/lib/battery/battery_params_deprecated.c diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10041_sihsim_airplane b/ROMFS/px4fmu_common/init.d-posix/airframes/10041_sihsim_airplane index 8580464c4906..d863ad63587d 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10041_sihsim_airplane +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10041_sihsim_airplane @@ -24,8 +24,6 @@ param set-default CBRK_SUPPLY_CHK 894281 # - without safety switch param set-default CBRK_IO_SAFETY 22027 -param set-default BAT_N_CELLS 3 - param set-default SIH_T_MAX 6 param set-default SIH_MASS 0.3 param set-default SIH_IXX 0.00402 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10042_sihsim_xvert b/ROMFS/px4fmu_common/init.d-posix/airframes/10042_sihsim_xvert index 536fc6076c39..2ab294ac2476 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10042_sihsim_xvert +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10042_sihsim_xvert @@ -33,8 +33,6 @@ param set-default CBRK_SUPPLY_CHK 894281 # - without safety switch param set-default CBRK_IO_SAFETY 22027 -param set-default BAT_N_CELLS 3 - param set-default SIH_T_MAX 2 param set-default SIH_Q_MAX 0.0165 param set-default SIH_MASS 0.2 diff --git a/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil b/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil index 07c7d925c238..dacfa2ec7be0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil @@ -44,8 +44,6 @@ param set-default CBRK_SUPPLY_CHK 894281 # - without safety switch param set-default CBRK_IO_SAFETY 22027 -param set-default BAT_N_CELLS 3 - param set SIH_T_MAX 6 param set SIH_MASS 0.3 param set SIH_IXX 0.00402 diff --git a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil index 6ac7bea691c4..a9b2f7f03b1b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil @@ -62,8 +62,6 @@ param set-default CBRK_SUPPLY_CHK 894281 # - without safety switch param set-default CBRK_IO_SAFETY 22027 -param set-default BAT_N_CELLS 3 - param set SIH_T_MAX 2.0 param set SIH_Q_MAX 0.0165 param set SIH_MASS 0.2 diff --git a/boards/sky-drones/smartap-airlink/init/rc.board_defaults b/boards/sky-drones/smartap-airlink/init/rc.board_defaults index 212c72657f44..4a38b479f3c3 100644 --- a/boards/sky-drones/smartap-airlink/init/rc.board_defaults +++ b/boards/sky-drones/smartap-airlink/init/rc.board_defaults @@ -13,7 +13,6 @@ param set-default SENS_EN_THERMAL 1 # Enable heater param set-default SENS_TEMP_ID 2359314 # Heated IMU ID # Battery scaling -param set-default BAT_N_CELLS 4 param set-default BAT1_N_CELLS 4 param set-default BAT1_V_DIV 15.51 diff --git a/src/drivers/smart_battery/batmon/batmon.cpp b/src/drivers/smart_battery/batmon/batmon.cpp index bb6b61da0b36..8cfe3031ca43 100644 --- a/src/drivers/smart_battery/batmon/batmon.cpp +++ b/src/drivers/smart_battery/batmon/batmon.cpp @@ -240,7 +240,7 @@ int Batmon::get_batmon_startup_info() _cell_count = math::min((uint8_t)num_cells, (uint8_t)MAX_CELL_COUNT); int32_t _num_cells = num_cells; - param_set(param_find("BAT_N_CELLS"), &_num_cells); + param_set(param_find("BAT1_N_CELLS"), &_num_cells); return ret; } diff --git a/src/lib/battery/battery_params_deprecated.c b/src/lib/battery/battery_params_deprecated.c deleted file mode 100644 index 829e636c2c27..000000000000 --- a/src/lib/battery/battery_params_deprecated.c +++ /dev/null @@ -1,70 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file battery_params_deprecated.c - * - * Defines the deprcated single battery configuration which are temporarily kept for backwards compatibility with QGC. - */ - -/** - * This parameter is deprecated. Please use BAT1_V_EMPTY instead. - * - * @group Battery Calibration - * @category system - */ -PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.6f); - -/** - * This parameter is deprecated. Please use BAT1_V_CHARGED instead. - * - * @group Battery Calibration - * @category system - */ -PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.05f); - -/** - * This parameter is deprecated. Please use BAT1_V_LOAD_DROP instead. - * - * @group Battery Calibration - * @category system - */ -PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.3f); - -/** - * This parameter is deprecated. Please use BAT1_N_CELLS instead. - * - * @group Battery Calibration - * @category system - */ -PARAM_DEFINE_INT32(BAT_N_CELLS, 3); diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index cbac547c93b7..d5d774696d68 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -292,10 +292,6 @@ MavlinkParametersManager::send() param_find("BAT_CRIT_THR"); param_find("BAT_EMERGEN_THR"); param_find("BAT_LOW_THR"); - param_find("BAT_N_CELLS"); // deprecated - param_find("BAT_V_CHARGED"); // deprecated - param_find("BAT_V_EMPTY"); // deprecated - param_find("BAT_V_LOAD_DROP"); // deprecated param_find("CAL_ACC0_ID"); param_find("CAL_GYRO0_ID"); param_find("CAL_MAG0_ID"); From 3cbe2ae2b3197e74eb73bd0e5d87bc6dee9d23f6 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 14 Jun 2024 16:20:50 +0200 Subject: [PATCH 351/652] v5_default: remove Local Position Estimator from default build Signed-off-by: Silvan Fuhrer --- boards/px4/fmu-v5/default.px4board | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index beb865832145..321113dd3cef 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -62,7 +62,7 @@ CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y From 783cf9aede3d009f9e91c5de8e3099c4b0408b74 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 14 Jun 2024 10:11:08 -0400 Subject: [PATCH 352/652] vscode: cmake default status bar visibility - this is important for setting the active PX4 configuration --- .vscode/settings.json | 1 + 1 file changed, 1 insertion(+) diff --git a/.vscode/settings.json b/.vscode/settings.json index 67016f098380..0192c81e8602 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -15,6 +15,7 @@ "cmake.buildDirectory": "${workspaceFolder}/build/${variant:CONFIG}", "cmake.configureOnOpen": true, "cmake.ctest.parallelJobs": 1, + "cmake.options.statusBarVisibility": "compact", "cmake.skipConfigureIfCachePresent": true, "cmakeExplorer.buildDir": "${workspaceFolder}/build/px4_sitl_test", "cmakeExplorer.parallelJobs": 1, From c0d6b676334c7f28884b5bccd24cbbd554331a18 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 14 Jun 2024 10:05:32 -0400 Subject: [PATCH 353/652] matrix: Vector2/Vector4 override ops so specific Vector type is returned - mirrored from Vector3 --- src/lib/matrix/matrix/Vector2.hpp | 39 ++++++++++++++++++++++++++++++ src/lib/matrix/matrix/Vector4.hpp | 40 +++++++++++++++++++++++++++++++ 2 files changed, 79 insertions(+) diff --git a/src/lib/matrix/matrix/Vector2.hpp b/src/lib/matrix/matrix/Vector2.hpp index 3b5bbadca8a7..3376445fdaec 100644 --- a/src/lib/matrix/matrix/Vector2.hpp +++ b/src/lib/matrix/matrix/Vector2.hpp @@ -56,6 +56,45 @@ class Vector2 : public Vector return a(0) * b(1, 0) - a(1) * b(0, 0); } + /** + * Override matrix ops so Vector2 type is returned + */ + + Vector2 operator+(Vector2 other) const + { + return Matrix21::operator+(other); + } + + Vector2 operator+(Type scalar) const + { + return Matrix21::operator+(scalar); + } + + Vector2 operator-(Vector2 other) const + { + return Matrix21::operator-(other); + } + + Vector2 operator-(Type scalar) const + { + return Matrix21::operator-(scalar); + } + + Vector2 operator-() const + { + return Matrix21::operator-(); + } + + Vector2 operator*(Type scalar) const + { + return Matrix21::operator*(scalar); + } + + Type operator*(Vector2 b) const + { + return Vector::operator*(b); + } + Type operator%(const Matrix21 &b) const { return (*this).cross(b); diff --git a/src/lib/matrix/matrix/Vector4.hpp b/src/lib/matrix/matrix/Vector4.hpp index 4eba1de6394f..5115d420e35f 100644 --- a/src/lib/matrix/matrix/Vector4.hpp +++ b/src/lib/matrix/matrix/Vector4.hpp @@ -82,6 +82,46 @@ class Vector4 : public Vector Vector4(const Slice &slice_in) : Vector(slice_in) { } + + /** + * Override matrix ops so Vector4 type is returned + */ + + Vector4 operator+(Vector4 other) const + { + return Matrix41::operator+(other); + } + + Vector4 operator+(Type scalar) const + { + return Matrix41::operator+(scalar); + } + + Vector4 operator-(Vector4 other) const + { + return Matrix41::operator-(other); + } + + Vector4 operator-(Type scalar) const + { + return Matrix41::operator-(scalar); + } + + Vector4 operator-() const + { + return Matrix41::operator-(); + } + + Vector4 operator*(Type scalar) const + { + return Matrix41::operator*(scalar); + } + + Type operator*(Vector4 b) const + { + return Vector::operator*(b); + } + }; using Vector4f = Vector4; From f646f1ba984f04e2925650f49b4e854b80ecd337 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 14 Jun 2024 17:10:08 +0200 Subject: [PATCH 354/652] AirspeedSelector: only update with lpos if coming from GNSS (#23268) Compared to GNSS, alternate position observation methods are less accurate and thus generally not good enough to do airspeed validation with. Airspeed validation is thus disabled if no GNSS fusion is happening. Signed-off-by: Silvan Fuhrer --- .../airspeed_selector/AirspeedValidator.cpp | 18 +++++++++--------- .../airspeed_selector/AirspeedValidator.hpp | 8 ++++---- .../airspeed_selector_main.cpp | 18 +++++++++--------- 3 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/modules/airspeed_selector/AirspeedValidator.cpp b/src/modules/airspeed_selector/AirspeedValidator.cpp index 63343b402322..b83d419b5fdd 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.cpp +++ b/src/modules/airspeed_selector/AirspeedValidator.cpp @@ -50,16 +50,16 @@ AirspeedValidator::update_airspeed_validator(const airspeed_validator_update_dat // get indicated airspeed from input data (raw airspeed) _IAS = input_data.airspeed_indicated_raw; - update_CAS_scale_validated(input_data.lpos_valid, input_data.ground_velocity, input_data.airspeed_true_raw); + update_CAS_scale_validated(input_data.gnss_valid, input_data.ground_velocity, input_data.airspeed_true_raw); update_CAS_scale_applied(); update_CAS_TAS(input_data.air_pressure_pa, input_data.air_temperature_celsius); - update_wind_estimator(input_data.timestamp, input_data.airspeed_true_raw, input_data.lpos_valid, + update_wind_estimator(input_data.timestamp, input_data.airspeed_true_raw, input_data.gnss_valid, input_data.ground_velocity, input_data.lpos_evh, input_data.lpos_evv, input_data.q_att); update_in_fixed_wing_flight(input_data.in_fixed_wing_flight); check_airspeed_data_stuck(input_data.timestamp); check_load_factor(input_data.accel_z); check_airspeed_innovation(input_data.timestamp, input_data.vel_test_ratio, input_data.mag_test_ratio, - input_data.ground_velocity, input_data.lpos_valid); + input_data.ground_velocity, input_data.gnss_valid); update_airspeed_valid_status(input_data.timestamp); } @@ -71,12 +71,12 @@ AirspeedValidator::reset_airspeed_to_invalid(const uint64_t timestamp) } void -AirspeedValidator::update_wind_estimator(const uint64_t time_now_usec, float airspeed_true_raw, bool lpos_valid, +AirspeedValidator::update_wind_estimator(const uint64_t time_now_usec, float airspeed_true_raw, bool gnss_valid, const matrix::Vector3f &vI, float lpos_evh, float lpos_evv, const Quatf &q_att) { _wind_estimator.update(time_now_usec); - if (lpos_valid && _in_fixed_wing_flight) { + if (gnss_valid && _in_fixed_wing_flight) { // airspeed fusion (with raw TAS) const float hor_vel_variance = lpos_evh * lpos_evh; @@ -109,9 +109,9 @@ AirspeedValidator::get_wind_estimator_states(uint64_t timestamp) } void -AirspeedValidator::update_CAS_scale_validated(bool lpos_valid, const matrix::Vector3f &vI, float airspeed_true_raw) +AirspeedValidator::update_CAS_scale_validated(bool gnss_valid, const matrix::Vector3f &vI, float airspeed_true_raw) { - if (!_in_fixed_wing_flight || !lpos_valid) { + if (!_in_fixed_wing_flight || !gnss_valid) { return; } @@ -212,7 +212,7 @@ AirspeedValidator::check_airspeed_data_stuck(uint64_t time_now) void AirspeedValidator::check_airspeed_innovation(uint64_t time_now, float estimator_status_vel_test_ratio, - float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool lpos_valid) + float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool gnss_valid) { // Check normalised innovation levels with requirement for continuous data and use of hysteresis // to prevent false triggering. @@ -226,7 +226,7 @@ AirspeedValidator::check_airspeed_innovation(uint64_t time_now, float estimator_ _innovations_check_failed = false; _aspd_innov_integ_state = 0.f; - } else if (!lpos_valid || estimator_status_vel_test_ratio > 1.f || estimator_status_mag_test_ratio > 1.f) { + } else if (!gnss_valid || estimator_status_vel_test_ratio > 1.f || estimator_status_mag_test_ratio > 1.f) { //nav velocity data is likely not good //don't run the test but don't reset the check if it had previously failed when nav velocity data was still likely good _aspd_innov_integ_state = 0.f; diff --git a/src/modules/airspeed_selector/AirspeedValidator.hpp b/src/modules/airspeed_selector/AirspeedValidator.hpp index ed7008a5c621..58f79e0009ce 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.hpp +++ b/src/modules/airspeed_selector/AirspeedValidator.hpp @@ -56,7 +56,7 @@ struct airspeed_validator_update_data { float airspeed_true_raw; uint64_t airspeed_timestamp; matrix::Vector3f ground_velocity; - bool lpos_valid; + bool gnss_valid; float lpos_evh; float lpos_evv; matrix::Quatf q_att; @@ -175,15 +175,15 @@ class AirspeedValidator void update_in_fixed_wing_flight(bool in_fixed_wing_flight) { _in_fixed_wing_flight = in_fixed_wing_flight; } - void update_wind_estimator(const uint64_t timestamp, float airspeed_true_raw, bool lpos_valid, + void update_wind_estimator(const uint64_t timestamp, float airspeed_true_raw, bool gnss_valid, const matrix::Vector3f &vI, float lpos_evh, float lpos_evv, const Quatf &q_att); - void update_CAS_scale_validated(bool lpos_valid, const matrix::Vector3f &vI, float airspeed_true_raw); + void update_CAS_scale_validated(bool gnss_valid, const matrix::Vector3f &vI, float airspeed_true_raw); void update_CAS_scale_applied(); void update_CAS_TAS(float air_pressure_pa, float air_temperature_celsius); void check_airspeed_data_stuck(uint64_t timestamp); void check_airspeed_innovation(uint64_t timestamp, float estimator_status_vel_test_ratio, - float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool lpos_valid); + float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool gnss_valid); void check_load_factor(float accel_z); void update_airspeed_valid_status(const uint64_t timestamp); void reset(); diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index a25e2d4768c7..28fb87c2b6c1 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -146,7 +146,7 @@ class AirspeedModule : public ModuleBase, public ModuleParams, int _valid_airspeed_index{-2}; /**< index of currently chosen (valid) airspeed sensor */ int _prev_airspeed_index{-2}; /**< previously chosen airspeed sensor index */ bool _initialized{false}; /**< module initialized*/ - bool _vehicle_local_position_valid{false}; /**< local position (from GPS) valid */ + bool _gnss_lpos_valid{false}; /**< local position (from GNSS) valid */ bool _in_takeoff_situation{true}; /**< in takeoff situation (defined as not yet stall speed reached) */ float _ground_minus_wind_TAS{NAN}; /**< true airspeed from groundspeed minus windspeed */ float _ground_minus_wind_CAS{NAN}; /**< calibrated airspeed from groundspeed minus windspeed */ @@ -347,7 +347,7 @@ AirspeedModule::Run() struct airspeed_validator_update_data input_data = {}; input_data.timestamp = _time_now_usec; input_data.ground_velocity = vI; - input_data.lpos_valid = _vehicle_local_position_valid; + input_data.gnss_valid = _gnss_lpos_valid; input_data.lpos_evh = _vehicle_local_position.evh; input_data.lpos_evv = _vehicle_local_position.evv; input_data.q_att = _q_att; @@ -515,10 +515,10 @@ void AirspeedModule::poll_topics() } } - _vehicle_local_position_valid = (_time_now_usec - _vehicle_local_position.timestamp < 1_s) - && (_vehicle_local_position.timestamp > 0) - && _vehicle_local_position.v_xy_valid - && !_vehicle_local_position.dead_reckoning; + _gnss_lpos_valid = (_time_now_usec - _vehicle_local_position.timestamp < 1_s) + && (_vehicle_local_position.timestamp > 0) + && _vehicle_local_position.v_xy_valid + && _estimator_status.control_mode_flags & (1 << estimator_status_s::CS_GPS); } void AirspeedModule::update_wind_estimator_sideslip() @@ -526,7 +526,7 @@ void AirspeedModule::update_wind_estimator_sideslip() // update wind and airspeed estimator _wind_estimator_sideslip.update(_time_now_usec); - if (_vehicle_local_position_valid + if (_gnss_lpos_valid && _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && !_vehicle_land_detected.landed) { Vector3f vI(_vehicle_local_position.vx, _vehicle_local_position.vy, _vehicle_local_position.vz); @@ -603,8 +603,8 @@ void AirspeedModule::select_airspeed_and_publish() if (_valid_airspeed_index < airspeed_index::FIRST_SENSOR_INDEX || _param_airspeed_primary_index.get() == airspeed_index::GROUND_MINUS_WIND_INDEX) { - // _vehicle_local_position_valid determines if ground-wind estimate is valid - if (_vehicle_local_position_valid && + // _gnss_lpos_valid determines if ground-wind estimate is valid + if (_gnss_lpos_valid && (_param_airspeed_fallback_gw.get() || _param_airspeed_primary_index.get() == airspeed_index::GROUND_MINUS_WIND_INDEX)) { _valid_airspeed_index = airspeed_index::GROUND_MINUS_WIND_INDEX; From 8258cd63ba7e5fb06d21b1d8c179c0be0d92f725 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 15 Jun 2024 13:22:39 +1200 Subject: [PATCH 355/652] ist8310: do reset before WHOAMI call (#23161) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * ist8310: do reset before WHOAMI call Apparently, the IST8310's WHOAMI register is writeable. Presumably, this can get corrupted by bus noise. It is only reset if powered off for 30s. Therefore, we do a reset before doing the WHOAMI. * ist8310: improve comment Co-authored-by: Beat Küng --------- Co-authored-by: Beat Küng --- src/drivers/magnetometer/isentek/ist8310/IST8310.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp b/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp index b7d8512ce931..d48321d14845 100644 --- a/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp +++ b/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp @@ -85,6 +85,15 @@ void IST8310::print_status() int IST8310::probe() { + // Apparently, the IST8310's WHOAMI register is writeable. Presumably, + // this can get corrupted by bus noise. It is only reset if powered off + // for 30s or by a reset. + // + // Therefore, we do a reset before doing the WHOAMI. + RegisterWrite(Register::CNTL2, CNTL2_BIT::SRST); + + px4_usleep(10000); + const uint8_t WAI = RegisterRead(Register::WAI); if (WAI != Device_ID) { From 4fe0bb47622322c3404c0d23604ed04715c415f0 Mon Sep 17 00:00:00 2001 From: Isidro Date: Sat, 15 Jun 2024 03:41:05 +0200 Subject: [PATCH 356/652] fix find in "files_to_check_code_style.sh" (#23269) * refactor: not necessary "if [ -f "$FILE" ]" * fix: exclude directories --------- Co-authored-by: Isidro Arias --- Tools/astyle/check_code_style.sh | 28 +++++++++++------------ Tools/astyle/files_to_check_code_style.sh | 2 +- 2 files changed, 14 insertions(+), 16 deletions(-) diff --git a/Tools/astyle/check_code_style.sh b/Tools/astyle/check_code_style.sh index 3a2fcef35be8..c68b32a9a2bc 100755 --- a/Tools/astyle/check_code_style.sh +++ b/Tools/astyle/check_code_style.sh @@ -3,22 +3,20 @@ FILE=$1 DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) -if [ -f "$FILE" ]; then - CHECK_FAILED=$(${DIR}/fix_code_style.sh --dry-run --formatted $FILE) - if [ -n "$CHECK_FAILED" ]; then - ${DIR}/fix_code_style.sh --quiet < $FILE > $FILE.pretty +CHECK_FAILED=$(${DIR}/fix_code_style.sh --dry-run --formatted $FILE) +if [ -n "$CHECK_FAILED" ]; then + ${DIR}/fix_code_style.sh --quiet < $FILE > $FILE.pretty - echo -e 'Formatting issue found in' $FILE - echo - git --no-pager diff --no-index --minimal --histogram --color=always $FILE $FILE.pretty | grep -vE -e "^.{,4}diff.*\.pretty.{,3}$" -e "^.{,4}--- a/.*$" -e "^.{,4}\+\+\+ b/.*$" -e "^.{,5}@@ .* @@.*$" -e "^.{,4}index .{10}\.\." - rm -f $FILE.pretty - echo + echo -e 'Formatting issue found in' $FILE + echo + git --no-pager diff --no-index --minimal --histogram --color=always $FILE $FILE.pretty | grep -vE -e "^.{,4}diff.*\.pretty.{,3}$" -e "^.{,4}--- a/.*$" -e "^.{,4}\+\+\+ b/.*$" -e "^.{,5}@@ .* @@.*$" -e "^.{,4}index .{10}\.\." + rm -f $FILE.pretty + echo - if [[ $PX4_ASTYLE_FIX -eq 1 ]]; then - ${DIR}/fix_code_style.sh $FILE - else - echo 'to fix automatically run "make format" or "./Tools/astyle/fix_code_style.sh' $FILE'"' - exit 1 - fi + if [[ $PX4_ASTYLE_FIX -eq 1 ]]; then + ${DIR}/fix_code_style.sh $FILE + else + echo 'to fix automatically run "make format" or "./Tools/astyle/fix_code_style.sh' $FILE'"' + exit 1 fi fi diff --git a/Tools/astyle/files_to_check_code_style.sh b/Tools/astyle/files_to_check_code_style.sh index 734d6f5323d5..97a2d8c6fc86 100755 --- a/Tools/astyle/files_to_check_code_style.sh +++ b/Tools/astyle/files_to_check_code_style.sh @@ -31,4 +31,4 @@ exec find boards msg src platforms test \ -path src/lib/cdrstream/rosidl -prune -o \ -path src/modules/zenoh/zenoh-pico -prune -o \ -path boards/modalai/voxl2/libfc-sensor-api -prune -o \ - -type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN + \( -type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) -print \) | grep $PATTERN From fcb479cd3d667e3625fca37111c524c2a04a08b6 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Fri, 14 Jun 2024 17:43:15 -0800 Subject: [PATCH 357/652] platforms: nuttx: SerialImpl: fix poll timeout and integer underflow (#23248) * platforms: nuttx: SerialImpl: fix poll timeout * platforms: posix: SerialImpl: fix poll timeout --- platforms/nuttx/src/px4/common/SerialImpl.cpp | 6 +++--- platforms/posix/src/px4/common/SerialImpl.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index 3131435a0f5c..19533659d01e 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -272,11 +272,11 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char fds[0].fd = _serial_fd; fds[0].events = POLLIN; - hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us); + hrt_abstime elapsed_time_us = hrt_elapsed_time(&start_time_us); - if (remaining_time <= 0) { break; } + if (elapsed_time_us > timeout_us) { break; } - int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time); + int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), (timeout_us - elapsed_time_us) / 1000); if (ret > 0) { if (fds[0].revents & POLLIN) { diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 03a5a6543739..f92e1e308f51 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -265,11 +265,11 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char fds[0].fd = _serial_fd; fds[0].events = POLLIN; - hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us); + hrt_abstime elapsed_time_us = hrt_elapsed_time(&start_time_us); - if (remaining_time <= 0) { break; } + if (elapsed_time_us > timeout_us) { break; } - int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time); + int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), (timeout_us - elapsed_time_us) / 1000); if (ret > 0) { if (fds[0].revents & POLLIN) { From ad58808cf31dfcbb3b606f19631de4a9d5165893 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 17 Jun 2024 16:25:56 +0200 Subject: [PATCH 358/652] update gazebo classic (#23276) Signed-off-by: Silvan Fuhrer --- Tools/simulation/gazebo-classic/sitl_gazebo-classic | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/simulation/gazebo-classic/sitl_gazebo-classic b/Tools/simulation/gazebo-classic/sitl_gazebo-classic index da7206e05770..67431d233f0f 160000 --- a/Tools/simulation/gazebo-classic/sitl_gazebo-classic +++ b/Tools/simulation/gazebo-classic/sitl_gazebo-classic @@ -1 +1 @@ -Subproject commit da7206e057703cc645770f02437013358b71e1c0 +Subproject commit 67431d233f0f08de647f0eb11239816f9c8bd6c6 From 96360f3069b63d5117db3d00093cc3e812486d58 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Fri, 14 Jun 2024 17:07:52 -0800 Subject: [PATCH 359/652] boards: fmu-v5: disable FAKE_GPS and SD_BENCH --- boards/px4/fmu-v5/default.px4board | 2 -- 1 file changed, 2 deletions(-) diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index 321113dd3cef..f2944c3e374b 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -98,7 +98,6 @@ CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_REFLECT=y -CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y @@ -107,4 +106,3 @@ CONFIG_SYSTEMCMDS_UORB=y CONFIG_SYSTEMCMDS_USB_CONNECTED=y CONFIG_SYSTEMCMDS_VER=y CONFIG_SYSTEMCMDS_WORK_QUEUE=y -CONFIG_EXAMPLES_FAKE_GPS=y From 2515b8fc63399ea93332bcefeecc8ddd11cdda18 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Fri, 14 Jun 2024 17:09:16 -0800 Subject: [PATCH 360/652] kconfig: common_distance_sensor: remove MB12XX --- src/drivers/distance_sensor/Kconfig | 1 - 1 file changed, 1 deletion(-) diff --git a/src/drivers/distance_sensor/Kconfig b/src/drivers/distance_sensor/Kconfig index 43c8f3cc9227..f45abe877c50 100644 --- a/src/drivers/distance_sensor/Kconfig +++ b/src/drivers/distance_sensor/Kconfig @@ -8,7 +8,6 @@ menu "Distance sensors" select DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C select DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL select DRIVERS_DISTANCE_SENSOR_LL40LS - select DRIVERS_DISTANCE_SENSOR_MB12XX select DRIVERS_DISTANCE_SENSOR_SRF02 select DRIVERS_DISTANCE_SENSOR_TERARANGER select DRIVERS_DISTANCE_SENSOR_TF02PRO From f9160853fa2a0db214fcd4004d6622fd9c78e5ba Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 17 Jun 2024 11:52:17 -0400 Subject: [PATCH 361/652] rc_update: purge deprecated RC switch parameters - these are old RC switch configuration parameters that haven't been used for years, but were hardcoded into old versions of QGC - RC_MAP_RATT_SW, RC_MAP_POSCTL_SW, RC_MAP_ACRO_SW, RC_MAP_STAB_SW, RC_MAP_MAN_SW deleted - --- src/modules/rc_update/params_deprecated.c | 140 ---------------------- src/modules/rc_update/rc_update.cpp | 37 +----- 2 files changed, 1 insertion(+), 176 deletions(-) diff --git a/src/modules/rc_update/params_deprecated.c b/src/modules/rc_update/params_deprecated.c index 93c06dd19c0b..550f2169ee12 100644 --- a/src/modules/rc_update/params_deprecated.c +++ b/src/modules/rc_update/params_deprecated.c @@ -63,143 +63,3 @@ * @value 18 Channel 18 */ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); - -/** - * Rattitude switch channel (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_RATT_SW, 0); - -/** - * Position Control switch channel (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0); - -/** - * Acro switch channel (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0); - -/** - * Stabilize switch channel mapping (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_STAB_SW, 0); - -/** - * Manual switch channel mapping (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_MAN_SW, 0); diff --git a/src/modules/rc_update/rc_update.cpp b/src/modules/rc_update/rc_update.cpp index 6aa4ffd20b52..fb5491d7653c 100644 --- a/src/modules/rc_update/rc_update.cpp +++ b/src/modules/rc_update/rc_update.cpp @@ -162,8 +162,8 @@ void RCUpdate::updateParams() || _param_rc_map_pitch.get() > 0 || _param_rc_map_yaw.get() > 0); - // deprecated parameters, will be removed post v1.12 once QGC is updated { + // deprecated parameter, needs to be fully removed from QGC int32_t rc_map_value = 0; if (param_get(param_find("RC_MAP_MODE_SW"), &rc_map_value) == PX4_OK) { @@ -172,41 +172,6 @@ void RCUpdate::updateParams() param_reset(param_find("RC_MAP_MODE_SW")); } } - - if (param_get(param_find("RC_MAP_RATT_SW"), &rc_map_value) == PX4_OK) { - if (rc_map_value != 0) { - PX4_WARN("RC_MAP_RATT_SW deprecated"); - param_reset(param_find("RC_MAP_RATT_SW")); - } - } - - if (param_get(param_find("RC_MAP_POSCTL_SW"), &rc_map_value) == PX4_OK) { - if (rc_map_value != 0) { - PX4_WARN("RC_MAP_POSCTL_SW deprecated"); - param_reset(param_find("RC_MAP_POSCTL_SW")); - } - } - - if (param_get(param_find("RC_MAP_ACRO_SW"), &rc_map_value) == PX4_OK) { - if (rc_map_value != 0) { - PX4_WARN("RC_MAP_ACRO_SW deprecated"); - param_reset(param_find("RC_MAP_ACRO_SW")); - } - } - - if (param_get(param_find("RC_MAP_STAB_SW"), &rc_map_value) == PX4_OK) { - if (rc_map_value != 0) { - PX4_WARN("RC_MAP_STAB_SW deprecated"); - param_reset(param_find("RC_MAP_STAB_SW")); - } - } - - if (param_get(param_find("RC_MAP_MAN_SW"), &rc_map_value) == PX4_OK) { - if (rc_map_value != 0) { - PX4_WARN("RC_MAP_MAN_SW deprecated"); - param_reset(param_find("RC_MAP_MAN_SW")); - } - } } // Center throttle trim when it's set to the minimum to correct for hardcoded QGC RC calibration From cd4c495377bd1a97976eff67a35382a1447ed356 Mon Sep 17 00:00:00 2001 From: Thomas Frans <160142177+flyingthingsintothings@users.noreply.github.com> Date: Mon, 17 Jun 2024 18:25:24 +0200 Subject: [PATCH 362/652] drivers/gps: extract Septentrio into new standalone drivers/gnss/septentrio module (#22904) Having a generic interface over the GPS drivers makes dedicated functionality for each driver harder. Move the Septentrio driver into its own module under the `gnss` driver directory, and let it have its own parameters for only the functionality it requires. This also helps with adding new features because they only need to be implemented for the driver that wants it, simplifying testing. --- boards/cuav/nora/default.px4board | 1 + boards/cubepilot/cubeorange/default.px4board | 1 + .../cubepilot/cubeorangeplus/default.px4board | 1 + boards/mro/pixracerpro/default.px4board | 1 + boards/px4/fmu-v2/default.px4board | 1 + boards/px4/fmu-v3/default.px4board | 1 + boards/px4/fmu-v4/default.px4board | 1 + msg/GpsDump.msg | 12 +- msg/SensorGps.msg | 9 +- src/drivers/gnss/Kconfig | 1 + src/drivers/gnss/septentrio/CMakeLists.txt | 50 + src/drivers/gnss/septentrio/Kconfig | 5 + src/drivers/gnss/septentrio/README.md | 6 + src/drivers/gnss/septentrio/module.h | 80 + src/drivers/gnss/septentrio/module.yaml | 205 ++ src/drivers/gnss/septentrio/rtcm.cpp | 162 ++ src/drivers/gnss/septentrio/rtcm.h | 132 ++ src/drivers/gnss/septentrio/sbf/decoder.cpp | 252 +++ src/drivers/gnss/septentrio/sbf/decoder.h | 233 +++ src/drivers/gnss/septentrio/sbf/messages.h | 353 ++++ src/drivers/gnss/septentrio/septentrio.cpp | 1702 +++++++++++++++++ src/drivers/gnss/septentrio/septentrio.h | 715 +++++++ src/drivers/gnss/septentrio/util.cpp | 59 + src/drivers/gnss/septentrio/util.h | 50 + src/drivers/gps/CMakeLists.txt | 3 +- src/drivers/gps/gps.cpp | 27 +- src/drivers/gps/params.c | 21 +- 27 files changed, 4028 insertions(+), 56 deletions(-) create mode 100644 src/drivers/gnss/Kconfig create mode 100644 src/drivers/gnss/septentrio/CMakeLists.txt create mode 100644 src/drivers/gnss/septentrio/Kconfig create mode 100644 src/drivers/gnss/septentrio/README.md create mode 100644 src/drivers/gnss/septentrio/module.h create mode 100644 src/drivers/gnss/septentrio/module.yaml create mode 100644 src/drivers/gnss/septentrio/rtcm.cpp create mode 100644 src/drivers/gnss/septentrio/rtcm.h create mode 100644 src/drivers/gnss/septentrio/sbf/decoder.cpp create mode 100644 src/drivers/gnss/septentrio/sbf/decoder.h create mode 100644 src/drivers/gnss/septentrio/sbf/messages.h create mode 100644 src/drivers/gnss/septentrio/septentrio.cpp create mode 100644 src/drivers/gnss/septentrio/septentrio.h create mode 100644 src/drivers/gnss/septentrio/util.cpp create mode 100644 src/drivers/gnss/septentrio/util.h diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index 2a0e40e37efe..8c3e304856c3 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -14,6 +14,7 @@ CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y diff --git a/boards/cubepilot/cubeorange/default.px4board b/boards/cubepilot/cubeorange/default.px4board index e3c84b183895..480f896d67cf 100644 --- a/boards/cubepilot/cubeorange/default.px4board +++ b/boards/cubepilot/cubeorange/default.px4board @@ -15,6 +15,7 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/cubepilot/cubeorangeplus/default.px4board b/boards/cubepilot/cubeorangeplus/default.px4board index d755eea8d814..e3fc787417c6 100644 --- a/boards/cubepilot/cubeorangeplus/default.px4board +++ b/boards/cubepilot/cubeorangeplus/default.px4board @@ -15,6 +15,7 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index 40301136e26a..fb49c90866cb 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -13,6 +13,7 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_BOSCH_BMI085=y CONFIG_DRIVERS_IMU_BOSCH_BMI088=y diff --git a/boards/px4/fmu-v2/default.px4board b/boards/px4/fmu-v2/default.px4board index f0753941e03d..b796d1bfbf49 100644 --- a/boards/px4/fmu-v2/default.px4board +++ b/boards/px4/fmu-v2/default.px4board @@ -10,6 +10,7 @@ CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y CONFIG_DRIVERS_IMU_ST_L3GD20=y diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index 5c24d0e731fb..96b71c0cf653 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -15,6 +15,7 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y diff --git a/boards/px4/fmu-v4/default.px4board b/boards/px4/fmu-v4/default.px4board index ab106bdb7b90..e7906db52c85 100644 --- a/boards/px4/fmu-v4/default.px4board +++ b/boards/px4/fmu-v4/default.px4board @@ -15,6 +15,7 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y diff --git a/msg/GpsDump.msg b/msg/GpsDump.msg index 3aa1313aa680..2477bcfa3a1e 100644 --- a/msg/GpsDump.msg +++ b/msg/GpsDump.msg @@ -1,12 +1,10 @@ # This message is used to dump the raw gps communication to the log. -# Set the parameter GPS_DUMP_COMM to 1 to use this. -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # time since system start (microseconds) -uint8 instance # Instance of GNSS receiver - -uint8 len # length of data, MSB bit set = message to the gps device, - # clear = message from the device -uint8[79] data # data to write to the log +uint8 instance # Instance of GNSS receiver +uint8 len # length of data, MSB bit set = message to the gps device, + # clear = message from the device +uint8[79] data # data to write to the log uint8 ORB_QUEUE_LENGTH = 8 diff --git a/msg/SensorGps.msg b/msg/SensorGps.msg index db18899cb1c0..ce2bfad4fd8e 100644 --- a/msg/SensorGps.msg +++ b/msg/SensorGps.msg @@ -12,7 +12,14 @@ float64 altitude_ellipsoid_m # Altitude above Ellipsoid, meters float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec) float32 c_variance_rad # GPS course accuracy estimate, (radians) -uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. +uint8 FIX_TYPE_NONE = 1 # Value 0 is also valid to represent no fix. +uint8 FIX_TYPE_2D = 2 +uint8 FIX_TYPE_3D = 3 +uint8 FIX_TYPE_RTCM_CODE_DIFFERENTIAL = 4 +uint8 FIX_TYPE_RTK_FLOAT = 5 +uint8 FIX_TYPE_RTK_FIXED = 6 +uint8 FIX_TYPE_EXTRAPOLATED = 8 +uint8 fix_type # Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. float32 eph # GPS horizontal position accuracy (metres) float32 epv # GPS vertical position accuracy (metres) diff --git a/src/drivers/gnss/Kconfig b/src/drivers/gnss/Kconfig new file mode 100644 index 000000000000..6353836988b2 --- /dev/null +++ b/src/drivers/gnss/Kconfig @@ -0,0 +1 @@ +rsource "*/Kconfig" diff --git a/src/drivers/gnss/septentrio/CMakeLists.txt b/src/drivers/gnss/septentrio/CMakeLists.txt new file mode 100644 index 000000000000..62451fc9b1f3 --- /dev/null +++ b/src/drivers/gnss/septentrio/CMakeLists.txt @@ -0,0 +1,50 @@ +############################################################################ +# +# 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_module( + MODULE driver__septentrio + MAIN septentrio + COMPILE_FLAGS + # -DDEBUG_BUILD # Enable during development of the module + -DSEP_LOG_ERROR # Enable module-level error logs + # -DSEP_LOG_WARN # Enable module-level warning logs + # -DSEP_LOG_INFO # Enable module-level info logs + # -DSEP_LOG_TRACE_PARSING # Tracing of parsing steps + SRCS + septentrio.cpp + util.cpp + rtcm.cpp + sbf/decoder.cpp + MODULE_CONFIG + module.yaml + ) diff --git a/src/drivers/gnss/septentrio/Kconfig b/src/drivers/gnss/septentrio/Kconfig new file mode 100644 index 000000000000..5d3d52388587 --- /dev/null +++ b/src/drivers/gnss/septentrio/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_GNSS_SEPTENTRIO + bool "Septentrio GNSS receivers" + default n + ---help--- + Enable support for Septentrio receivers diff --git a/src/drivers/gnss/septentrio/README.md b/src/drivers/gnss/septentrio/README.md new file mode 100644 index 000000000000..664df63a145d --- /dev/null +++ b/src/drivers/gnss/septentrio/README.md @@ -0,0 +1,6 @@ +# Septentrio GNSS Driver + +## SBF Library + +The `sbf/` directory contains all the logic required to work with SBF, including message +definitions, block IDs and a simple parser for the messages used by PX4. \ No newline at end of file diff --git a/src/drivers/gnss/septentrio/module.h b/src/drivers/gnss/septentrio/module.h new file mode 100644 index 000000000000..28b52240b643 --- /dev/null +++ b/src/drivers/gnss/septentrio/module.h @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file module.h + * + * Module functionality for the Septentrio GNSS driver. + * + * @author Thomas Frans +*/ + +#pragma once + +#include + +#ifdef DEBUG_BUILD +#ifndef SEP_LOG_ERROR +#define SEP_LOG_ERROR +#endif +#ifndef SEP_LOG_WARN +#define SEP_LOG_WARN +#endif +#ifndef SEP_LOG_INFO +#define SEP_LOG_INFO +#endif +#endif + +#ifdef SEP_LOG_ERROR +#define SEP_ERR(...) {PX4_WARN(__VA_ARGS__);} +#else +#define SEP_ERR(...) {} +#endif + +#ifdef SEP_LOG_WARN +#define SEP_WARN(...) {PX4_WARN(__VA_ARGS__);} +#else +#define SEP_WARN(...) {} +#endif + +#ifdef SEP_LOG_INFO +#define SEP_INFO(...) {PX4_INFO(__VA_ARGS__);} +#else +#define SEP_INFO(...) {} +#endif + +#ifdef SEP_LOG_TRACE_PARSING +#define SEP_TRACE_PARSING(...) {PX4_DEBUG(__VA_ARGS__);} +#else +#define SEP_TRACE_PARSING(...) {} +#endif diff --git a/src/drivers/gnss/septentrio/module.yaml b/src/drivers/gnss/septentrio/module.yaml new file mode 100644 index 000000000000..49788b7f9759 --- /dev/null +++ b/src/drivers/gnss/septentrio/module.yaml @@ -0,0 +1,205 @@ +module_name: Septentrio + +serial_config: + - command: set DUAL_GPS_ARGS "-e ${SERIAL_DEV} -g p:${BAUD_PARAM}" + port_config_param: + name: SEP_PORT2_CFG + group: Septentrio + label: Secondary GPS port + - command: septentrio start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} ${DUAL_GPS_ARGS} + port_config_param: + name: SEP_PORT1_CFG + group: Septentrio + default: GPS1 + label: GPS Port + +parameters: + - group: Septentrio + definitions: + SEP_STREAM_MAIN: + description: + short: Main stream used during automatic configuration + long: | + The stream the autopilot sets up on the receiver to output the main data. + + Set this to another value if the default stream is already used for another purpose. + type: int32 + min: 1 + max: 10 + default: 1 + reboot_required: true + SEP_STREAM_LOG: + description: + short: Logging stream used during automatic configuration + long: | + The stream the autopilot sets up on the receiver to output the logging data. + + Set this to another value if the default stream is already used for another purpose. + type: int32 + min: 1 + max: 10 + default: 2 + reboot_required: true + SEP_OUTP_HZ: + description: + short: Output frequency of main SBF blocks + long: | + The output frequency of the main SBF blocks needed for PVT information. + type: enum + min: 0 + max: 3 + default: 1 + values: + 0: 5 Hz + 1: 10 Hz + 2: 20 Hz + 3: 25 Hz + reboot_required: true + SEP_YAW_OFFS: + description: + short: Heading/Yaw offset for dual antenna GPS + long: | + Heading offset angle for dual antenna GPS setups that support heading estimation. + + Set this to 0 if the antennas are parallel to the forward-facing direction + of the vehicle and the rover antenna is in front. + + The offset angle increases clockwise. + + Set this to 90 if the rover antenna is placed on the + right side of the vehicle and the moving base antenna is on the left side. + type: float + decimal: 3 + default: 0 + min: 0 + max: 360 + unit: deg + reboot_required: true + SEP_SAT_INFO: + description: + short: Enable sat info + long: | + Enable publication of satellite info (ORB_ID(satellite_info)) if possible. + type: boolean + default: 0 + reboot_required: true + SEP_PITCH_OFFS: + description: + short: Pitch offset for dual antenna GPS + long: | + Vertical offsets can be compensated for by adjusting the Pitch offset. + + Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. + This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. + Since pitch is defined as the right-handed rotation about the vehicle Y axis, + a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch. + type: float + decimal: 3 + default: 0 + min: -90 + max: 90 + unit: deg + reboot_required: true + SEP_DUMP_COMM: + description: + short: Log GPS communication data + long: | + Dump raw communication data from and to the connected receiver to the log file. + type: enum + default: 0 + min: 0 + max: 3 + values: + 0: Disabled + 1: From receiver + 2: To receiver + 3: Both + SEP_AUTO_CONFIG: + description: + short: Toggle automatic receiver configuration + long: | + By default, the receiver is automatically configured. Sometimes it may be used for multiple purposes. + If the offered parameters aren't sufficient, this parameter can be disabled to have full control of the receiver configuration. + A good way to use this is to enable automatic configuration, let the receiver be configured, and then disable it to make manual adjustments. + type: boolean + default: true + reboot_required: true + SEP_CONST_USAGE: + description: + short: Usage of different constellations + long: | + Choice of which constellations the receiver should use for PVT computation. + + When this is 0, the constellation usage isn't changed. + type: bitmask + bit: + 0: GPS + 1: GLONASS + 2: Galileo + 3: SBAS + 4: BeiDou + default: 0 + min: 0 + max: 63 + reboot_required: true + SEP_LOG_HZ: + description: + short: Logging frequency for the receiver + long: | + Select the frequency at which the connected receiver should log data to its internal storage. + type: enum + default: 0 + min: 0 + max: 10 + values: + 0: Disabled + 1: 0.1 Hz + 2: 0.2 Hz + 3: 0.5 Hz + 4: 1 Hz + 5: 2 Hz + 6: 5 Hz + 7: 10 Hz + 8: 20 Hz + 9: 25 Hz + 10: 50 Hz + reboot_required: true + SEP_LOG_LEVEL: + description: + short: Logging level for the receiver + long: | + Select the level of detail that needs to be logged by the receiver. + type: enum + default: 2 + min: 0 + max: 3 + values: + 0: Lite + 1: Basic + 2: Default + 3: Full + reboot_required: true + SEP_LOG_FORCE: + description: + short: Whether to overwrite or add to existing logging + long: | + When the receiver is already set up to log data, this decides whether extra logged data should be added or overwrite existing data. + type: boolean + default: false + reboot_required: true + SEP_HARDW_SETUP: + description: + short: Setup and expected use of the hardware + long: | + Setup and expected use of the hardware. + + - Default: Use two receivers as completely separate instances. + - Moving base: Use two receivers in a rover & moving base setup for heading. + type: enum + default: 0 + min: 0 + max: 1 + values: + 0: Default + 1: Moving base + reboot_required: true diff --git a/src/drivers/gnss/septentrio/rtcm.cpp b/src/drivers/gnss/septentrio/rtcm.cpp new file mode 100644 index 000000000000..007b2a168e33 --- /dev/null +++ b/src/drivers/gnss/septentrio/rtcm.cpp @@ -0,0 +1,162 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file rtcm.cpp + * + * @author Thomas Frans +*/ + +#include "rtcm.h" + +#include +#include + +#include "module.h" + +namespace septentrio +{ + +namespace rtcm +{ + +Decoder::Decoder() +{ + reset(); +} + +Decoder::~Decoder() +{ + delete[] _message; +} + +Decoder::State Decoder::add_byte(uint8_t byte) +{ + switch (_state) { + case State::SearchingPreamble: + if (byte == PREAMBLE) { + _message[_current_index] = byte; + _current_index++; + _state = State::GettingHeader; + } + + break; + + case State::GettingHeader: + _message[_current_index] = byte; + _current_index++; + + if (header_received()) { + _message_length = parse_message_length(); + + if (_message_length > MAX_BODY_SIZE) { + reset(); + return _state; + + } else if (_message_length + HEADER_SIZE + CRC_SIZE > INITIAL_BUFFER_LENGTH) { + uint16_t new_buffer_size = _message_length + HEADER_SIZE + CRC_SIZE; + uint8_t *new_buffer = new uint8_t[new_buffer_size]; + + if (!new_buffer) { + reset(); + return _state; + } + + memcpy(new_buffer, _message, HEADER_SIZE); + delete[](_message); + + _message = new_buffer; + } + + _state = State::Busy; + } + + break; + + case State::Busy: + _message[_current_index] = byte; + _current_index++; + + if (_message_length + HEADER_SIZE + CRC_SIZE == _current_index) { + _state = State::Done; + } + + break; + + case State::Done: + SEP_WARN("RTCM: Discarding excess byte"); + break; + } + + return _state; +} + +void Decoder::reset() +{ + if (_message) { + delete[] _message; + } + + _message = new uint8_t[INITIAL_BUFFER_LENGTH]; + _current_index = 0; + _message_length = 0; + _state = State::SearchingPreamble; +} + +uint16_t Decoder::parse_message_length() const +{ + if (!header_received()) { + return PX4_ERROR; + } + + return ((static_cast(_message[1]) & 3) << 8) | _message[2]; +} + +bool Decoder::header_received() const +{ + return _current_index >= HEADER_SIZE; +} + +uint16_t Decoder::received_bytes() const +{ + return _current_index; +} + +uint16_t Decoder::message_id() const +{ + return (_message[3] << 4) | (_message[4] >> 4); +} + +} // namespace rtcm + +} // namespace septentrio diff --git a/src/drivers/gnss/septentrio/rtcm.h b/src/drivers/gnss/septentrio/rtcm.h new file mode 100644 index 000000000000..672ac08da9e1 --- /dev/null +++ b/src/drivers/gnss/septentrio/rtcm.h @@ -0,0 +1,132 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file rtcm.h + * + * @author Thomas Frans + */ + +#pragma once + +#include +#include + +namespace septentrio +{ + +namespace rtcm +{ + +constexpr uint8_t PREAMBLE = 0xD3; +constexpr uint8_t HEADER_SIZE = 3; ///< Total number of bytes in a message header. +constexpr uint8_t CRC_SIZE = 3; ///< Total number of bytes in the CRC. +constexpr uint8_t LENGTH_FIELD_BITS = 10; ///< Total number of bits used for the length. +constexpr uint16_t MAX_BODY_SIZE = 1 << LENGTH_FIELD_BITS; ///< Maximum allowed size of the message body. + +class Decoder +{ +public: + enum class State { + /// Searching for the first byte of an RTCM message. + SearchingPreamble, + + /// Getting the complete header of an RTCM message. + GettingHeader, + + /// Getting a complete RTCM message. + Busy, + + /// Complete RTCM message is available. + Done, + }; + + Decoder(); + ~Decoder(); + + /** + * Add a byte to the current message. + * + * @param byte The new byte. + * + * @return true if message complete (use @message to get it) + */ + State add_byte(uint8_t b); + + /** + * @brief Reset the parser to a clean state. + */ + void reset(); + + uint8_t *message() const { return _message; } + + /** + * @brief Number of received bytes of the current message. + */ + uint16_t received_bytes() const; + + /** + * @brief The id of the current message. + * + * This should only be called if the message has been received completely. + * + * @return The id of the current complete message. + */ + uint16_t message_id() const; + +private: + static constexpr uint16_t INITIAL_BUFFER_LENGTH = 300; + + /** + * @brief Parse the message lentgh of the current message. + * + * @return The expected length of the current message without header and CRC. + */ + uint16_t parse_message_length() const; + + /** + * @brief Check whether the full header has been received. + * + * @return `true` if the full header is available, `false` otherwise. + */ + bool header_received() const; + + uint8_t *_message{nullptr}; + uint16_t _message_length; ///< The total length of the message excluding header and CRC (3 bytes each). + uint16_t _current_index; ///< The current index of the byte we expect to read into the buffer. + State _state{State::SearchingPreamble}; ///< Current state of the parser. +}; + +} // namespace rtcm + +} // namespace septentrio diff --git a/src/drivers/gnss/septentrio/sbf/decoder.cpp b/src/drivers/gnss/septentrio/sbf/decoder.cpp new file mode 100644 index 000000000000..318a5c4db968 --- /dev/null +++ b/src/drivers/gnss/septentrio/sbf/decoder.cpp @@ -0,0 +1,252 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file decoder.cpp + * + * Decoding logic for the Septentrio Binary Format (SBF). + * + * @author Thomas Frans + */ + +#include "decoder.h" + +#include +#include +#include +#include + +#include "../module.h" +#include "../util.h" +#include "drivers/gnss/septentrio/sbf/messages.h" + +namespace septentrio +{ + +namespace sbf +{ + +Decoder::State Decoder::add_byte(uint8_t byte) +{ + uint8_t *message = reinterpret_cast(&_message); + + switch (_state) { + case State::SearchingSync1: + if (byte == (uint8_t)k_sync1) { + // Sync is always same, so we don't store it. + _current_index++; + _state = State::SearchingSync2; + } + + break; + + case State::SearchingSync2: + if (byte == (uint8_t)k_sync2) { + // Sync is always same, so we don't store it. + _current_index++; + _state = State::Busy; + + } else { + reset(); + } + + break; + + case State::Busy: + message[_current_index] = byte; + _current_index++; + + if (done()) { + _state = State::Done; + } + + break; + + case State::Done: + SEP_WARN("SBF: Discarding excess byte"); + break; + } + + return _state; +} + +BlockID Decoder::id() const +{ + return _state == State::Done ? _message.header.id_number : BlockID::Invalid; +} + +int Decoder::parse(Header *header) const +{ + if (can_parse()) { + memcpy(header, &_message.header, sizeof(Header)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(DOP *message) const +{ + if (can_parse() && id() == BlockID::DOP) { + memcpy(message, _message.payload, sizeof(DOP)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(PVTGeodetic *message) const +{ + if (can_parse() && id() == BlockID::PVTGeodetic) { + memcpy(message, _message.payload, sizeof(PVTGeodetic)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(ReceiverStatus *message) const +{ + if (can_parse() && id() == BlockID::ReceiverStatus) { + memcpy(message, _message.payload, sizeof(ReceiverStatus)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(QualityInd *message) const +{ + if (can_parse() && id() == BlockID::QualityInd) { + // Safe to copy entire size of the message as it is smaller than the maximum expected SBF message size. + // It's up to the user of the parsed message to ignore the invalid fields. + memcpy(message, _message.payload, sizeof(QualityInd)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(RFStatus *message) const +{ + if (can_parse() && id() == BlockID::PVTGeodetic) { + memcpy(message, _message.payload, sizeof(RFStatus) - sizeof(RFStatus::rf_band)); + + for (uint8_t i = 0; i < math::min(message->n, k_max_rfband_blocks); i++) { + memcpy(&message->rf_band[i], &_message.payload[sizeof(RFStatus) - sizeof(RFStatus::rf_band) + i * + message->sb_length], sizeof(RFBand)); + } + + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(GALAuthStatus *message) const +{ + if (can_parse() && id() == BlockID::GALAuthStatus) { + memcpy(message, _message.payload, sizeof(GALAuthStatus)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(VelCovGeodetic *message) const +{ + if (can_parse() && id() == BlockID::VelCovGeodetic) { + memcpy(message, _message.payload, sizeof(VelCovGeodetic)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(GEOIonoDelay *message) const +{ + if (can_parse() && id() == BlockID::GEOIonoDelay) { + memcpy(message, _message.payload, sizeof(GEOIonoDelay) - sizeof(GEOIonoDelay::idc)); + + for (size_t i = 0; i < math::min(message->n, (uint8_t)4); i++) { + memcpy(&message->idc[i], &_message.payload[sizeof(GEOIonoDelay) - sizeof(GEOIonoDelay::idc) + i * + message->sb_length], sizeof(IDC)); + } + + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(AttEuler *message) const +{ + if (can_parse() && id() == BlockID::AttEuler) { + memcpy(message, _message.payload, sizeof(AttEuler)); + return PX4_OK; + } + + return PX4_ERROR; +} + +int Decoder::parse(AttCovEuler *message) const +{ + if (can_parse() && id() == BlockID::AttCovEuler) { + memcpy(message, _message.payload, sizeof(AttCovEuler)); + return PX4_OK; + } + + return PX4_ERROR; +} + +void Decoder::reset() +{ + _current_index = 0; + _state = State::SearchingSync1; + memset(&_message, 0, sizeof(_message)); +} + +bool Decoder::done() const +{ + return (_current_index >= 14 && _current_index >= _message.header.length) || _current_index >= sizeof(_message); +} + +bool Decoder::can_parse() const +{ + return done() + && _message.header.crc == buffer_crc16(reinterpret_cast(&_message) + 4, _message.header.length - 4); +} + +} // namespace sbf + +} // namespace septentrio diff --git a/src/drivers/gnss/septentrio/sbf/decoder.h b/src/drivers/gnss/septentrio/sbf/decoder.h new file mode 100644 index 000000000000..78a62ebc0f42 --- /dev/null +++ b/src/drivers/gnss/septentrio/sbf/decoder.h @@ -0,0 +1,233 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file decoder.h + * + * Decoding logic for the Septentrio Binary Format (SBF). + * + * @author Thomas Frans +*/ + +#pragma once + +#include + +#include "messages.h" + +namespace septentrio +{ + +namespace sbf +{ + +#pragma pack(push, 1) + +/// A complete SBF message with parsed header and unparsed body. +typedef struct { + Header header; + uint8_t payload[k_max_message_size]; +} message_t; + +#pragma pack(pop) + +/** + * @brief A decoder and parser for Septentrio Binary Format (SBF) data. + */ +class Decoder +{ +public: + /** + * @brief The current decoding state of the decoder. + */ + enum class State { + /// Searching for the first sync byte of an SBF message. + SearchingSync1, + + /// Searching for the second sync byte of an SBF message. + SearchingSync2, + + /// In the process of receiving an SBF message. + Busy, + + /// Done receiving an SBF message and ready to parse. + Done, + }; + + /** + * @brief Add one byte to the decoder. + * + * @param byte The byte to add. + * + * @return The decoding state after adding the byte. + */ + State add_byte(uint8_t byte); + + /** + * @brief Get the id of the current message. + * + * @return The SBF id of the current message. + */ + BlockID id() const; + + /** + * @brief Try to parse the current header. + * + * @param header The header data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(Header *header) const; + + /** + * @brief Parse a DOP SBF message. + * + * @param message The DOP data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(DOP *message) const; + + /** + * @brief Parse a PVTGeodetic SBF message. + * + * @param message The PVTGeodetic data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(PVTGeodetic *message) const; + + /** + * @brief Parse a ReceiverStatus SBF message. + * + * @param message The ReceiverStatus data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(ReceiverStatus *message) const; + + /** + * @brief Parse a QualityInd SBF message. + * + * @param message The QualityInd data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(QualityInd *message) const; + + /** + * @brief Parse an RFSTatus SBF message. + * + * @param message The RFStatus data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(RFStatus *message) const; + + /** + * @brief Parse a GALAuthStatus SBF message. + * + * @param message The GALAuthStatus data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(GALAuthStatus *message) const; + + /** + * @brief Parse a VelCovGeodetic SBF message. + * + * @param message The VelCovGeodetic data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(VelCovGeodetic *message) const; + + /** + * @brief Parse a GEOIonoDelay SBF message. + * + * @param message The GEOIonoDelay data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(GEOIonoDelay *message) const; // NOTE: This serves as an example of how to parse sub-blocks. + + /** + * @brief Parse an AttEuler SBF message. + * + * @param message The AttEuler data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(AttEuler *message) const; + + /** + * @brief Parse an AttCovEuler SBF message. + * + * @param message The AttCovEuler data structure to parse into. + * + * @return `PX4_OK` if success, or `PX4_ERROR` when an error occurs. + */ + int parse(AttCovEuler *message) const; + + /** + * @brief Reset the decoder to a clean state. + * + * If the decoder is in the process of decoding a message or contains a complete message, it will discard it and + * become ready for the next message. + */ + void reset(); +private: + /** + * @brief Check whether a full message has been received. + * + * Does not guarantee validity of the message, only that a complete message should be available. + * + * @return `true` if a message is ready, `false` if still decoding. + */ + bool done() const; + + /** + * @brief Check whether a full message has been received and is valid. + * + * @return `true` if the data can be parsed, `false` if the message is incomplete or not valid. + */ + bool can_parse() const; + + State _state{State::SearchingSync1}; + uint16_t _current_index; + message_t _message; +}; + +} // namespace sbf + +} // namespace septentrio diff --git a/src/drivers/gnss/septentrio/sbf/messages.h b/src/drivers/gnss/septentrio/sbf/messages.h new file mode 100644 index 000000000000..e51a6f469b31 --- /dev/null +++ b/src/drivers/gnss/septentrio/sbf/messages.h @@ -0,0 +1,353 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file messages.h + * + * @brief Septentrio binary format (SBF) protocol message definitions. + * + * @author Thomas Frans + */ + +#pragma once + +#include +#include + +namespace septentrio +{ + +namespace sbf +{ + +constexpr char k_sync1 {'$'}; +constexpr char k_sync2 {'@'}; + +// Do-Not-Use values for fields in SBF blocks. The receiver can set certain fields to these values to signal that they are invalid. +// Most fields of a certain type will use these values (u2 representing a value often has DNU value of 65535). +// For the ones that do not use these, custom ones can be specified together with the blocks. +constexpr uint32_t k_dnu_u4_value {4294967295}; +constexpr uint32_t k_dnu_u4_bitfield {0}; +constexpr uint16_t k_dnu_u2_value {65535}; +constexpr uint16_t k_dnu_u2_bitfield {0}; +constexpr float k_dnu_f4_value {-2 * 10000000000}; +constexpr double k_dnu_f8_value {-2 * 10000000000}; + +/// Maximum size of all expected messages. +/// This needs to be bigger than the maximum size of all declared SBF blocks so that `memcpy()` can safely copy from the decoding buffer using this value into messages. +constexpr size_t k_max_message_size {300}; + +/// Maximum expected number of sub-blocks. +constexpr uint8_t k_max_quality_indicators {9}; +constexpr uint8_t k_max_rfband_blocks {4}; + +/** + * IDs of all the available SBF messages that we care about. +*/ +enum class BlockID : uint16_t { + Invalid = 0, + DOP = 4001, + PVTGeodetic = 4007, + ReceiverStatus = 4014, + QualityInd = 4082, + RFStatus = 4092, + GALAuthStatus = 4245, + VelCovGeodetic = 5908, + EndOfPVT = 5921, + GEOIonoDelay = 5933, + AttEuler = 5938, + AttCovEuler = 5939, +}; + +#pragma pack(push, 1) + +/** + * Common SBF message header. + */ +struct Header { + uint8_t sync1; + uint8_t sync2; + uint16_t crc; + BlockID id_number: 13; + uint16_t id_revision: 3; + uint16_t length; + uint32_t tow; + uint16_t wnc; +}; + +struct DOP { + uint8_t nr_sv; + uint8_t reserved; + uint16_t p_dop; + uint16_t t_dop; + uint16_t h_dop; + uint16_t v_dop; + float hpl; + float vpl; +}; + +struct PVTGeodetic { + static constexpr uint8_t k_dnu_nr_sv {255}; + enum class ModeType : uint8_t { + NoPVT = 0, + StandAlonePVT = 1, + DifferentialPVT = 2, + FixedLocation = 3, + RTKFixed = 4, + RTKFloat = 5, + PVTWithSBAS = 6, + MovingBaseRTKFixed = 7, + MovingBaseRTKFloat = 8, + PrecisePointPositioning = 10, + }; + enum class Error : uint8_t { + None = 0, + InsufficientMeasurements = 1, + InsufficientEphemerides = 2, + DOPTooLarge = 3, + SquaredResidualSumTooLarge = 4, + NoConvergence = 5, + InsufficientMeasurementsAfterOutlierRejection = 6, + ExportLawsForbidPositionOutput = 7, + InsufficientDifferentialCorrections = 8, + MissingBaseStationCoordinates = 9, + MissingRequiredRTKFixedPosition = 10, + }; + ModeType mode_type: 4; + uint8_t mode_reserved: 2; + uint8_t mode_base_fixed: 1; + uint8_t mode_2d: 1; + Error error; + double latitude; + double longitude; + double height; + float undulation; + float vn; + float ve; + float vu; + float cog; + double rx_clk_bias; + float rx_clk_drift; + uint8_t time_system; + uint8_t datum; + uint8_t nr_sv; + uint8_t wa_corr_info; + uint16_t reference_id; + uint16_t mean_corr_age; + uint32_t signal_info; + uint8_t alert_flag; + uint8_t nr_bases; + uint16_t ppp_info; + uint16_t latency; + uint16_t h_accuracy; + uint16_t v_accuracy; +}; + +struct ReceiverStatus { + uint8_t cpu_load; + uint8_t ext_error_siserror: 1; + uint8_t ext_error_diff_corr_error: 1; + uint8_t ext_error_ext_sensor_error: 1; + uint8_t ext_error_setup_error: 1; + uint8_t ext_error_reserved: 4; + uint32_t uptime; + uint32_t rx_state_reserved1: 1; + uint32_t rx_state_active_antenna: 1; + uint32_t rx_state_ext_freq: 1; + uint32_t rx_state_ext_time: 1; + uint32_t rx_state_wn_set: 1; + uint32_t rx_state_tow_set: 1; + uint32_t rx_state_fine_time: 1; + uint32_t rx_state_internal_disk_activity: 1; + uint32_t rx_state_internal_disk_full: 1; + uint32_t rx_state_internal_disk_mounted: 1; + uint32_t rx_state_int_ant: 1; + uint32_t rx_state_refout_locked: 1; + uint32_t rx_state_reserved2: 1; + uint32_t rx_state_external_disk_activity: 1; + uint32_t rx_state_external_disk_full: 1; + uint32_t rx_state_external_disk_mounted: 1; + uint32_t rx_state_pps_in_cal: 1; + uint32_t rx_state_diff_corr_in: 1; + uint32_t rx_state_internet: 1; + uint32_t rx_state_reserved3: 13; + uint32_t rx_error_reserved1: 3; + uint32_t rx_error_software: 1; + uint32_t rx_error_watchdog: 1; + uint32_t rx_error_antenna: 1; + uint32_t rx_error_congestion: 1; + uint32_t rx_error_reserved2: 1; + uint32_t rx_error_missed_event: 1; + uint32_t rx_error_cpu_overload: 1; + uint32_t rx_error_invalid_config: 1; + uint32_t rx_error_out_of_geofence: 1; + uint32_t rx_error_reserved3: 22; + uint8_t n; + uint8_t sb_length; + uint8_t cmd_count; + uint8_t temperature; +}; + +struct QualityIndicator { + enum class Type : uint8_t { + Overall = 0, + GNSSSignalsMainAntenna = 1, + GNSSSignalsAuxAntenna = 2, + RFPowerMainAntenna = 11, + RFPowerAuxAntenna = 12, + CPUHeadroom = 21, + OCXOStability = 25, + BaseStationMeasurements = 30, + RTKPostProcessing = 31, + }; + Type type: 8; + uint16_t value: 4; + uint16_t reserved: 4; +}; + +struct QualityInd { + uint8_t n; + uint8_t reserved1; + // Only support the currently available indicators for now so we don't have to allocate. + QualityIndicator indicators[k_max_quality_indicators]; +}; + +struct RFBand { + uint32_t frequency; + uint16_t bandwidth; + uint8_t info_mode: 4; + uint8_t info_reserved: 2; + uint8_t info_antenna_id: 2; +}; + +struct RFStatus { + uint8_t n; + uint8_t sb_length; + uint8_t flags_inauthentic_gnss_signals: 1; + uint8_t flags_inauthentic_navigation_message: 1; + uint8_t flags_reserved: 6; + uint8_t reserved[3]; + RFBand rf_band[k_max_rfband_blocks]; +}; + +struct GALAuthStatus { + uint16_t osnma_status_status: 3; + uint16_t osnma_status_initialization_progress: 8; + uint16_t osnma_status_trusted_time_source: 3; + uint16_t osnma_status_merkle_tree_busy: 1; + uint16_t osnma_status_reserved: 1; + float trusted_time_delta; + uint64_t gal_active_mask; + uint64_t gal_authentic_mask; + uint64_t gps_active_mask; + uint64_t gps_authentic_mask; +}; + +struct VelCovGeodetic { + uint8_t mode_type: 4; + uint8_t mode_reserved: 2; + uint8_t mode_base_fixed: 1; + uint8_t mode_2d: 1; + uint8_t error; + float cov_vn_vn; + float cov_ve_ve; + float cov_vu_vu; + float cov_dt_dt; + float cov_vn_ve; + float cov_vn_vu; + float cov_vn_dt; + float cov_ve_vu; + float cov_ve_dt; + float cov_vu_dt; +}; + +struct IDC { + uint8_t igp_mask_no; + uint8_t givei; + uint8_t reserved[2]; + float vertical_delay; +}; + +struct GEOIonoDelay { + uint8_t prn; + uint8_t bandnbr; + uint8_t iodi; + uint8_t n; + uint8_t sb_length; + uint8_t reserved; + IDC idc[4]; +}; + +struct AttEuler { + enum class Error : uint8_t { + None = 0, + InsufficientMeasurements = 1, + }; + uint8_t nr_sv; + Error error_aux1: 2; + Error error_aux2: 2; + uint8_t error_reserved: 3; + uint8_t error_not_requested: 1; + uint16_t mode; + uint16_t reserved; + float heading; + float pitch; + float roll; + float pitch_dot; + float roll_dot; + float heading_dot; +}; + +struct AttCovEuler { + enum class Error : uint8_t { + None = 0, + InsufficientMeasurements = 1, + }; + uint8_t reserved; + Error error_aux1: 2; + Error error_aux2: 2; + uint8_t error_reserved: 3; + uint8_t error_not_requested: 1; + float cov_headhead; + float cov_pitchpitch; + float cov_rollroll; + float cov_headpitch; + float cov_headroll; + float cov_pitchroll; +}; + +#pragma pack(pop) + +} // namespace sbf + +} // namespace septentrio diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp new file mode 100644 index 000000000000..ad99ed6342c8 --- /dev/null +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -0,0 +1,1702 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file septentrio.cpp + * + * Septentrio GNSS receiver driver + * + * @author Matej Franceskin + * @author Seppe Geuens + * @author Thomas Frans +*/ + +#include "septentrio.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "util.h" +#include "sbf/messages.h" + +using namespace device; + +namespace septentrio +{ + +/** + * RTC drift time when time synchronization is needed (in seconds). +*/ +constexpr int k_max_allowed_clock_drift = 5; + +/** + * If silence from the receiver for this time (ms), assume full data received. +*/ +constexpr int k_receiver_read_timeout = 2; + +/** + * The maximum allowed time for reading from the receiver. + */ +constexpr int k_max_receiver_read_timeout = 50; + +/** + * Minimum amount of bytes we try to read at one time from the receiver. +*/ +constexpr size_t k_min_receiver_read_bytes = 32; + +constexpr uint8_t k_max_command_size = 120; +constexpr uint16_t k_timeout_5hz = 500; +constexpr uint32_t k_read_buffer_size = 150; +constexpr time_t k_gps_epoch_secs = 1234567890ULL; // TODO: This seems wrong + +// Septentrio receiver commands +// - erst: exeResetReceiver +// - sso: setSBFOutput +// - ssu: setSatelliteUsage +// - scs: setCOMSettings +// - srd: setReceiverDynamics +// - sto: setAttitudeOffset +// - sdio: setDataInOut +// - gecm: getEchoMessage +// - sga: setGNSSAttitude +constexpr const char *k_command_force_input = "SSSSSSSSSS\n"; +constexpr const char *k_command_reset_hot = "erst,soft,none\n"; +constexpr const char *k_command_reset_warm = "erst,soft,PVTData\n"; +constexpr const char *k_command_reset_cold = "erst,hard,SatData\n"; +constexpr const char *k_command_sbf_output_pvt = + "sso,Stream%lu,%s,PVTGeodetic+VelCovGeodetic+DOP+AttEuler+AttCovEuler+EndOfPVT+ReceiverStatus,%s\n"; +constexpr const char *k_command_set_sbf_output = + "sso,Stream%lu,%s,%s%s,%s\n"; +constexpr const char *k_command_clear_sbf = "sso,Stream%lu,%s,none,off\n"; +constexpr const char *k_command_set_baud_rate = + "scs,%s,baud%lu\n"; // The receiver sends the reply at the new baud rate! +constexpr const char *k_command_set_dynamics = "srd,%s,UAV\n"; +constexpr const char *k_command_set_attitude_offset = "sto,%.3f,%.3f\n"; +constexpr const char *k_command_set_data_io = "sdio,%s,Auto,%s\n"; +constexpr const char *k_command_set_satellite_usage = "ssu,%s\n"; +constexpr const char *k_command_ping = "gecm\n"; +constexpr const char *k_command_set_gnss_attitude = "sga,%s\n"; + +constexpr const char *k_gnss_attitude_source_moving_base = "MovingBase"; +constexpr const char *k_gnss_attitude_source_multi_antenna = "MultiAntenna"; + +constexpr const char *k_frequency_0_1hz = "sec10"; +constexpr const char *k_frequency_0_2hz = "sec5"; +constexpr const char *k_frequency_0_5hz = "sec2"; +constexpr const char *k_frequency_1_0hz = "sec1"; +constexpr const char *k_frequency_2_0hz = "msec500"; +constexpr const char *k_frequency_5_0hz = "msec200"; +constexpr const char *k_frequency_10_0hz = "msec100"; +constexpr const char *k_frequency_20_0hz = "msec50"; +constexpr const char *k_frequency_25_0hz = "msec40"; +constexpr const char *k_frequency_50_0hz = "msec20"; + +px4::atomic SeptentrioDriver::_secondary_instance {nullptr}; + +SeptentrioDriver::SeptentrioDriver(const char *device_path, Instance instance, uint32_t baud_rate) : + Device(MODULE_NAME), + _instance(instance), + _baud_rate(baud_rate) +{ + strncpy(_port, device_path, sizeof(_port) - 1); + // Enforce null termination. + _port[sizeof(_port) - 1] = '\0'; + + reset_gps_state_message(); + + int32_t enable_sat_info {0}; + get_parameter("SEP_SAT_INFO", &enable_sat_info); + + if (enable_sat_info) { + _message_satellite_info = new satellite_info_s(); + } + + get_parameter("SEP_YAW_OFFS", &_heading_offset); + get_parameter("SEP_PITCH_OFFS", &_pitch_offset); + + int32_t dump_mode {0}; + get_parameter("SEP_DUMP_COMM", &dump_mode); + DumpMode mode = static_cast(dump_mode); + + if (mode != DumpMode::Disabled) { + initialize_communication_dump(mode); + } + + int32_t receiver_stream_main {k_default_main_stream}; + get_parameter("SEP_STREAM_MAIN", &receiver_stream_main); + _receiver_stream_main = receiver_stream_main; + int32_t receiver_stream_log {k_default_log_stream}; + get_parameter("SEP_STREAM_LOG", &receiver_stream_log); + _receiver_stream_log = receiver_stream_log; + + int32_t automatic_configuration {true}; + get_parameter("SEP_AUTO_CONFIG", &automatic_configuration); + _automatic_configuration = static_cast(automatic_configuration); + + get_parameter("SEP_CONST_USAGE", &_receiver_constellation_usage); + + int32_t logging_frequency {static_cast(ReceiverLogFrequency::Hz1_0)}; + get_parameter("SEP_LOG_HZ", &logging_frequency); + _receiver_logging_frequency = static_cast(logging_frequency); + int32_t logging_level {static_cast(ReceiverLogLevel::Default)}; + get_parameter("SEP_LOG_LEVEL", &logging_level); + _receiver_logging_level = static_cast(logging_level); + int32_t logging_overwrite {false}; + get_parameter("SEP_LOG_FORCE", &logging_overwrite); + _receiver_logging_overwrite = logging_overwrite; + int32_t receiver_setup {static_cast(ReceiverSetup::Default)}; + get_parameter("SEP_HARDW_SETUP", &receiver_setup); + _receiver_setup = static_cast(receiver_setup); + int32_t sbf_output_frequency {static_cast(SBFOutputFrequency::Hz5_0)}; + get_parameter("SEP_OUTP_HZ", &sbf_output_frequency); + _sbf_output_frequency = static_cast(sbf_output_frequency); + + if (_instance == Instance::Secondary && _receiver_setup == ReceiverSetup::MovingBase) { + _rtcm_decoder = new rtcm::Decoder(); + } + + set_device_type(DRV_GPS_DEVTYPE_SBF); +} + +SeptentrioDriver::~SeptentrioDriver() +{ + if (_instance == Instance::Main) { + if (await_second_instance_shutdown() == PX4_ERROR) { + SEP_ERR("Secondary instance shutdown timed out"); + } + } + + if (_message_data_from_receiver) { + delete _message_data_from_receiver; + } + + if (_message_data_to_receiver) { + delete _message_data_to_receiver; + } + + if (_message_satellite_info) { + delete _message_satellite_info; + } + + if (_rtcm_decoder) { + delete _rtcm_decoder; + } +} + +int SeptentrioDriver::print_status() +{ + SeptentrioDriver *secondary_instance = _secondary_instance.load(); + + switch (_instance) { + case Instance::Main: + PX4_INFO("Main GPS"); + break; + + case Instance::Secondary: + PX4_INFO(""); + PX4_INFO("Secondary GPS"); + break; + } + + PX4_INFO("health: %s, port: %s, baud rate: %lu", is_healthy() ? "OK" : "NOT OK", _port, _baud_rate); + PX4_INFO("controller -> receiver data rate: %lu B/s", output_data_rate()); + PX4_INFO("receiver -> controller data rate: %lu B/s", input_data_rate()); + PX4_INFO("sat info: %s", (_message_satellite_info != nullptr) ? "enabled" : "disabled"); + + if (_message_gps_state.timestamp != 0) { + + PX4_INFO("rate RTCM injection: %6.2f Hz", static_cast(rtcm_injection_frequency())); + + print_message(ORB_ID(sensor_gps), _message_gps_state); + } + + if (_instance == Instance::Main && secondary_instance) { + secondary_instance->print_status(); + } + + return 0; +} + +void SeptentrioDriver::run() +{ + while (!should_exit()) { + switch (_state) { + case State::OpeningSerialPort: { + _uart.setPort(_port); + + if (_uart.open()) { + _state = State::ConfiguringDevice; + + } else { + // Failed to open port, so wait a bit before trying again. + px4_usleep(200000); + } + + break; + } + + case State::ConfiguringDevice: { + if (configure() == PX4_OK) { + SEP_INFO("Automatic configuration successful"); + _state = State::ReceivingData; + + } else { + // Failed to configure device, so wait a bit before trying again. + px4_usleep(200000); + } + + break; + } + + case State::ReceivingData: { + int receive_result {0}; + + receive_result = receive(k_timeout_5hz); + + if (receive_result == -1) { + _state = State::ConfiguringDevice; + } + + if (_message_satellite_info && (receive_result & 2)) { + publish_satellite_info(); + } + + break; + } + + } + + reset_if_scheduled(); + + handle_inject_data_topic(); + + if (update_monitoring_interval_ended()) { + start_update_monitoring_interval(); + } + } + +} + +int SeptentrioDriver::task_spawn(int argc, char *argv[]) +{ + return task_spawn(argc, argv, Instance::Main); +} + +int SeptentrioDriver::task_spawn(int argc, char *argv[], Instance instance) +{ + px4_main_t entry_point; + static constexpr int k_task_stack_size = PX4_STACK_ADJUSTED(2048); + + if (instance == Instance::Main) { + entry_point = &run_trampoline; + + } else { + entry_point = &run_trampoline_secondary; + } + + px4_task_t task_id = px4_task_spawn_cmd("septentrio", + SCHED_DEFAULT, + SCHED_PRIORITY_SLOW_DRIVER, + k_task_stack_size, + entry_point, + (char *const *)argv); + + if (task_id < 0) { + // `_task_id` of module that hasn't been started before or has been stopped should already be -1. + // This is just to make sure. + _task_id = -1; + return -errno; + } + + if (instance == Instance::Main) { + _task_id = task_id; + } + + return 0; +} + +int SeptentrioDriver::run_trampoline_secondary(int argc, char *argv[]) +{ + // Get rid of the task name (first argument) + argc -= 1; + argv += 1; + + SeptentrioDriver *gps = instantiate(argc, argv, Instance::Secondary); + + if (gps) { + _secondary_instance.store(gps); + gps->run(); + _secondary_instance.store(nullptr); + delete gps; + + } else { + return -1; + } + + return 0; +} + +SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[]) +{ + return instantiate(argc, argv, Instance::Main); +} + +SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[], Instance instance) +{ + ModuleArguments arguments{}; + SeptentrioDriver *gps{nullptr}; + + if (parse_cli_arguments(argc, argv, arguments) == PX4_ERROR) { + return nullptr; + } + + if (instance == Instance::Main) { + if (Serial::validatePort(arguments.device_path_main)) { + gps = new SeptentrioDriver(arguments.device_path_main, instance, arguments.baud_rate_main); + + } else { + PX4_ERR("invalid device (-d) %s", arguments.device_path_main ? arguments.device_path_main : ""); + } + + if (gps && arguments.device_path_secondary) { + task_spawn(argc, argv, Instance::Secondary); + + if (await_second_instance_startup() == PX4_ERROR) { + return nullptr; + } + } + + } else { + if (Serial::validatePort(arguments.device_path_secondary)) { + gps = new SeptentrioDriver(arguments.device_path_secondary, instance, arguments.baud_rate_secondary); + + } else { + PX4_ERR("Invalid secondary device (-e) %s", arguments.device_path_secondary ? arguments.device_path_secondary : ""); + } + } + + return gps; +} + +// Called from outside driver thread. +// Return 0 on success, -1 otherwise. +int SeptentrioDriver::custom_command(int argc, char *argv[]) +{ + bool handled = false; + SeptentrioDriver *driver_instance; + + if (!is_running()) { + PX4_INFO("not running"); + return -1; + } + + driver_instance = get_instance(); + + if (argc >= 1 && strcmp(argv[0], "reset") == 0) { + if (argc == 2) { + ReceiverResetType type{ReceiverResetType::None}; + + if (strcmp(argv[1], "hot") == 0) { + type = ReceiverResetType::Hot; + + } else if (strcmp(argv[1], "warm") == 0) { + type = ReceiverResetType::Warm; + + } else if (strcmp(argv[1], "cold") == 0) { + type = ReceiverResetType::Cold; + + } else { + print_usage("incorrect reset type"); + } + + if (type != ReceiverResetType::None) { + driver_instance->schedule_reset(type); + handled = true; + } + + } else { + print_usage("incorrect usage of reset command"); + } + } + + return (handled) ? 0 : print_usage("unknown command"); +} + +int SeptentrioDriver::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +GPS driver module that handles the communication with Septentrio devices and publishes the position via uORB. + +The module supports a secondary GPS device, specified via `-e` parameter. The position will be published on +the second uORB topic instance. It can be used for logging and heading computation. + +### Examples + +Starting 2 GPS devices (main one on /dev/ttyS3, secondary on /dev/ttyS4) +$ septentrio start -d /dev/ttyS3 -e /dev/ttyS4 + +Initiate warm restart of GPS device +$ gps reset warm +)DESCR_STR"); + PRINT_MODULE_USAGE_NAME("septentrio", "driver"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "Primary Septentrio receiver", false); + PRINT_MODULE_USAGE_PARAM_INT('b', 0, 57600, 1500000, "Primary baud rate", true); + PRINT_MODULE_USAGE_PARAM_STRING('e', nullptr, "", "Secondary Septentrio receiver", true); + PRINT_MODULE_USAGE_PARAM_INT('g', 0, 57600, 1500000, "Secondary baud rate", true); + + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reset connected receiver"); + PRINT_MODULE_USAGE_ARG("cold|warm|hot", "Specify reset type", false); + + return 0; +} + +int SeptentrioDriver::reset(ReceiverResetType type) +{ + bool res = false; + + force_input(); + + switch (type) { + case ReceiverResetType::Hot: + res = send_message_and_wait_for_ack(k_command_reset_hot, k_receiver_ack_timeout); + break; + + case ReceiverResetType::Warm: + res = send_message_and_wait_for_ack(k_command_reset_warm, k_receiver_ack_timeout); + break; + + case ReceiverResetType::Cold: + res = send_message_and_wait_for_ack(k_command_reset_cold, k_receiver_ack_timeout); + break; + + default: + break; + } + + if (res) { + return PX4_OK; + } else { + return PX4_ERROR; + } +} + +int SeptentrioDriver::force_input() +{ + ssize_t written = write(reinterpret_cast(k_command_force_input), strlen(k_command_force_input)); + + if (written < 0) { + return PX4_ERROR; + } else { + // The receiver can't receive input right after forcing input. From testing, the duration seems to be 1 ms, so wait 10 ms to be sure. + px4_usleep(10000); + return PX4_OK; + } +} + +int SeptentrioDriver::parse_cli_arguments(int argc, char *argv[], ModuleArguments& arguments) +{ + int ch{'\0'}; + int myoptind{1}; + const char *myoptarg{nullptr}; + + while ((ch = px4_getopt(argc, argv, "d:e:b:g:", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'b': + if (px4_get_parameter_value(myoptarg, arguments.baud_rate_main) != 0) { + PX4_ERR("baud rate parsing failed"); + return PX4_ERROR; + } + break; + case 'g': + if (px4_get_parameter_value(myoptarg, arguments.baud_rate_secondary) != 0) { + PX4_ERR("baud rate parsing failed"); + return PX4_ERROR; + } + break; + case 'd': + arguments.device_path_main = myoptarg; + break; + + case 'e': + arguments.device_path_secondary = myoptarg; + break; + + case '?': + return PX4_ERROR; + + default: + PX4_WARN("unrecognized flag"); + return PX4_ERROR; + break; + } + } + + return PX4_OK; +} + +int SeptentrioDriver::await_second_instance_startup() +{ + uint32_t i = 0; + + do { + px4_usleep(2500); + } while (!_secondary_instance.load() && ++i < 400); + + if (!_secondary_instance.load()) { + SEP_ERR("Timed out while waiting for second instance to start"); + return PX4_ERROR; + } + + return PX4_OK; +} + +int SeptentrioDriver::await_second_instance_shutdown() +{ + if (_instance == Instance::Secondary) { + return PX4_OK; + } + + SeptentrioDriver* secondary_instance = _secondary_instance.load(); + + if (secondary_instance) { + secondary_instance->request_stop(); + + uint32_t i {0}; + + // Give the secondary instance 2 seconds at most to properly shut down. + while (_secondary_instance.load() && i < 100) { + px4_usleep(20000); + + ++i; + } + + return _secondary_instance.load() ? PX4_ERROR : PX4_OK; + } else { + return PX4_OK; + } +} + +void SeptentrioDriver::schedule_reset(ReceiverResetType reset_type) +{ + SeptentrioDriver *secondary_instance = _secondary_instance.load(); + + _scheduled_reset.store((int)reset_type); + + if (_instance == Instance::Main && secondary_instance) { + secondary_instance->schedule_reset(reset_type); + } +} + +uint32_t SeptentrioDriver::detect_receiver_baud_rate(bool forced_input) { + // So we can restore the port to its original state. + const uint32_t original_baud_rate = _uart.getBaudrate(); + + // Baud rates we expect the receiver to be running at. + uint32_t expected_baud_rates[] = {115200, 115200, 230400, 57600, 460800, 500000, 576000, 38400, 921600, 1000000, 1500000}; + if (_baud_rate != 0) { + expected_baud_rates[0] = _baud_rate; + } + + for (uint i = 0; i < sizeof(expected_baud_rates)/sizeof(expected_baud_rates[0]); i++) { + if (set_baudrate(expected_baud_rates[i]) != PX4_OK) { + set_baudrate(original_baud_rate); + return 0; + } + + if (forced_input) { + force_input(); + } + + if (send_message_and_wait_for_ack(k_command_ping, k_receiver_ack_timeout)) { + SEP_INFO("Detected baud rate: %lu", expected_baud_rates[i]); + set_baudrate(original_baud_rate); + return expected_baud_rates[i]; + } + } + + set_baudrate(original_baud_rate); + return 0; +} + +int SeptentrioDriver::detect_serial_port(char* const port_name) { + // Read buffer to get the COM port + char buf[k_read_buffer_size]; + size_t buffer_offset = 0; // The offset into the string where the next data should be read to. + hrt_abstime timeout_time = hrt_absolute_time() + 5 * 1000 * k_receiver_ack_timeout; + bool response_detected = false; + + // Receiver prints prompt after a message. + if (!send_message(k_command_ping)) { + return PX4_ERROR; + } + + do { + // Read at most the amount of available bytes in the buffer after the current offset, -1 because we need '\0' at the end for a valid string. + int read_result = read(reinterpret_cast(buf) + buffer_offset, sizeof(buf) - buffer_offset - 1, k_receiver_ack_timeout); + + if (read_result < 0) { + SEP_WARN("SBF read error"); + return PX4_ERROR; + } + + // Sanitize the data so it doesn't contain any `0` values. + for (size_t i = buffer_offset; i < buffer_offset + read_result; i++) { + if (buf[i] == 0) { + buf[i] = 1; + } + } + + buffer_offset += read_result; + + // Make sure the current buffer is a valid string. + buf[buffer_offset] = '\0'; + + char* port_name_address = strstr(buf, ">"); + + // Check if we found a port candidate. + if (buffer_offset > 4 && port_name_address != nullptr) { + size_t port_name_offset = reinterpret_cast(port_name_address) - reinterpret_cast(buf) - 4; + for (size_t i = 0; i < 4; i++) { + port_name[i] = buf[port_name_offset + i]; + } + // NOTE: This limits the ports to serial and USB ports only. Otherwise the detection doesn't work correctly. + if (strstr(port_name, "COM") != nullptr || strstr(port_name, "USB") != nullptr) { + response_detected = true; + break; + } + } + + if (buffer_offset + 1 >= sizeof(buf)) { + // Copy the last 3 bytes such that a half port isn't lost. + for (int i = 0; i < 4; i++) { + buf[i] = buf[sizeof(buf) - 4 + i]; + } + buffer_offset = 3; + } + } while (timeout_time > hrt_absolute_time()); + + if (!response_detected) { + SEP_WARN("No valid serial port detected"); + return PX4_ERROR; + } else { + SEP_INFO("Serial port found: %s", port_name); + return PX4_OK; + } +} + +int SeptentrioDriver::configure() +{ + char msg[k_max_command_size] {}; + + // Passively detect receiver baud rate. + uint32_t detected_receiver_baud_rate = detect_receiver_baud_rate(true); + + if (detected_receiver_baud_rate == 0) { + SEP_INFO("CONFIG: failed baud detection"); + return PX4_ERROR; + } + + // Set same baud rate on our end. + if (set_baudrate(detected_receiver_baud_rate) != PX4_OK) { + SEP_INFO("CONFIG: failed local baud rate setting"); + return PX4_ERROR; + } + + char com_port[5] {}; + + // Passively detect receiver port. + if (detect_serial_port(com_port) != PX4_OK) { + SEP_INFO("CONFIG: failed port detection"); + return PX4_ERROR; + } + + // We should definitely match baud rates and detect used port, but don't do other configuration if not requested. + // This will force input on the receiver. That shouldn't be a problem as it's on our own connection. + if (!_automatic_configuration) { + return PX4_OK; + } + + // If user requested specific baud rate, set it now. Otherwise keep detected baud rate. + if (strstr(com_port, "COM") != nullptr && _baud_rate != 0) { + snprintf(msg, sizeof(msg), k_command_set_baud_rate, com_port, _baud_rate); + + if (!send_message(msg)) { + SEP_INFO("CONFIG: baud rate command write error"); + return PX4_ERROR; + } + + // When sending a command and setting the baud rate right after, the controller could send the command at the new baud rate. + // From testing this could take some time. + px4_usleep(1000000); + + if (set_baudrate(_baud_rate) != PX4_OK) { + SEP_INFO("CONFIG: failed local baud rate setting"); + return PX4_ERROR; + } + + if (!send_message_and_wait_for_ack(k_command_ping, k_receiver_ack_timeout)) { + SEP_INFO("CONFIG: failed remote baud rate setting"); + return PX4_ERROR; + } + } else { + _baud_rate = detected_receiver_baud_rate; + } + + // Delete all sbf outputs on current COM port to remove clutter data + snprintf(msg, sizeof(msg), k_command_clear_sbf, _receiver_stream_main, com_port); + + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + SEP_INFO("CONFIG: failed delete output"); + return PX4_ERROR; // connection and/or baudrate detection failed + } + + // Define/inquire the type of data that the receiver should accept/send on a given connection descriptor + snprintf(msg, sizeof(msg), k_command_set_data_io, com_port, "SBF"); + + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + return PX4_ERROR; + } + + // Specify the offsets that the receiver applies to the computed attitude angles. + snprintf(msg, sizeof(msg), k_command_set_attitude_offset, (double)(_heading_offset * 180 / M_PI_F), (double)_pitch_offset); + + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + return PX4_ERROR; + } + + snprintf(msg, sizeof(msg), k_command_set_dynamics, "high"); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + return PX4_ERROR; + } + + const char *sbf_frequency {k_frequency_10_0hz}; + switch (_sbf_output_frequency) { + case SBFOutputFrequency::Hz5_0: + sbf_frequency = k_frequency_5_0hz; + break; + case SBFOutputFrequency::Hz10_0: + sbf_frequency = k_frequency_10_0hz; + break; + case SBFOutputFrequency::Hz20_0: + sbf_frequency = k_frequency_20_0hz; + break; + case SBFOutputFrequency::Hz25_0: + sbf_frequency = k_frequency_25_0hz; + break; + } + + // Output a set of SBF blocks on a given connection at a regular interval. + snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, _receiver_stream_main, com_port, sbf_frequency); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + SEP_INFO("Failed to configure SBF"); + return PX4_ERROR; + } + + if (_receiver_setup == ReceiverSetup::MovingBase) { + if (_instance == Instance::Secondary) { + snprintf(msg, sizeof(msg), k_command_set_data_io, com_port, "+RTCMv3"); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + SEP_INFO("Failed to configure RTCM output"); + } + } else { + snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_moving_base); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + SEP_INFO("Failed to configure attitude source"); + } + } + } else { + snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_multi_antenna); + // This fails on single-antenna receivers, which is fine. Therefore don't check for acknowledgement. + if (!send_message(msg)) { + SEP_INFO("Failed to configure attitude source"); + return PX4_ERROR; + } + } + + // Internal logging on the receiver. + if (_receiver_logging_frequency != ReceiverLogFrequency::Disabled && _receiver_stream_log != _receiver_stream_main) { + const char *frequency {nullptr}; + const char *level {nullptr}; + + switch (_receiver_logging_frequency) { + case ReceiverLogFrequency::Hz0_1: + frequency = k_frequency_0_1hz; + break; + case ReceiverLogFrequency::Hz0_2: + frequency = k_frequency_0_2hz; + break; + case ReceiverLogFrequency::Hz0_5: + frequency = k_frequency_0_5hz; + break; + case ReceiverLogFrequency::Hz1_0: + default: + frequency = k_frequency_1_0hz; + break; + case ReceiverLogFrequency::Hz2_0: + frequency = k_frequency_2_0hz; + break; + case ReceiverLogFrequency::Hz5_0: + frequency = k_frequency_5_0hz; + break; + case ReceiverLogFrequency::Hz10_0: + frequency = k_frequency_10_0hz; + break; + case ReceiverLogFrequency::Hz20_0: + frequency = k_frequency_20_0hz; + break; + case ReceiverLogFrequency::Hz25_0: + frequency = k_frequency_25_0hz; + break; + case ReceiverLogFrequency::Hz50_0: + frequency = k_frequency_50_0hz; + break; + } + + switch (_receiver_logging_level) { + case ReceiverLogLevel::Lite: + level = "Comment+ReceiverStatus"; + break; + case ReceiverLogLevel::Basic: + level = "Comment+ReceiverStatus+PostProcess+Event"; + break; + case ReceiverLogLevel::Default: + default: + level = "Comment+ReceiverStatus+PostProcess+Event+Support"; + break; + case ReceiverLogLevel::Full: + level = "Comment+ReceiverStatus+PostProcess+Event+Support+BBSamples"; + break; + } + + snprintf(msg, sizeof(msg), k_command_set_sbf_output, _receiver_stream_log, "DSK1", _receiver_logging_overwrite ? "" : "+", level, frequency); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + SEP_ERR("Failed to configure logging"); + return PX4_ERROR; + } + } else if (_receiver_stream_log == _receiver_stream_main) { + SEP_WARN("Skipping logging setup: logging stream can't equal main stream"); + } + + // Set up the satellites used in PVT computation. + if (_receiver_constellation_usage != static_cast(SatelliteUsage::Default)) { + char requested_satellites[40] {}; + if (_receiver_constellation_usage & static_cast(SatelliteUsage::GPS)) { + strcat(requested_satellites, "GPS+"); + } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::GLONASS)) { + strcat(requested_satellites, "GLONASS+"); + } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::Galileo)) { + strcat(requested_satellites, "GALILEO+"); + } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::SBAS)) { + strcat(requested_satellites, "SBAS+"); + } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::BeiDou)) { + strcat(requested_satellites, "BEIDOU+"); + } + // Make sure to remove the trailing '+' if any. + requested_satellites[math::max(static_cast(strlen(requested_satellites)) - 1, 0)] = '\0'; + snprintf(msg, sizeof(msg), k_command_set_satellite_usage, requested_satellites); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { + SEP_ERR("Failed to configure constellation usage"); + return PX4_ERROR; + } + } + + return PX4_OK; +} + +int SeptentrioDriver::parse_char(const uint8_t byte) +{ + int result = 0; + + switch (_active_decoder) { + case DecodingStatus::Searching: + if (_sbf_decoder.add_byte(byte) != sbf::Decoder::State::SearchingSync1) { + _active_decoder = DecodingStatus::SBF; + } else if (_rtcm_decoder && _rtcm_decoder->add_byte(byte) != rtcm::Decoder::State::SearchingPreamble) { + _active_decoder = DecodingStatus::RTCMv3; + } + break; + case DecodingStatus::SBF: + if (_sbf_decoder.add_byte(byte) == sbf::Decoder::State::Done) { + if (process_message() == PX4_OK) { + result = 1; + } + _sbf_decoder.reset(); + _active_decoder = DecodingStatus::Searching; + } + break; + case DecodingStatus::RTCMv3: + if (_rtcm_decoder->add_byte(byte) == rtcm::Decoder::State::Done) { + if (process_message() == PX4_OK) { + result = 1; + } + _rtcm_decoder->reset(); + _active_decoder = DecodingStatus::Searching; + } + break; + } + + return result; +} + +int SeptentrioDriver::process_message() +{ + int result = PX4_ERROR; + + switch (_active_decoder) { + case DecodingStatus::Searching: { + SEP_ERR("Can't process incomplete message!"); + result = PX4_ERROR; + break; + } + case DecodingStatus::SBF: { + using namespace sbf; + + switch (_sbf_decoder.id()) { + case BlockID::Invalid: { + SEP_TRACE_PARSING("Tried to process invalid SBF message"); + break; + } + case BlockID::DOP: { + SEP_TRACE_PARSING("Processing DOP SBF message"); + _current_interval_messages.dop = true; + + DOP dop; + + if (_sbf_decoder.parse(&dop) == PX4_OK) { + _message_gps_state.hdop = dop.h_dop * 0.01f; + _message_gps_state.vdop = dop.v_dop * 0.01f; + result = PX4_OK; + } + + break; + } + case BlockID::PVTGeodetic: { + using ModeType = PVTGeodetic::ModeType; + using Error = PVTGeodetic::Error; + + SEP_TRACE_PARSING("Processing PVTGeodetic SBF message"); + _current_interval_messages.pvt_geodetic = true; + + Header header; + PVTGeodetic pvt_geodetic; + + if (_sbf_decoder.parse(&header) == PX4_OK && _sbf_decoder.parse(&pvt_geodetic) == PX4_OK) { + if (pvt_geodetic.mode_type < ModeType::StandAlonePVT) { + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; + + } else if (pvt_geodetic.mode_type == ModeType::PVTWithSBAS) { + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTCM_CODE_DIFFERENTIAL; + + } else if (pvt_geodetic.mode_type == ModeType::RTKFloat || pvt_geodetic.mode_type == ModeType::MovingBaseRTKFloat) { + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FLOAT; + + } else if (pvt_geodetic.mode_type == ModeType::RTKFixed || pvt_geodetic.mode_type == ModeType::MovingBaseRTKFixed) { + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FIXED; + + } else { + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_3D; + } + + // Check fix and error code + _message_gps_state.vel_ned_valid = _message_gps_state.fix_type > sensor_gps_s::FIX_TYPE_NONE && pvt_geodetic.error == Error::None; + + // Check boundaries and invalidate GPS velocities + if (pvt_geodetic.vn <= k_dnu_f4_value || pvt_geodetic.ve <= k_dnu_f4_value || pvt_geodetic.vu <= k_dnu_f4_value) { + _message_gps_state.vel_ned_valid = false; + } + + // Check boundaries and invalidate position + // We're not just checking for the do-not-use value but for any value beyond the specified max values + if (pvt_geodetic.latitude <= k_dnu_f8_value || + pvt_geodetic.longitude <= k_dnu_f8_value || + pvt_geodetic.height <= k_dnu_f8_value || + pvt_geodetic.undulation <= k_dnu_f4_value) { + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; + } + + if (pvt_geodetic.nr_sv != PVTGeodetic::k_dnu_nr_sv) { + _message_gps_state.satellites_used = pvt_geodetic.nr_sv; + + if (_message_satellite_info) { + // Only fill in the satellite count for now (we could use the ChannelStatus message for the + // other data, but it's really large: >800B) + _message_satellite_info->timestamp = hrt_absolute_time(); + _message_satellite_info->count = _message_gps_state.satellites_used; + } + + } else { + _message_gps_state.satellites_used = 0; + } + + _message_gps_state.latitude_deg = pvt_geodetic.latitude * M_RAD_TO_DEG; + _message_gps_state.longitude_deg = pvt_geodetic.longitude * M_RAD_TO_DEG; + _message_gps_state.altitude_msl_m = pvt_geodetic.height - static_cast(pvt_geodetic.undulation); + _message_gps_state.altitude_ellipsoid_m = pvt_geodetic.height; + + /* H and V accuracy are reported in 2DRMS, but based off the u-blox reporting we expect RMS. + * Divide by 100 from cm to m and in addition divide by 2 to get RMS. */ + _message_gps_state.eph = static_cast(pvt_geodetic.h_accuracy) / 200.0f; + _message_gps_state.epv = static_cast(pvt_geodetic.v_accuracy) / 200.0f; + + _message_gps_state.vel_n_m_s = pvt_geodetic.vn; + _message_gps_state.vel_e_m_s = pvt_geodetic.ve; + _message_gps_state.vel_d_m_s = -1.0f * pvt_geodetic.vu; + _message_gps_state.vel_m_s = sqrtf(_message_gps_state.vel_n_m_s * _message_gps_state.vel_n_m_s + + _message_gps_state.vel_e_m_s * _message_gps_state.vel_e_m_s); + + _message_gps_state.cog_rad = pvt_geodetic.cog * M_DEG_TO_RAD_F; + _message_gps_state.c_variance_rad = M_DEG_TO_RAD_F; + + _message_gps_state.time_utc_usec = 0; +#ifndef __PX4_QURT // NOTE: Functionality isn't available on Snapdragon yet. + struct tm timeinfo; + time_t epoch; + + // Convert to unix timestamp + memset(&timeinfo, 0, sizeof(timeinfo)); + + timeinfo.tm_year = 1980 - 1900; + timeinfo.tm_mon = 0; + timeinfo.tm_mday = 6 + header.wnc * 7; + timeinfo.tm_hour = 0; + timeinfo.tm_min = 0; + timeinfo.tm_sec = header.tow / 1000; + + epoch = mktime(&timeinfo); + + if (epoch > k_gps_epoch_secs) { + // FMUv2+ boards have a hardware RTC, but GPS helps us to configure it + // and control its drift. Since we rely on the HRT for our monotonic + // clock, updating it from time to time is safe. + + timespec ts; + memset(&ts, 0, sizeof(ts)); + ts.tv_sec = epoch; + ts.tv_nsec = (header.tow % 1000) * 1000 * 1000; + set_clock(ts); + + _message_gps_state.time_utc_usec = static_cast(epoch) * 1000000ULL; + _message_gps_state.time_utc_usec += (header.tow % 1000) * 1000; + } + +#endif + _message_gps_state.timestamp = hrt_absolute_time(); + result = PX4_OK; + } + + break; + } + + case BlockID::ReceiverStatus: { + SEP_TRACE_PARSING("Processing ReceiverStatus SBF message"); + + ReceiverStatus receiver_status; + + if (_sbf_decoder.parse(&receiver_status) == PX4_OK) { + _message_gps_state.rtcm_msg_used = receiver_status.rx_state_diff_corr_in ? sensor_gps_s::RTCM_MSG_USED_USED : sensor_gps_s::RTCM_MSG_USED_NOT_USED; + } + + break; + } + case BlockID::QualityInd: { + SEP_TRACE_PARSING("Processing QualityInd SBF message"); + break; + } + case BlockID::RFStatus: { + SEP_TRACE_PARSING("Processing RFStatus SBF message"); + break; + } + case BlockID::GALAuthStatus: { + SEP_TRACE_PARSING("Processing GALAuthStatus SBF message"); + break; + } + case BlockID::EndOfPVT: { + SEP_TRACE_PARSING("Processing EndOfPVT SBF message"); + + // EndOfPVT guarantees that all PVT blocks for this epoch have been sent, so it's safe to assume the uORB message contains all required data. + publish(); + break; + } + case BlockID::VelCovGeodetic: { + SEP_TRACE_PARSING("Processing VelCovGeodetic SBF message"); + _current_interval_messages.vel_cov_geodetic = true; + + VelCovGeodetic vel_cov_geodetic; + + if (_sbf_decoder.parse(&vel_cov_geodetic) == PX4_OK) { + _message_gps_state.s_variance_m_s = vel_cov_geodetic.cov_ve_ve; + + if (_message_gps_state.s_variance_m_s < vel_cov_geodetic.cov_vn_vn) { + _message_gps_state.s_variance_m_s = vel_cov_geodetic.cov_vn_vn; + } + + if (_message_gps_state.s_variance_m_s < vel_cov_geodetic.cov_vu_vu) { + _message_gps_state.s_variance_m_s = vel_cov_geodetic.cov_vu_vu; + } + } + + break; + } + case BlockID::GEOIonoDelay: { + SEP_TRACE_PARSING("Processing GEOIonoDelay SBF message"); + break; + } + case BlockID::AttEuler: { + using Error = AttEuler::Error; + + SEP_TRACE_PARSING("Processing AttEuler SBF message"); + _current_interval_messages.att_euler = true; + + AttEuler att_euler; + + if (_sbf_decoder.parse(&att_euler) && + !att_euler.error_not_requested && + att_euler.error_aux1 == Error::None && + att_euler.error_aux2 == Error::None) { + float heading = att_euler.heading * M_PI_F / 180.0f; // Range of degrees to range of radians in [0, 2PI]. + + // Ensure range is in [-PI, PI]. + if (heading > M_PI_F) { + heading -= 2.f * M_PI_F; + } + + _message_gps_state.heading = heading; + } + + break; + } + case BlockID::AttCovEuler: { + using Error = AttCovEuler::Error; + + SEP_TRACE_PARSING("Processing AttCovEuler SBF message"); + _current_interval_messages.att_cov_euler = true; + + AttCovEuler att_cov_euler; + + if (_sbf_decoder.parse(&att_cov_euler) == PX4_OK && + !att_cov_euler.error_not_requested && + att_cov_euler.error_aux1 == Error::None && + att_cov_euler.error_aux2 == Error::None) { + _message_gps_state.heading_accuracy = att_cov_euler.cov_headhead * M_PI_F / 180.0f; // Convert range of degrees to range of radians in [0, 2PI] + } + + break; + } + } + + break; + } + case DecodingStatus::RTCMv3: { + SEP_TRACE_PARSING("Processing RTCMv3 message"); + publish_rtcm_corrections(_rtcm_decoder->message(), _rtcm_decoder->received_bytes()); + break; + } + } + + return result; +} + +bool SeptentrioDriver::send_message(const char *msg) +{ + PX4_DEBUG("Send MSG: %s", msg); + int length = strlen(msg); + + return (write(reinterpret_cast(msg), length) == length); +} + +bool SeptentrioDriver::send_message_and_wait_for_ack(const char *msg, const int timeout) +{ + if (!send_message(msg)) { + return false; + } + + // Wait for acknowledge + // For all valid set -, get - and exe -commands, the first line of the reply is an exact copy + // of the command as entered by the user, preceded with "$R: " + char buf[k_read_buffer_size]; + char expected_response[k_max_command_size+4]; + snprintf(expected_response, sizeof(expected_response), "$R: %s", msg); + uint16_t response_check_character = 0; + // Length of the message without the newline but including the preceding response part "$R: " + size_t response_len = strlen(msg) + 3; + hrt_abstime timeout_time = hrt_absolute_time() + 1000 * timeout; + + do { + int read_result = read(reinterpret_cast(buf), sizeof(buf), 50); + + if (read_result < 0) { + SEP_WARN("SBF read error"); + return false; + } + + for (int i = 0; i < read_result; i++) { + if (response_check_character == response_len) { + // We encountered the complete response + return true; + } else if (expected_response[response_check_character] == buf[i]) { + ++response_check_character; + } else { + response_check_character = 0; + } + } + } while (timeout_time > hrt_absolute_time()); + + PX4_DEBUG("Response: timeout"); + return false; +} + +int SeptentrioDriver::receive(unsigned timeout) +{ + int ret = 0; + int handled = 0; + uint8_t buf[k_read_buffer_size]; + + // timeout additional to poll + hrt_abstime time_started = hrt_absolute_time(); + + while (true) { + // Wait for only `k_receiver_read_timeout` if something already received. + ret = read(buf, sizeof(buf), handled ? k_receiver_read_timeout : timeout); + + if (ret < 0) { + // Something went wrong when polling or reading. + SEP_WARN("poll_or_read err"); + return -1; + + } else { + // Pass received bytes to the packet decoder. + for (int i = 0; i < ret; i++) { + handled |= parse_char(buf[i]); + } + } + + if (handled > 0) { + return handled; + } + + // abort after timeout if no useful packets received + if (time_started + timeout * 1000 < hrt_absolute_time()) { + PX4_DEBUG("timed out, returning"); + return -1; + } + } +} + +int SeptentrioDriver::read(uint8_t *buf, size_t buf_length, int timeout) +{ + int num_read = poll_or_read(buf, buf_length, timeout); + + if (num_read > 0) { + _current_interval_bytes_read += num_read; + if (should_dump_incoming()) { + dump_gps_data(buf, num_read, DataDirection::FromReceiver); + } + } + + return num_read; +} + +int SeptentrioDriver::poll_or_read(uint8_t *buf, size_t buf_length, int timeout) +{ + int read_timeout = math::min(k_max_receiver_read_timeout, timeout); + + return _uart.readAtLeast(buf, buf_length, math::min(k_min_receiver_read_bytes, buf_length), read_timeout); +} + +int SeptentrioDriver::write(const uint8_t* buf, size_t buf_length) +{ + ssize_t write_result = _uart.write(buf, buf_length); + + if (write_result >= 0) { + _current_interval_bytes_written += write_result; + if (should_dump_outgoing()) { + dump_gps_data(buf, write_result, DataDirection::ToReceiver); + } + } + + return write_result; +} + +int SeptentrioDriver::initialize_communication_dump(DumpMode mode) +{ + if (mode == DumpMode::FromReceiver || mode == DumpMode::Both) { + _message_data_from_receiver = new gps_dump_s(); + + if (!_message_data_from_receiver) { + SEP_ERR("Failed to allocate incoming dump buffer"); + return PX4_ERROR; + } + + memset(_message_data_from_receiver, 0, sizeof(*_message_data_from_receiver)); + } + if (mode == DumpMode::ToReceiver || mode == DumpMode::Both) { + _message_data_to_receiver = new gps_dump_s(); + + if (!_message_data_to_receiver) { + SEP_ERR("failed to allocated dump data"); + return PX4_ERROR; + } + + memset(_message_data_to_receiver, 0, sizeof(*_message_data_to_receiver)); + } + + if (mode != DumpMode::Disabled) { + _gps_dump_pub.advertise(); + } + + return PX4_OK; +} + +void SeptentrioDriver::reset_if_scheduled() +{ + ReceiverResetType reset_type = (ReceiverResetType)_scheduled_reset.load(); + + if (reset_type != ReceiverResetType::None) { + _scheduled_reset.store((int)ReceiverResetType::None); + int res = reset(reset_type); + + if (res == PX4_OK) { + SEP_INFO("Reset succeeded."); + } else { + SEP_INFO("Reset failed."); + } + } +} + +int SeptentrioDriver::set_baudrate(uint32_t baud) +{ + if (_uart.setBaudrate(baud)) { + SEP_INFO("baud controller: %lu", baud); + return PX4_OK; + } else { + return PX4_ERROR; + } +} + +void SeptentrioDriver::handle_inject_data_topic() +{ + // We don't want to call copy again further down if we have already done a copy in the selection process. + bool already_copied = false; + gps_inject_data_s msg; + + // If there has not been a valid RTCM message for a while, try to switch to a different RTCM link + if ((hrt_absolute_time() - _last_rtcm_injection_time) > 5_s) { + + for (int instance = 0; instance < _gps_inject_data_sub.size(); instance++) { + const bool exists = _gps_inject_data_sub[instance].advertised(); + + if (exists) { + if (_gps_inject_data_sub[instance].copy(&msg)) { + if ((hrt_absolute_time() - msg.timestamp) < 5_s) { + // Remember that we already did a copy on this instance. + already_copied = true; + _selected_rtcm_instance = instance; + break; + } + } + } + } + } + + bool updated = already_copied; + + // Limit maximum number of GPS injections to 8 since usually + // GPS injections should consist of 1-4 packets (GPS, GLONASS, BeiDou, Galileo). + // Looking at 8 packets thus guarantees, that at least a full injection + // data set is evaluated. + // Moving Base requires a higher rate, so we allow up to 8 packets. + const size_t max_num_injections = gps_inject_data_s::ORB_QUEUE_LENGTH; + size_t num_injections = 0; + + do { + if (updated) { + num_injections++; + + // Prevent injection of data from self or from ground if moving base and this is rover. + if ((_instance == Instance::Secondary && msg.device_id != get_device_id()) || (_instance == Instance::Main && msg.device_id == get_device_id()) || _receiver_setup != ReceiverSetup::MovingBase) { + /* Write the message to the gps device. Note that the message could be fragmented. + * But as we don't write anywhere else to the device during operation, we don't + * need to assemble the message first. + */ + write(msg.data, msg.len); + + ++_current_interval_rtcm_injections; + _last_rtcm_injection_time = hrt_absolute_time(); + } + } + + updated = _gps_inject_data_sub[_selected_rtcm_instance].update(&msg); + + } while (updated && num_injections < max_num_injections); +} + +void SeptentrioDriver::publish() +{ + _message_gps_state.device_id = get_device_id(); + _message_gps_state.selected_rtcm_instance = _selected_rtcm_instance; + _message_gps_state.rtcm_injection_rate = rtcm_injection_frequency(); + + _sensor_gps_pub.publish(_message_gps_state); + + // Heading/yaw data can be updated at a lower rate than the other navigation data. + // The uORB message definition requires this data to be set to a NAN if no new valid data is available. + _message_gps_state.heading = NAN; + + if (_message_gps_state.spoofing_state != _spoofing_state) { + + if (_message_gps_state.spoofing_state > sensor_gps_s::SPOOFING_STATE_NONE) { + SEP_WARN("GPS spoofing detected! (state: %d)", _message_gps_state.spoofing_state); + } + + _spoofing_state = _message_gps_state.spoofing_state; + } + + if (_message_gps_state.jamming_state != _jamming_state) { + + if (_message_gps_state.jamming_state > sensor_gps_s::JAMMING_STATE_WARNING) { + SEP_WARN("GPS jamming detected! (state: %d) (indicator: %d)", _message_gps_state.jamming_state, + (uint8_t)_message_gps_state.jamming_indicator); + } + + _jamming_state = _message_gps_state.jamming_state; + } +} + +void SeptentrioDriver::publish_satellite_info() +{ + if (_message_satellite_info) { + _satellite_info_pub.publish(*_message_satellite_info); + } +} + +void SeptentrioDriver::publish_rtcm_corrections(uint8_t *data, size_t len) +{ + gps_inject_data_s gps_inject_data{}; + + gps_inject_data.timestamp = hrt_absolute_time(); + gps_inject_data.device_id = get_device_id(); + + size_t capacity = (sizeof(gps_inject_data.data) / sizeof(gps_inject_data.data[0])); + + if (len > capacity) { + gps_inject_data.flags = 1; //LSB: 1=fragmented + + } else { + gps_inject_data.flags = 0; + } + + size_t written = 0; + + while (written < len) { + + gps_inject_data.len = len - written; + + if (gps_inject_data.len > capacity) { + gps_inject_data.len = capacity; + } + + memcpy(gps_inject_data.data, &data[written], gps_inject_data.len); + + _gps_inject_data_pub.publish(gps_inject_data); + + written = written + gps_inject_data.len; + } +} + +void SeptentrioDriver::dump_gps_data(const uint8_t *data, size_t len, DataDirection data_direction) +{ + gps_dump_s *dump_data = data_direction == DataDirection::FromReceiver ? _message_data_from_receiver : _message_data_to_receiver; + dump_data->instance = _instance == Instance::Main ? 0 : 1; + + while (len > 0) { + size_t write_len = len; + + if (write_len > sizeof(dump_data->data) - dump_data->len) { + write_len = sizeof(dump_data->data) - dump_data->len; + } + + memcpy(dump_data->data + dump_data->len, data, write_len); + data += write_len; + dump_data->len += write_len; + len -= write_len; + + if (dump_data->len >= sizeof(dump_data->data)) { + if (data_direction == DataDirection::ToReceiver) { + dump_data->len |= 1 << 7; + } + + dump_data->timestamp = hrt_absolute_time(); + _gps_dump_pub.publish(*dump_data); + dump_data->len = 0; + } + } +} + +bool SeptentrioDriver::should_dump_incoming() const +{ + return _message_data_from_receiver != 0; +} + +bool SeptentrioDriver::should_dump_outgoing() const +{ + return _message_data_to_receiver != 0; +} + +void SeptentrioDriver::start_update_monitoring_interval() +{ + PX4_DEBUG("Update monitoring interval started"); + _last_interval_rtcm_injections = _current_interval_rtcm_injections; + _last_interval_bytes_written = _current_interval_bytes_written; + _last_interval_bytes_read = _current_interval_bytes_read; + _last_interval_messages = _current_interval_messages; + _current_interval_rtcm_injections = 0; + _current_interval_bytes_written = 0; + _current_interval_bytes_read = 0; + _current_interval_messages = MessageTracker {}; + _current_interval_start_time = hrt_absolute_time(); +} + +bool SeptentrioDriver::update_monitoring_interval_ended() const +{ + return current_monitoring_interval_duration() > k_update_monitoring_interval_duration; +} + +hrt_abstime SeptentrioDriver::current_monitoring_interval_duration() const +{ + return hrt_absolute_time() - _current_interval_start_time; +} + +float SeptentrioDriver::rtcm_injection_frequency() const +{ + return _last_interval_rtcm_injections / us_to_s(static_cast(k_update_monitoring_interval_duration)); +} + +uint32_t SeptentrioDriver::output_data_rate() const +{ + return static_cast(_last_interval_bytes_written / us_to_s(static_cast(k_update_monitoring_interval_duration))); +} + +uint32_t SeptentrioDriver::input_data_rate() const +{ + return static_cast(_last_interval_bytes_read / us_to_s(static_cast(k_update_monitoring_interval_duration))); +} + +bool SeptentrioDriver::receiver_configuration_healthy() const +{ + return _last_interval_messages.dop && + _last_interval_messages.pvt_geodetic && + _last_interval_messages.vel_cov_geodetic && + _last_interval_messages.att_euler && + _last_interval_messages.att_cov_euler; +} + +float SeptentrioDriver::us_to_s(uint64_t us) +{ + return static_cast(us) / 1000000.0f; +} + +bool SeptentrioDriver::clock_needs_update(timespec real_time) +{ + timespec rtc_system_time; + + px4_clock_gettime(CLOCK_REALTIME, &rtc_system_time); + int drift_time = abs(rtc_system_time.tv_sec - real_time.tv_sec); + + return drift_time >= k_max_allowed_clock_drift; +} + +void SeptentrioDriver::set_clock(timespec rtc_gps_time) +{ + if (clock_needs_update(rtc_gps_time)) { + px4_clock_settime(CLOCK_REALTIME, &rtc_gps_time); + } +} + +bool SeptentrioDriver::is_healthy() const +{ + if (_state == State::ReceivingData) { + if (!receiver_configuration_healthy()) { + return false; + } + } + + return true; +} + +void SeptentrioDriver::reset_gps_state_message() +{ + memset(&_message_gps_state, 0, sizeof(_message_gps_state)); + _message_gps_state.heading = NAN; + _message_gps_state.heading_offset = matrix::wrap_pi(math::radians(_heading_offset)); +} + +uint32_t SeptentrioDriver::get_parameter(const char *name, int32_t *value) +{ + return _get_parameter(name, value); +} + +uint32_t SeptentrioDriver::get_parameter(const char *name, float *value) +{ + return _get_parameter(name, value); +} + +} // namespace septentrio + +extern "C" __EXPORT int septentrio_main(int argc, char *argv[]) +{ + return septentrio::SeptentrioDriver::main(argc, argv); +} diff --git a/src/drivers/gnss/septentrio/septentrio.h b/src/drivers/gnss/septentrio/septentrio.h new file mode 100644 index 000000000000..371c0f2d98cc --- /dev/null +++ b/src/drivers/gnss/septentrio/septentrio.h @@ -0,0 +1,715 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file septentrio.h + * + * Septentrio GNSS receiver driver + * + * @author Matej Franceskin + * @author Seppe Geuens + * @author Thomas Frans +*/ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "module.h" +#include "sbf/decoder.h" +#include "rtcm.h" + +using namespace time_literals; + +namespace septentrio +{ + +/** + * The parsed command line arguments for this module. + */ +struct ModuleArguments { + int baud_rate_main {0}; + int baud_rate_secondary {0}; + const char *device_path_main {nullptr}; + const char *device_path_secondary {nullptr}; +}; + +/** + * Which raw communication data to dump to the log file. +*/ +enum class DumpMode : int32_t { + Disabled = 0, + FromReceiver = 1, + ToReceiver = 2, + Both = 3, +}; + +/** + * Instance of the driver. +*/ +enum class Instance : uint8_t { + Main = 0, + Secondary, +}; + +/** + * Hardware setup and use of the connected receivers. +*/ +enum class ReceiverSetup { + /// Two receivers with the same purpose. + Default = 0, + + /// One rover and one moving base receiver, used for heading with two single-antenna receivers. + MovingBase = 1, +}; + +/** + * Type of reset to perform on the receiver. +*/ +enum class ReceiverResetType { + /** + * There is no pending GPS reset. + */ + None, + + /** + * In hot start mode, the receiver was powered down only for a short time (4 hours or less), + * so that its ephemeris is still valid. Since the receiver doesn't need to download ephemeris + * again, this is the fastest startup method. + */ + Hot, + + /** + * In warm start mode, the receiver has approximate information for time, position, and coarse + * satellite position data (Almanac). In this mode, after power-up, the receiver normally needs + * to download ephemeris before it can calculate position and velocity data. + */ + Warm, + + /** + * In cold start mode, the receiver has no information from the last position at startup. + * Therefore, the receiver must search the full time and frequency space, and all possible + * satellite numbers. If a satellite signal is found, it is tracked to decode the ephemeris, + * whereas the other channels continue to search satellites. Once there is a sufficient number + * of satellites with valid ephemeris, the receiver can calculate position and velocity data. + */ + Cold +}; + +/** + * Direction of raw data. +*/ +enum class DataDirection { + /// Data sent by the flight controller to the receiver. + ToReceiver, + + /// Data sent by the receiver to the flight controller. + FromReceiver, +}; + +/** + * Which satellites the receiver should use for PVT computation. +*/ +enum class SatelliteUsage : int32_t { + Default = 0, + GPS = 1 << 0, + GLONASS = 1 << 1, + Galileo = 1 << 2, + SBAS = 1 << 3, + BeiDou = 1 << 4, +}; + +/** + * General logging level of the receiver that determines the blocks to log. +*/ +enum class ReceiverLogLevel : int32_t { + Lite = 0, + Basic = 1, + Default = 2, + Full = 3, +}; + +/** + * Logging frequency of the receiver that determines SBF output frequency. +*/ +enum class ReceiverLogFrequency : int32_t { + Disabled = 0, + Hz0_1 = 1, + Hz0_2 = 2, + Hz0_5 = 3, + Hz1_0 = 4, + Hz2_0 = 5, + Hz5_0 = 6, + Hz10_0 = 7, + Hz20_0 = 8, + Hz25_0 = 9, + Hz50_0 = 10, +}; + +/** + * Output frequency for the main SBF blocks required for PVT computation. +*/ +enum class SBFOutputFrequency : int32_t { + Hz5_0 = 0, + Hz10_0 = 1, + Hz20_0 = 2, + Hz25_0 = 3, +}; + +/** + * Tracker for messages received by the driver. +*/ +struct MessageTracker { + bool dop {false}; + bool pvt_geodetic {false}; + bool vel_cov_geodetic {false}; + bool att_euler {false}; + bool att_cov_euler {false}; +}; + +/** + * Used for a bitmask to keep track of received messages to know when we need to broadcast them and to monitor receiver health. +*/ +enum class ReceiverOutputTracker { + None = 0, + DOP = 1 << 0, + PVTGeodetic = 1 << 1, + VelCovGeodetic = 1 << 2, + AttEuler = 1 << 3, + AttCovEuler = 1 << 4, + HeadingMessages = AttEuler + AttCovEuler, + RequiredPositionMessages = DOP + PVTGeodetic + VelCovGeodetic + AttCovEuler, + PositioningMessages = DOP + PVTGeodetic + VelCovGeodetic + AttEuler + AttCovEuler, +}; + +class SeptentrioDriver : public ModuleBase, public device::Device +{ +public: + SeptentrioDriver(const char *device_path, Instance instance, uint32_t baud_rate); + ~SeptentrioDriver() override; + + /** @see ModuleBase */ + int print_status() override; + + /** @see ModuleBase */ + void run() override; + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + static int task_spawn(int argc, char *argv[], Instance instance); + + /** + * @brief Secondary run trampoline to support two driver instances. + */ + static int run_trampoline_secondary(int argc, char *argv[]); + + /** @see ModuleBase */ + static SeptentrioDriver *instantiate(int argc, char *argv[]); + + static SeptentrioDriver *instantiate(int argc, char *argv[], Instance instance); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + /** + * @brief Reset the connected GPS receiver. + * + * @return `PX4_OK` on success, `PX4_ERROR` on otherwise + */ + int reset(ReceiverResetType type); + + /** + * @brief Force command input on the currently used port on the receiver. + * + * @return `PX4_OK` on success, `PX4_ERROR` otherwise + */ + int force_input(); +private: + enum class State { + OpeningSerialPort, + ConfiguringDevice, + ReceivingData, + }; + + /** + * The current decoder that data has to be fed to. + */ + enum class DecodingStatus { + Searching, + SBF, + RTCMv3, + }; + + enum class ReceiveResult { + ReadError, + Timeout, + Receiving, + MessageAvailable, + }; + + /** + * Maximum timeout to wait for command acknowledgement by the receiver. + */ + static constexpr uint16_t k_receiver_ack_timeout = 200; + + /** + * Duration of one update monitoring interval in us. + * This should be longer than the time it takes for all *positioning* SBF messages to be sent once by the receiver! + * Otherwise the driver will assume the receiver configuration isn't healthy because it doesn't see all blocks in time. + */ + static constexpr hrt_abstime k_update_monitoring_interval_duration = 5_s; + + /** + * The default stream for output of PVT data. + */ + static constexpr uint8_t k_default_main_stream = 1; + + /** + * The default stream for output of logging data. + */ + static constexpr uint8_t k_default_log_stream = 2; + + /** + * @brief Parse command line arguments for this module. + * + * @param argc Number of arguments. + * @param argv The arguments. + * @param arguments The parsed arguments. + * + * @return `PX4_OK` on success, `PX4_ERROR` on a parsing error. + */ + static int parse_cli_arguments(int argc, char *argv[], ModuleArguments &arguments); + + /** + * @brief Wait for the second instance to properly start up. + * + * @return `PX4_OK` once the second instance has started, or `PX4_ERROR` if timed out waiting. + */ + static int await_second_instance_startup(); + + /** + * @brief Wait for the second instance to properly shut down. + * + * @return `PX4_OK` once the second instance has shut down, or `PX4_ERROR` if timed out waiting. + */ + int await_second_instance_shutdown(); + + /** + * @brief Schedule a reset of the connected receiver. + */ + void schedule_reset(ReceiverResetType type); + + /** + * @brief Detect the current baud rate used by the receiver on the connected port. + * + * @param force_input Choose whether the receiver forces input on the port + * + * @return The detected baud rate on success, or `0` on error + */ + uint32_t detect_receiver_baud_rate(bool forced_input); + + /** + * @brief Try to detect the serial port used on the receiver side. + * + * @param port_name A string with a length of 5 to store the result + * + * @return `PX4_OK` on success, `PX4_ERROR` on error + */ + int detect_serial_port(char *const port_name); + + /** + * @brief Configure the attached receiver based on the user's parameters. + * + * If the user has disabled automatic configuration, only execute the steps that do not touch the receiver (e.g., baud rate detection, port detection...). + * + * @return `PX4_OK` on success, `PX4_ERROR` otherwise. + */ + int configure(); + + /** + * @brief Parse the next byte of a received message from the receiver. + * + * @return 0 = decoding, 1 = message handled, 2 = sat info message handled + */ + int parse_char(const uint8_t byte); + + /** + * @brief Process a fully received message from the receiver. + * + * @return `PX4_OK` on message handled, `PX4_ERROR` on error. + */ + int process_message(); + + /** + * @brief Add payload rx byte. + * + * @return -1 = error, 0 = ok, 1 = payload received completely + */ + int payload_rx_add(const uint8_t byte); + + /** + * @brief Parses incoming SBF blocks. + * + * @return bitfield: all 0 = no message handled, 1 = position handled, 2 = satellite info handled + */ + int payload_rx_done(); + + /** + * @brief Send a message. + * + * @return true on success, false on write error (errno set) + */ + [[nodiscard]] bool send_message(const char *msg); + + /** + * @brief Send a message and waits for acknowledge. + * + * @param msg The message to send to the receiver + * @param timeout The time before sending the message times out + * + * @return true on success, false on write error (errno set) or ack wait timeout + */ + [[nodiscard]] bool send_message_and_wait_for_ack(const char *msg, const int timeout); + + /** + * @brief Receive incoming messages. + * + * @param timeout Maximum time to wait for new data in ms, after which we return. + * + * @return -1 = error, 0 = no message handled, 1 = message handled, 2 = sat info message handled + */ + int receive(unsigned timeout); + + /** + * @brief Read from the receiver. + * + * @param buf Data that is read + * @param buf_length Size of the buffer + * @param timeout Reading timeout + * + * @return 0 on nothing read or poll timeout, <0 on error and >0 on bytes read (nr of bytes) + */ + int read(uint8_t *buf, size_t buf_length, int timeout); + + /** + * @brief This is an abstraction for the poll on serial used. + * + * @param buf The read buffer + * @param buf_length Size of the read buffer + * @param timeout Read timeout in ms + * + * @return 0 on nothing read or poll timeout, <0 on error and >0 on bytes read (nr of bytes) + */ + int poll_or_read(uint8_t *buf, size_t buf_length, int timeout); + + /** + * @brief Write to the receiver. + * + * @param buf Data to be written + * @param buf_length Amount of bytes to be written + * + * @return the number of bytes written on success, or -1 otherwise + */ + int write(const uint8_t *buf, size_t buf_length); + + /** + * @brief Initialize uORB GPS logging and advertise the topic. + * + * @return `PX4_OK` on success, `PX4_ERROR` otherwise + */ + int initialize_communication_dump(DumpMode mode); + + /** + * @brief Reset the receiver if it was requested by the user. + */ + void reset_if_scheduled(); + + /** + * @brief Set the baudrate of the serial connection. + * + * @param baud The baud rate of the connection + * + * @return `PX4_OK` on success, `PX4_ERROR` on otherwise + */ + int set_baudrate(uint32_t baud); + + /** + * @brief Handle incoming messages on the "inject data" uORB topic and send them to the receiver. + */ + void handle_inject_data_topic(); + + /** + * @brief Send data to the receiver, such as RTCM injections. + * + * @param data The raw data to send to the device + * @param len The size of `data` + * + * @return `true` if all the data was written correctly, `false` otherwise + */ + inline bool inject_data(uint8_t *data, size_t len); + + /** + * @brief Publish new GPS data with uORB. + */ + void publish(); + + /** + * @brief Publish new GPS satellite data with uORB. + */ + void publish_satellite_info(); + + /** + * @brief Publish RTCM corrections. + * + * @param data: The raw data to publish + * @param len: The size of `data` + */ + void publish_rtcm_corrections(uint8_t *data, size_t len); + + /** + * @brief Dump gps communication. + * + * @param data The raw data of the message. + * @param len The size of `data`. + * @param data_direction The type of data, either incoming or outgoing. + */ + void dump_gps_data(const uint8_t *data, size_t len, DataDirection data_direction); + + /** + * @brief Check whether we should dump incoming data. + * + * @return `true` when we should dump incoming data, `false` otherwise. + */ + bool should_dump_incoming() const; + + /** + * @brief Check whether we should dump outgoing data. + * + * @return `true` when we should dump outgoing data, `false` otherwise. + */ + bool should_dump_outgoing() const; + + /** + * @brief Start a new update frequency monitoring interval. + */ + void start_update_monitoring_interval(); + + /** + * @brief Check whether the current update monitoring interval should end. + * + * @return `true` if a new interval should be started, or `false` if the current interval is still valid. + */ + bool update_monitoring_interval_ended() const; + + /** + * @brief Get the duration of the current update frequency monitoring interval. + * + * @return The duration of the current interval in us. + */ + hrt_abstime current_monitoring_interval_duration() const; + + /** + * @brief Calculate RTCM message injection frequency for the current measurement interval. + * + * @return The RTCM message injection frequency for the current measurement interval in Hz. + */ + float rtcm_injection_frequency() const; + + /** + * @brief Calculate output data rate to the receiver for the current measurement interval. + * + * @return The output data rate for the current measurement interval in B/s. + */ + uint32_t output_data_rate() const; + + /** + * @brief Calculate input data rate from the receiver for the current measurement interval. + * + * @return The input data rate for the current measurement interval in B/s. + */ + uint32_t input_data_rate() const; + + /** + * @brief Check whether the current receiver configuration is likely healthy. + * + * @return `true` if the receiver is operating correctly, `false` if it needs to be reconfigured. + */ + bool receiver_configuration_healthy() const; + + /** + * @brief Convert from microseconds to seconds. + * + * @return `us` converted into seconds. + */ + static float us_to_s(uint64_t us); + + /** + * @brief Check if the system clock needs to be updated with new time obtained from the receiver. + * + * Setting the clock on Nuttx temporarily pauses interrupts. Therefore it should only be set if it is absolutely necessary. + * + * @return `true` if the clock should be update, `false` if the clock is still accurate enough. + */ + static bool clock_needs_update(timespec real_time); + + /** + * @brief Used to set the system clock accurately. + * + * This does not guarantee that the clock will be set. + * + * @param time The current time. + */ + static void set_clock(timespec rtc_gps_time); + + /** + * @brief Check whether the driver is operating correctly. + * + * @return `true` if the driver is working as expected, `false` otherwise. + */ + bool is_healthy() const; + + /** + * @brief Reset the GPS state uORB message for reuse. + */ + void reset_gps_state_message(); + + /** + * @brief Get the parameter with the given name into `value`. + * + * @param name The name of the parameter. + * @param value The value in which to store the parameter. + * + * @return `PX4_OK` on success, or `PX4_ERROR` if the parameter wasn't found. + */ + static uint32_t get_parameter(const char *name, int32_t *value); + + /** + * @brief Get the parameter with the given name into `value`. + * + * @param name The name of the parameter. + * @param value The value in which to store the parameter. + * + * @return `PX4_OK` on success, or `PX4_ERROR` if the parameter wasn't found. + */ + static uint32_t get_parameter(const char *name, float *value); + + /** + * @brief Don't use this, use the other parameter functions instead! + */ + template + static uint32_t _get_parameter(const char *name, T *value) + { + param_t handle = param_find(name); + + if (handle == PARAM_INVALID || param_get(handle, value) == PX4_ERROR) { + SEP_ERR("Failed to get parameter %s", name); + return PX4_ERROR; + } + + return PX4_OK; + } + + State _state {State::OpeningSerialPort}; ///< Driver state which allows for single run loop + px4::atomic _scheduled_reset {static_cast(ReceiverResetType::None)}; ///< The type of receiver reset that is scheduled + DumpMode _dump_communication_mode {DumpMode::Disabled}; ///< GPS communication dump mode + device::Serial _uart {}; ///< Serial UART port for communication with the receiver + char _port[20] {}; ///< The path of the used serial device + hrt_abstime _last_rtcm_injection_time {0}; ///< Time of last RTCM injection + uint8_t _selected_rtcm_instance {0}; ///< uORB instance that is being used for RTCM corrections + uint8_t _spoofing_state {0}; ///< Receiver spoofing state + uint8_t _jamming_state {0}; ///< Receiver jamming state + const Instance _instance {Instance::Main}; ///< The receiver that this instance of the driver controls + uint32_t _baud_rate {0}; + static px4::atomic _secondary_instance; + hrt_abstime _sleep_end {0}; ///< End time for sleeping + State _resume_state {State::OpeningSerialPort}; ///< Resume state after sleep + + // Module configuration + float _heading_offset {0.0f}; ///< The heading offset given by the `SEP_YAW_OFFS` parameter + float _pitch_offset {0.0f}; ///< The pitch offset given by the `SEP_PITCH_OFFS` parameter + uint32_t _receiver_stream_main {k_default_main_stream}; ///< The main output stream for the receiver given by the `SEP_STREAM_MAIN` parameter + uint32_t _receiver_stream_log {k_default_log_stream}; ///< The log output stream for the receiver given by the `SEP_STREAM_LOG` parameter + SBFOutputFrequency _sbf_output_frequency {SBFOutputFrequency::Hz5_0}; ///< Output frequency of the main SBF blocks given by the `SEP_OUTP_HZ` parameter + ReceiverLogFrequency _receiver_logging_frequency {ReceiverLogFrequency::Hz1_0}; ///< Logging frequency of the receiver given by the `SEP_LOG_HZ` parameter + ReceiverLogLevel _receiver_logging_level {ReceiverLogLevel::Default}; ///< Logging level of the receiver given by the `SEP_LOG_LEVEL` parameter + bool _receiver_logging_overwrite {0}; ///< Logging overwrite behavior, given by the `SEP_LOG_FORCE` parameter + bool _automatic_configuration {true}; ///< Automatic configuration of the receiver given by the `SEP_AUTO_CONFIG` parameter + ReceiverSetup _receiver_setup {ReceiverSetup::Default}; ///< Purpose of the receivers, given by the `SEP_HARDW_SETUP` parameter + int32_t _receiver_constellation_usage {0}; ///< Constellation usage in PVT computation given by the `SEP_CONST_USAGE` parameter + + // Decoding and parsing + DecodingStatus _active_decoder {DecodingStatus::Searching}; ///< Currently active decoder that new data has to be fed into + sbf::Decoder _sbf_decoder {}; ///< SBF message decoder + rtcm::Decoder *_rtcm_decoder {nullptr}; ///< RTCM message decoder + + // uORB topics and subscriptions + sensor_gps_s _message_gps_state {}; ///< uORB topic for position + gps_dump_s *_message_data_to_receiver {nullptr}; ///< uORB topic for dumping data to the receiver + gps_dump_s *_message_data_from_receiver {nullptr}; ///< uORB topic for dumping data from the receiver + satellite_info_s *_message_satellite_info {nullptr}; ///< uORB topic for satellite info + uORB::PublicationMulti _sensor_gps_pub {ORB_ID(sensor_gps)}; ///< uORB publication for gps position + uORB::Publication _gps_dump_pub {ORB_ID(gps_dump)}; ///< uORB publication for dump GPS data + uORB::Publication _gps_inject_data_pub {ORB_ID(gps_inject_data)}; ///< uORB publication for injected data to the receiver + uORB::PublicationMulti _satellite_info_pub {ORB_ID(satellite_info)}; ///< uORB publication for satellite info + uORB::SubscriptionMultiArray _gps_inject_data_sub {ORB_ID::gps_inject_data}; ///< uORB subscription about data to inject to the receiver + + // Data about update frequencies of various bits of information like RTCM message injection frequency, received data rate... + hrt_abstime _current_interval_start_time {0}; ///< Start time of the current update measurement interval in us + uint16_t _last_interval_rtcm_injections {0}; ///< Nr of RTCM message injections in the last measurement interval + uint16_t _current_interval_rtcm_injections {0}; ///< Nr of RTCM message injections in the current measurement interval + uint32_t _last_interval_bytes_written {0}; ///< Nr of bytes written to the receiver in the last measurement interval + uint32_t _current_interval_bytes_written {0}; ///< Nr of bytes written to the receiver in the current measurement interval + uint32_t _last_interval_bytes_read {0}; ///< Nr of bytes read from the receiver in the last measurement interval + uint32_t _current_interval_bytes_read {0}; ///< Nr of bytes read from the receiver in the current measurement interval + MessageTracker _last_interval_messages {}; ///< Messages encountered in the last measurement interval + MessageTracker _current_interval_messages {}; ///< Messages encountered in the current measurement interval +}; + +} // namespace septentrio diff --git a/src/drivers/gnss/septentrio/util.cpp b/src/drivers/gnss/septentrio/util.cpp new file mode 100644 index 000000000000..34bf02f58b89 --- /dev/null +++ b/src/drivers/gnss/septentrio/util.cpp @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file util.cpp + * + * @author Thomas Frans +*/ + +#include "util.h" + +namespace septentrio +{ + +uint16_t buffer_crc16(const uint8_t *data_p, uint32_t length) +{ + uint8_t x; + uint16_t crc = 0; + + while (length--) { + x = crc >> 8 ^ *data_p++; + x ^= x >> 4; + crc = static_cast((crc << 8) ^ (x << 12) ^ (x << 5) ^ x); + } + + return crc; +} + +} // namespace septentrio diff --git a/src/drivers/gnss/septentrio/util.h b/src/drivers/gnss/septentrio/util.h new file mode 100644 index 000000000000..e9de9af50dff --- /dev/null +++ b/src/drivers/gnss/septentrio/util.h @@ -0,0 +1,50 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file util.h + * + * @author Thomas Frans + */ + +#pragma once + +namespace septentrio +{ + +/** + * @brief Calculate buffer CRC16 + */ +uint16_t buffer_crc16(const uint8_t *data_p, uint32_t length); + +} // namespace septentrio diff --git a/src/drivers/gps/CMakeLists.txt b/src/drivers/gps/CMakeLists.txt index 9796d24fb3bc..74ee827283c3 100644 --- a/src/drivers/gps/CMakeLists.txt +++ b/src/drivers/gps/CMakeLists.txt @@ -51,9 +51,8 @@ px4_add_module( devices/src/nmea.cpp devices/src/unicore.cpp devices/src/crc.cpp - devices/src/sbf.cpp MODULE_CONFIG module.yaml DEPENDS git_gps_devices - ) + ) \ No newline at end of file diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 5cfe9eaaaf9e..c1dd783be029 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -73,7 +73,6 @@ # include "devices/src/mtk.h" # include "devices/src/femtomes.h" # include "devices/src/nmea.h" -# include "devices/src/sbf.h" #endif // CONSTRAINED_FLASH #include "devices/src/ubx.h" @@ -97,7 +96,6 @@ enum class gps_driver_mode_t { EMLIDREACH, FEMTOMES, NMEA, - SBF }; enum class gps_dump_comm_mode_t : int32_t { @@ -361,8 +359,6 @@ GPS::GPS(const char *path, gps_driver_mode_t mode, GPSHelper::Interface interfac case 5: _mode = gps_driver_mode_t::FEMTOMES; break; case 6: _mode = gps_driver_mode_t::NMEA; break; - - case 7: _mode = gps_driver_mode_t::SBF; break; #endif // CONSTRAINED_FLASH } } @@ -706,13 +702,6 @@ GPS::run() heading_offset = matrix::wrap_pi(math::radians(heading_offset)); } - handle = param_find("GPS_PITCH_OFFSET"); - float pitch_offset = 0.f; - - if (handle != PARAM_INVALID) { - param_get(handle, &pitch_offset); - } - int32_t gps_ubx_dynmodel = 7; // default to 7: airborne with <2g acceleration handle = param_find("GPS_UBX_DYNMODEL"); @@ -886,11 +875,6 @@ GPS::run() _helper = new GPSDriverNMEA(&GPS::callback, this, &_report_gps_pos, _p_report_sat_info, heading_offset); set_device_type(DRV_GPS_DEVTYPE_NMEA); break; - - case gps_driver_mode_t::SBF: - _helper = new GPSDriverSBF(&GPS::callback, this, &_report_gps_pos, _p_report_sat_info, heading_offset, pitch_offset); - set_device_type(DRV_GPS_DEVTYPE_SBF); - break; #endif // CONSTRAINED_FLASH default: @@ -1068,11 +1052,8 @@ GPS::run() break; case gps_driver_mode_t::FEMTOMES: - _mode = gps_driver_mode_t::SBF; - break; - - case gps_driver_mode_t::SBF: case gps_driver_mode_t::NMEA: // skip NMEA for auto-detection to avoid false positive matching + #endif // CONSTRAINED_FLASH _mode = gps_driver_mode_t::UBX; px4_usleep(500000); // tried all possible drivers. Wait a bit before next round @@ -1132,10 +1113,6 @@ GPS::print_status() case gps_driver_mode_t::NMEA: PX4_INFO("protocol: NMEA"); - break; - - case gps_driver_mode_t::SBF: - PX4_INFO("protocol: SBF"); #endif // CONSTRAINED_FLASH default: @@ -1508,8 +1485,6 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) } else if (!strcmp(myoptarg, "nmea")) { mode = gps_driver_mode_t::NMEA; - } else if (!strcmp(myoptarg, "sbf")) { - mode = gps_driver_mode_t::SBF; #endif // CONSTRAINED_FLASH } else { PX4_ERR("unknown protocol: %s", myoptarg); diff --git a/src/drivers/gps/params.c b/src/drivers/gps/params.c index e00048ea065d..5e5adbcfa9cd 100644 --- a/src/drivers/gps/params.c +++ b/src/drivers/gps/params.c @@ -169,24 +169,6 @@ PARAM_DEFINE_INT32(GPS_UBX_CFG_INTF, 0); */ PARAM_DEFINE_FLOAT(GPS_YAW_OFFSET, 0.f); -/** - * Pitch offset for dual antenna GPS - * - * Vertical offsets can be compensated for by adjusting the Pitch offset (Septentrio). - * - * Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch. - * - * - * @min -90 - * @max 90 - * @unit deg - * @reboot_required true - * @decimal 3 - * - * @group GPS - */ -PARAM_DEFINE_FLOAT(GPS_PITCH_OFFSET, 0.f); - /** * Protocol for Main GPS * @@ -203,7 +185,6 @@ PARAM_DEFINE_FLOAT(GPS_PITCH_OFFSET, 0.f); * @value 4 Emlid Reach * @value 5 Femtomes * @value 6 NMEA (generic) - * @value 7 Septentrio (SBF) * * @reboot_required true * @group GPS @@ -294,4 +275,4 @@ PARAM_DEFINE_INT32(GPS_1_GNSS, 0); * @reboot_required true * @group GPS */ -PARAM_DEFINE_INT32(GPS_2_GNSS, 0); +PARAM_DEFINE_INT32(GPS_2_GNSS, 0); \ No newline at end of file From c0d693bc504460087f4f4f4fb6ad2cc50b3173bd Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 17 Jun 2024 15:09:20 +0200 Subject: [PATCH 363/652] v5_stackcheck: disable CONFIG_DRIVERS_TONE_ALARM Signed-off-by: Silvan Fuhrer --- boards/px4/fmu-v5/stackcheck.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/px4/fmu-v5/stackcheck.px4board b/boards/px4/fmu-v5/stackcheck.px4board index 812a0f729570..0dd66dc3e483 100644 --- a/boards/px4/fmu-v5/stackcheck.px4board +++ b/boards/px4/fmu-v5/stackcheck.px4board @@ -20,6 +20,7 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_DRIVERS_POWER_MONITOR_INA226=n CONFIG_DRIVERS_PWM_INPUT=n CONFIG_DRIVERS_SMART_BATTERY_BATMON=n +CONFIG_DRIVERS_TONE_ALARM=n CONFIG_DRIVERS_UAVCAN=n CONFIG_EXAMPLES_FAKE_GPS=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n From aa55a777bae4c7f6524792ec4523fdff7677ce12 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Mon, 17 Jun 2024 16:02:14 +0200 Subject: [PATCH 364/652] Add px4_sitl_allyes to CI target --- .github/workflows/checks.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/checks.yml b/.github/workflows/checks.yml index f8a893e74729..d977aee7c13b 100644 --- a/.github/workflows/checks.yml +++ b/.github/workflows/checks.yml @@ -23,6 +23,7 @@ jobs: "shellcheck_all", "NO_NINJA_BUILD=1 px4_fmu-v5_default", "NO_NINJA_BUILD=1 px4_sitl_default", + "px4_sitl_allyes", "airframe_metadata", "module_documentation", "parameters_metadata", From 636cb57f27d2d67c8af9a68828f4adce9c9b2eb2 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 13 Jun 2024 05:42:18 -0700 Subject: [PATCH 365/652] NuttX with Backport Adding stm32h755II --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 6fbb26eb5219..f6ecf7c5664e 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 6fbb26eb521999844f099ac93974fdc7ccca6016 +Subproject commit f6ecf7c5664e2beb155d3eb5df07cf837013d73c From f726c0e187e0c1dc2b019fa6b4c28b970fd5f45f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 17 Jun 2024 07:26:20 -0700 Subject: [PATCH 366/652] spracing_h7extreme:rcc Tack upstream name fix --- boards/spracing/h7extreme/src/rcc.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/spracing/h7extreme/src/rcc.c b/boards/spracing/h7extreme/src/rcc.c index cd4299b880ea..73e9506040d8 100644 --- a/boards/spracing/h7extreme/src/rcc.c +++ b/boards/spracing/h7extreme/src/rcc.c @@ -364,7 +364,7 @@ __ramfunc__ void stm32_board_clockconfig(void) */ regval = getreg32(STM32_PWR_CR3); - regval |= STM32_PWR_CR3_LDOEN | STM32_PWR_CR3_LDOESCUEN; + regval |= STM32_PWR_CR3_LDOEN | STM32_PWR_CR3_SCUEN; putreg32(regval, STM32_PWR_CR3); /* Set the voltage output scale */ From 1c657a59b10185dfb52d8c8a16e1af6d0f59cf37 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 17 Jun 2024 07:30:43 -0700 Subject: [PATCH 367/652] px4_fmu-v5_stackcheck:Fit in flash --- boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig index 7350cb45322a..59fc09865501 100644 --- a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig @@ -116,7 +116,7 @@ CONFIG_INIT_STACKSIZE=3194 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 -CONFIG_LIBC_STRERROR=y +CONFIG_LIBC_STRERROR=n CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y From 206488b8446463ed3461dc81cdc77fcf5e344b4c Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 5 Aug 2023 20:46:27 -0400 Subject: [PATCH 368/652] ekf2: innovation sequence monitoring for all aid sources - add new 'innovation_filtered' and 'test_ratio_filtered' fields to estimator_aid_source topics --- msg/EstimatorAidSource1d.msg | 6 +- msg/EstimatorAidSource2d.msg | 14 +- msg/EstimatorAidSource3d.msg | 14 +- .../aid_sources/airspeed/airspeed_fusion.cpp | 45 ++-- .../aux_global_position.cpp | 26 +- .../EKF/aid_sources/auxvel/auxvel_fusion.cpp | 15 +- .../barometer/baro_height_control.cpp | 13 +- .../ekf2/EKF/aid_sources/drag/drag_fusion.cpp | 48 ++-- .../external_vision/ev_control.cpp | 3 - .../external_vision/ev_height_control.cpp | 11 +- .../external_vision/ev_pos_control.cpp | 22 +- .../external_vision/ev_vel_control.cpp | 39 +-- .../external_vision/ev_yaw_control.cpp | 45 ++-- .../EKF/aid_sources/fake_height_control.cpp | 5 +- .../ekf2/EKF/aid_sources/fake_pos_control.cpp | 17 +- .../aid_sources/gnss/gnss_height_control.cpp | 13 +- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 62 +++-- .../EKF/aid_sources/gnss/gps_yaw_fusion.cpp | 78 +++--- .../aid_sources/gravity/gravity_fusion.cpp | 20 +- .../aid_sources/magnetometer/mag_control.cpp | 20 +- .../optical_flow/optical_flow_control.cpp | 2 - .../optical_flow/optical_flow_fusion.cpp | 29 +-- .../range_finder/range_height_control.cpp | 17 +- .../aid_sources/sideslip/sideslip_fusion.cpp | 35 ++- src/modules/ekf2/EKF/ekf.cpp | 53 +--- src/modules/ekf2/EKF/ekf.h | 231 +++++++++++++----- src/modules/ekf2/EKF/estimator_interface.h | 1 - src/modules/ekf2/EKF/position_fusion.cpp | 57 ++--- .../terrain_estimator/terrain_estimator.cpp | 31 +-- src/modules/ekf2/EKF/velocity_fusion.cpp | 54 +--- src/modules/ekf2/EKF/yaw_fusion.cpp | 31 +-- 31 files changed, 524 insertions(+), 533 deletions(-) diff --git a/msg/EstimatorAidSource1d.msg b/msg/EstimatorAidSource1d.msg index 1b416835d670..56ef5cfb991f 100644 --- a/msg/EstimatorAidSource1d.msg +++ b/msg/EstimatorAidSource1d.msg @@ -11,8 +11,12 @@ float32 observation float32 observation_variance float32 innovation +float32 innovation_filtered + float32 innovation_variance -float32 test_ratio + +float32 test_ratio # normalized innovation squared +float32 test_ratio_filtered # signed filtered test ratio bool innovation_rejected # true if the observation has been rejected bool fused # true if the sample was successfully fused diff --git a/msg/EstimatorAidSource2d.msg b/msg/EstimatorAidSource2d.msg index 98e645a3ec92..069030eb15fd 100644 --- a/msg/EstimatorAidSource2d.msg +++ b/msg/EstimatorAidSource2d.msg @@ -1,5 +1,5 @@ -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample # the timestamp of the raw data (microseconds) +uint64 timestamp # time since system start (microseconds) +uint64 timestamp_sample # the timestamp of the raw data (microseconds) uint8 estimator_instance @@ -11,11 +11,15 @@ float32[2] observation float32[2] observation_variance float32[2] innovation +float32[2] innovation_filtered + float32[2] innovation_variance -float32[2] test_ratio -bool innovation_rejected # true if the observation has been rejected -bool fused # true if the sample was successfully fused +float32[2] test_ratio # normalized innovation squared +float32[2] test_ratio_filtered # signed filtered test ratio + +bool innovation_rejected # true if the observation has been rejected +bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_ev_pos estimator_aid_src_fake_pos estimator_aid_src_gnss_pos estimator_aid_src_aux_global_position # TOPICS estimator_aid_src_aux_vel estimator_aid_src_optical_flow estimator_aid_src_terrain_optical_flow diff --git a/msg/EstimatorAidSource3d.msg b/msg/EstimatorAidSource3d.msg index deb4c05bd0fb..b89add28e57e 100644 --- a/msg/EstimatorAidSource3d.msg +++ b/msg/EstimatorAidSource3d.msg @@ -1,5 +1,5 @@ -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample # the timestamp of the raw data (microseconds) +uint64 timestamp # time since system start (microseconds) +uint64 timestamp_sample # the timestamp of the raw data (microseconds) uint8 estimator_instance @@ -11,10 +11,14 @@ float32[3] observation float32[3] observation_variance float32[3] innovation +float32[3] innovation_filtered + float32[3] innovation_variance -float32[3] test_ratio -bool innovation_rejected # true if the observation has been rejected -bool fused # true if the sample was successfully fused +float32[3] test_ratio # normalized innovation squared +float32[3] test_ratio_filtered # signed filtered test ratio + +bool innovation_rejected # true if the observation has been rejected +bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_ev_vel estimator_aid_src_gnss_vel estimator_aid_src_gravity estimator_aid_src_mag diff --git a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp index 7f8539b1cb0e..69895181b1ed 100644 --- a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp @@ -63,6 +63,7 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) } #if defined(CONFIG_EKF2_GNSS) + // clear yaw estimator airspeed (updated later with true airspeed if airspeed fusion is active) if (_control_status.flags.fixed_wing) { if (_control_status.flags.in_air && !_control_status.flags.vehicle_at_rest) { @@ -74,6 +75,7 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) _yawEstimator.setTrueAirspeed(0.f); } } + #endif // CONFIG_EKF2_GNSS if (_params.arsp_thr <= 0.f) { @@ -89,11 +91,15 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) _innov_check_fail_status.flags.reject_airspeed = _aid_src_airspeed.innovation_rejected; // TODO: remove this redundant flag - const bool continuing_conditions_passing = _control_status.flags.in_air && _control_status.flags.fixed_wing && !_control_status.flags.fake_pos; + const bool continuing_conditions_passing = _control_status.flags.in_air + && _control_status.flags.fixed_wing + && !_control_status.flags.fake_pos; + const bool is_airspeed_significant = airspeed_sample.true_airspeed > _params.arsp_thr; const bool is_airspeed_consistent = (_aid_src_airspeed.test_ratio > 0.f && _aid_src_airspeed.test_ratio < 1.f); - const bool starting_conditions_passing = continuing_conditions_passing && is_airspeed_significant - && (is_airspeed_consistent || !_control_status.flags.wind || _control_status.flags.inertial_dead_reckoning); + const bool starting_conditions_passing = continuing_conditions_passing + && is_airspeed_significant + && (is_airspeed_consistent || !_control_status.flags.wind || _control_status.flags.inertial_dead_reckoning); if (_control_status.flags.fuse_aspd) { if (continuing_conditions_passing) { @@ -139,26 +145,22 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) void Ekf::updateAirspeed(const airspeedSample &airspeed_sample, estimator_aid_source1d_s &aid_src) const { - // reset flags - resetEstimatorAidStatus(aid_src); - // Variance for true airspeed measurement - (m/sec)^2 const float R = sq(math::constrain(_params.eas_noise, 0.5f, 5.0f) * math::constrain(airspeed_sample.eas2tas, 0.9f, 10.0f)); float innov = 0.f; float innov_var = 0.f; - sym::ComputeAirspeedInnovAndInnovVar(_state.vector(), P, airspeed_sample.true_airspeed, R, FLT_EPSILON, &innov, &innov_var); - - aid_src.observation = airspeed_sample.true_airspeed; - aid_src.observation_variance = R; - aid_src.innovation = innov; - aid_src.innovation_variance = innov_var; - - aid_src.timestamp_sample = airspeed_sample.time_us; - - const float innov_gate = fmaxf(_params.tas_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(aid_src, innov_gate); + sym::ComputeAirspeedInnovAndInnovVar(_state.vector(), P, airspeed_sample.true_airspeed, R, FLT_EPSILON, + &innov, &innov_var); + + updateAidSourceStatus(aid_src, + airspeed_sample.time_us, // sample timestamp + airspeed_sample.true_airspeed, // observation + R, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.tas_innov_gate, 1.f)); // innovation gate } void Ekf::fuseAirspeed(const airspeedSample &airspeed_sample, estimator_aid_source1d_s &aid_src) @@ -221,7 +223,6 @@ void Ekf::stopAirspeedFusion() { if (_control_status.flags.fuse_aspd) { ECL_INFO("stopping airspeed fusion"); - resetEstimatorAidStatus(_aid_src_airspeed); _control_status.flags.fuse_aspd = false; #if defined(CONFIG_EKF2_GNSS) @@ -235,16 +236,18 @@ void Ekf::resetWindUsingAirspeed(const airspeedSample &airspeed_sample) constexpr float sideslip_var = sq(math::radians(15.0f)); const float euler_yaw = getEulerYaw(_R_to_earth); - const float airspeed_var = sq(math::constrain(_params.eas_noise, 0.5f, 5.0f) * math::constrain(airspeed_sample.eas2tas, 0.9f, 10.0f)); + const float airspeed_var = sq(math::constrain(_params.eas_noise, 0.5f, 5.0f) + * math::constrain(airspeed_sample.eas2tas, 0.9f, 10.0f)); matrix::SquareMatrix P_wind; - sym::ComputeWindInitAndCovFromAirspeed(_state.vel, euler_yaw, airspeed_sample.true_airspeed, getVelocityVariance(), getYawVar(), sideslip_var, airspeed_var, &_state.wind_vel, &P_wind); + sym::ComputeWindInitAndCovFromAirspeed(_state.vel, euler_yaw, airspeed_sample.true_airspeed, getVelocityVariance(), + getYawVar(), sideslip_var, airspeed_var, &_state.wind_vel, &P_wind); resetStateCovariance(P_wind); ECL_INFO("reset wind using airspeed to (%.3f, %.3f)", (double)_state.wind_vel(0), (double)_state.wind_vel(1)); - _aid_src_airspeed.time_last_fuse = _time_delayed_us; + resetAidSourceStatusZeroInnovation(_aid_src_airspeed); } void Ekf::resetVelUsingAirspeed(const airspeedSample &airspeed_sample) 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 a0bee2b0a3ba..15be1c3ce6b4 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 @@ -80,23 +80,27 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed position = ekf.global_origin().project(sample.latitude, sample.longitude); //const float hgt = ekf.getEkfGlobalOriginAltitude() - (float)sample.altitude; // relax the upper observation noise limit which prevents bad measurements perturbing the position estimate - float pos_noise = math::max(sample.eph, _param_ekf2_agp_noise.get()); + float pos_noise = math::max(sample.eph, _param_ekf2_agp_noise.get(), 0.01f); const float pos_var = sq(pos_noise); const Vector2f pos_obs_var(pos_var, pos_var); - ekf.updateHorizontalPositionAidSrcStatus(sample.time_us, - position, // observation - pos_obs_var, // observation variance - math::max(_param_ekf2_agp_gate.get(), 1.f), // innovation gate - aid_src); + + ekf.updateAidSourceStatus(aid_src, + sample.time_us, // sample timestamp + position, // observation + pos_obs_var, // observation variance + Vector2f(ekf.state().pos) - position, // innovation + Vector2f(ekf.getPositionVariance()) + pos_obs_var, // innovation variance + math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate } const bool starting_conditions = PX4_ISFINITE(sample.latitude) && PX4_ISFINITE(sample.longitude) - && ekf.control_status_flags().yaw_align; + && ekf.control_status_flags().yaw_align; const bool continuing_conditions = starting_conditions && ekf.global_origin_valid(); switch (_state) { case State::stopped: + /* FALLTHROUGH */ case State::starting: if (starting_conditions) { @@ -116,6 +120,7 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed } } } + break; case State::active: @@ -124,8 +129,11 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed if (isTimedOut(aid_src.time_last_fuse, imu_delayed.time_us, ekf._params.no_aid_timeout_max) || (_reset_counters.lat_lon != sample.lat_lon_reset_counter)) { + ekf.resetHorizontalPositionTo(Vector2f(aid_src.observation), Vector2f(aid_src.observation_variance)); - aid_src.time_last_fuse = imu_delayed.time_us; + + ekf.resetAidSourceStatusZeroInnovation(aid_src); + _reset_counters.lat_lon = sample.lat_lon_reset_counter; } @@ -133,6 +141,7 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed ekf.disableControlStatusAuxGpos(); _state = State::stopped; } + break; default: @@ -143,6 +152,7 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed aid_src.timestamp = hrt_absolute_time(); _estimator_aid_src_aux_global_position_pub.publish(aid_src); #endif // MODULE_NAME + } else if ((_state != State::stopped) && isTimedOut(_time_last_buffer_push, imu_delayed.time_us, (uint64_t)5e6)) { ekf.disableControlStatusAuxGpos(); _state = State::stopped; diff --git a/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp index 4ef94e31ee9e..132aaa10559b 100644 --- a/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp @@ -36,13 +36,17 @@ void Ekf::controlAuxVelFusion() { if (_auxvel_buffer) { - auxVelSample auxvel_sample_delayed; + auxVelSample sample; - if (_auxvel_buffer->pop_first_older_than(_time_delayed_us, &auxvel_sample_delayed)) { + if (_auxvel_buffer->pop_first_older_than(_time_delayed_us, &sample)) { - resetEstimatorAidStatus(_aid_src_aux_vel); - - updateHorizontalVelocityAidSrcStatus(auxvel_sample_delayed.time_us, auxvel_sample_delayed.vel, auxvel_sample_delayed.velVar, fmaxf(_params.auxvel_gate, 1.f), _aid_src_aux_vel); + updateAidSourceStatus(_aid_src_aux_vel, + sample.time_us, // sample timestamp + sample.vel, // observation + sample.velVar, // observation variance + Vector2f(_state.vel.xy()) - sample.vel, // innovation + Vector2f(getStateVariance()) + sample.velVar, // innovation variance + math::max(_params.auxvel_gate, 1.f)); // innovation gate if (isHorizontalAidingActive()) { fuseHorizontalVelocity(_aid_src_aux_vel); @@ -55,5 +59,4 @@ void Ekf::stopAuxVelFusion() { ECL_INFO("stopping aux vel fusion"); //_control_status.flags.aux_vel = false; - resetEstimatorAidStatus(_aid_src_aux_vel); } diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index f8786c60f974..80c51e097954 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -59,8 +59,6 @@ void Ekf::controlBaroHeightFusion() const float measurement_var = sq(_params.baro_noise); - const float innov_gate = fmaxf(_params.baro_innov_gate, 1.f); - const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); if (measurement_valid) { @@ -80,11 +78,11 @@ void Ekf::controlBaroHeightFusion() } // vertical position innovation - baro measurement has opposite sign to earth z axis - updateVerticalPositionAidSrcStatus(baro_sample.time_us, - -(measurement - bias_est.getBias()), - measurement_var + bias_est.getBiasVar(), - innov_gate, - aid_src); + updateVerticalPositionAidStatus(aid_src, + baro_sample.time_us, + -(measurement - bias_est.getBias()), // observation + measurement_var + bias_est.getBiasVar(), // observation variance + math::max(_params.baro_innov_gate, 1.f)); // innovation gate // Compensate for positive static pressure transients (negative vertical position innovations) // caused by rotor wash ground interaction by applying a temporary deadzone to baro innovations. @@ -191,7 +189,6 @@ void Ekf::stopBaroHgtFusion() } _baro_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_baro_hgt); _control_status.flags.baro_hgt = false; } diff --git a/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp index 5b4baedf123f..c55ed14aaf4d 100644 --- a/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp @@ -105,11 +105,16 @@ void Ekf::fuseDrag(const dragSample &drag_sample) bcoef_inv(1) = bcoef_inv(0); } - _aid_src_drag.timestamp_sample = drag_sample.time_us; - _aid_src_drag.fused = false; - bool fused[] {false, false}; + Vector2f observation{}; + Vector2f observation_variance{R_ACC, R_ACC}; + Vector2f innovation{}; + Vector2f innovation_variance{}; + + // Apply an innovation consistency check with a 5 Sigma threshold + const float innov_gate = 5.f; + VectorState H; // perform sequential fusion of XY specific forces @@ -120,16 +125,15 @@ void Ekf::fuseDrag(const dragSample &drag_sample) // Drag is modelled as an arbitrary combination of bluff body drag that proportional to // equivalent airspeed squared, and rotor momentum drag that is proportional to true airspeed // parallel to the rotor disc and mass flow through the rotor disc. - const float pred_acc = -0.5f * bcoef_inv(axis_index) * rho * rel_wind_body(axis_index) * rel_wind_speed - rel_wind_body(axis_index) * mcoef_corrrected; + const float pred_acc = -0.5f * bcoef_inv(axis_index) * rho * rel_wind_body(axis_index) * rel_wind_speed + - rel_wind_body(axis_index) * mcoef_corrrected; - _aid_src_drag.observation[axis_index] = mea_acc; - _aid_src_drag.observation_variance[axis_index] = R_ACC; - _aid_src_drag.innovation[axis_index] = pred_acc - mea_acc; - _aid_src_drag.innovation_variance[axis_index] = NAN; // reset + observation(axis_index) = mea_acc; + innovation(axis_index) = pred_acc - mea_acc; if (axis_index == 0) { sym::ComputeDragXInnovVarAndH(state_vector_prev, P, rho, bcoef_inv(axis_index), mcoef_corrrected, R_ACC, FLT_EPSILON, - &_aid_src_drag.innovation_variance[axis_index], &H); + &innovation_variance(axis_index), &H); if (!using_bcoef_x && !using_mcoef) { continue; @@ -137,35 +141,41 @@ void Ekf::fuseDrag(const dragSample &drag_sample) } else if (axis_index == 1) { sym::ComputeDragYInnovVarAndH(state_vector_prev, P, rho, bcoef_inv(axis_index), mcoef_corrrected, R_ACC, FLT_EPSILON, - &_aid_src_drag.innovation_variance[axis_index], &H); + &innovation_variance(axis_index), &H); if (!using_bcoef_y && !using_mcoef) { continue; } } - if (_aid_src_drag.innovation_variance[axis_index] < R_ACC) { + if (innovation_variance(axis_index) < R_ACC) { // calculation is badly conditioned - return; + break; } - // Apply an innovation consistency check with a 5 Sigma threshold - const float innov_gate = 5.f; - setEstimatorAidStatusTestRatio(_aid_src_drag, innov_gate); + const float test_ratio = sq(innovation(axis_index)) / (sq(innov_gate) * innovation_variance(axis_index)); if (_control_status.flags.in_air && _control_status.flags.wind && !_control_status.flags.fake_pos - && PX4_ISFINITE(_aid_src_drag.innovation_variance[axis_index]) && PX4_ISFINITE(_aid_src_drag.innovation[axis_index]) - && (_aid_src_drag.test_ratio[axis_index] < 1.f) + && PX4_ISFINITE(innovation_variance(axis_index)) && PX4_ISFINITE(innovation(axis_index)) + && (test_ratio < 1.f) ) { - VectorState K = P * H / _aid_src_drag.innovation_variance[axis_index]; + VectorState K = P * H / innovation_variance(axis_index); - if (measurementUpdate(K, H, R_ACC, _aid_src_drag.innovation[axis_index])) { + if (measurementUpdate(K, H, R_ACC, innovation(axis_index))) { fused[axis_index] = true; } } } + updateAidSourceStatus(_aid_src_drag, + drag_sample.time_us, // sample timestamp + observation, // observation + observation_variance, // observation variance + innovation, // innovation + innovation_variance, // innovation variance + innov_gate); // innovation gate + if (fused[0] && fused[1]) { _aid_src_drag.fused = true; _aid_src_drag.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp index 0780f4111814..f757b59a788e 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp @@ -69,9 +69,6 @@ void Ekf::controlExternalVisionFusion() _ev_sample_prev = ev_sample; } - // record corresponding yaw state for future EV delta heading innovation (logging only) - _ev_yaw_pred_prev = getEulerYaw(_state.quat_nominal); - } else if ((_control_status.flags.ev_pos || _control_status.flags.ev_vel || _control_status.flags.ev_yaw || _control_status.flags.ev_hgt) && isTimedOut(_ev_sample_prev.time_us, 2 * EV_MAX_INTERVAL)) { diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp index 0552ace53c76..e4308c4fcf76 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp @@ -85,11 +85,11 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); - updateVerticalPositionAidSrcStatus(ev_sample.time_us, - measurement - bias_est.getBias(), - measurement_var + bias_est.getBiasVar(), - math::max(_params.ev_pos_innov_gate, 1.f), - aid_src); + updateVerticalPositionAidStatus(aid_src, + ev_sample.time_us, + measurement - bias_est.getBias(), // observation + measurement_var + bias_est.getBiasVar(), // observation variance + math::max(_params.ev_pos_innov_gate, 1.f)); // innovation gate // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation @@ -220,7 +220,6 @@ void Ekf::stopEvHgtFusion() } _ev_hgt_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_ev_hgt); _control_status.flags.ev_hgt = false; } diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp index 3f6027400ade..1e6e7904ddce 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp @@ -126,12 +126,14 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common } #if defined(CONFIG_EKF2_GNSS) + // increase minimum variance if GPS active (position reference) if (_control_status.flags.gps) { for (int i = 0; i < 2; i++) { pos_cov(i, i) = math::max(pos_cov(i, i), sq(_params.gps_pos_noise)); } } + #endif // CONFIG_EKF2_GNSS const Vector2f measurement{pos(0), pos(1)}; @@ -155,18 +157,24 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common } } - updateHorizontalPositionAidSrcStatus(ev_sample.time_us, - measurement - _ev_pos_b_est.getBias(), // observation - measurement_var + _ev_pos_b_est.getBiasVar(), // observation variance - math::max(_params.ev_pos_innov_gate, 1.f), // innovation gate - aid_src); + const Vector2f position = measurement - _ev_pos_b_est.getBias(); + const Vector2f pos_obs_var = measurement_var + _ev_pos_b_est.getBiasVar(); + + updateAidSourceStatus(aid_src, + ev_sample.time_us, // sample timestamp + position, // observation + pos_obs_var, // observation variance + Vector2f(_state.pos) - position, // innovation + Vector2f(getStateVariance()) + pos_obs_var, // innovation variance + math::max(_params.ev_pos_innov_gate, 1.f)); // innovation gate // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation if (measurement_valid && quality_sufficient) { _ev_pos_b_est.setMaxStateNoise(Vector2f(sqrtf(measurement_var(0)), sqrtf(measurement_var(1)))); _ev_pos_b_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd); // TODO - _ev_pos_b_est.fuseBias(measurement - Vector2f(_state.pos.xy()), measurement_var + Vector2f(getStateVariance())); + _ev_pos_b_est.fuseBias(measurement - Vector2f(_state.pos.xy()), + measurement_var + Vector2f(getStateVariance())); } if (!measurement_valid) { @@ -297,8 +305,6 @@ void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measure void Ekf::stopEvPosFusion() { if (_control_status.flags.ev_pos) { - resetEstimatorAidStatus(_aid_src_ev_pos); - _control_status.flags.ev_pos = false; } } diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp index aff345ac1140..e612452b762b 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp @@ -107,12 +107,14 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common } #if defined(CONFIG_EKF2_GNSS) + // increase minimum variance if GPS active (position reference) if (_control_status.flags.gps) { for (int i = 0; i < 2; i++) { vel_cov(i, i) = math::max(vel_cov(i, i), sq(_params.gps_vel_noise)); } } + #endif // CONFIG_EKF2_GNSS const Vector3f measurement{vel}; @@ -125,11 +127,13 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common const bool measurement_valid = measurement.isAllFinite() && measurement_var.isAllFinite(); - updateVelocityAidSrcStatus(ev_sample.time_us, - measurement, // observation - measurement_var, // observation variance - math::max(_params.ev_vel_innov_gate, 1.f), // innovation gate - aid_src); + updateAidSourceStatus(aid_src, + ev_sample.time_us, // sample timestamp + measurement, // observation + measurement_var, // observation variance + _state.vel - measurement, // innovation + getVelocityVariance() + measurement_var, // innovation variance + math::max(_params.ev_vel_innov_gate, 1.f)); // innovation gate if (!measurement_valid) { continuing_conditions_passing = false; @@ -149,7 +153,7 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common ECL_INFO("reset to %s", AID_SRC_NAME); _information_events.flags.reset_vel_to_vision = true; resetVelocityTo(measurement, measurement_var); - aid_src.time_last_fuse = _time_delayed_us; + resetAidSourceStatusZeroInnovation(aid_src); } else { // EV has reset, but quality isn't sufficient @@ -174,7 +178,7 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common _information_events.flags.reset_vel_to_vision = true; ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetVelocityTo(measurement, measurement_var); - aid_src.time_last_fuse = _time_delayed_us; + resetAidSourceStatusZeroInnovation(aid_src); if (_control_status.flags.in_air) { _nb_ev_vel_reset_available--; @@ -205,19 +209,25 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common if (starting_conditions_passing) { // activate fusion, only reset if necessary if (!isHorizontalAidingActive() || yaw_alignment_changed) { - ECL_INFO("starting %s fusion, resetting velocity to (%.3f, %.3f, %.3f)", AID_SRC_NAME, (double)measurement(0), (double)measurement(1), (double)measurement(2)); + ECL_INFO("starting %s fusion, resetting velocity to (%.3f, %.3f, %.3f)", AID_SRC_NAME, + (double)measurement(0), (double)measurement(1), (double)measurement(2)); + _information_events.flags.reset_vel_to_vision = true; + resetVelocityTo(measurement, measurement_var); + resetAidSourceStatusZeroInnovation(aid_src); - } else { + _control_status.flags.ev_vel = true; + + } else if (fuseVelocity(aid_src)) { ECL_INFO("starting %s fusion", AID_SRC_NAME); + _control_status.flags.ev_vel = true; } - aid_src.time_last_fuse = _time_delayed_us; - - _nb_ev_vel_reset_available = 5; - _information_events.flags.starting_vision_vel_fusion = true; - _control_status.flags.ev_vel = true; + if (_control_status.flags.ev_vel) { + _nb_ev_vel_reset_available = 5; + _information_events.flags.starting_vision_vel_fusion = true; + } } } } @@ -225,7 +235,6 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common void Ekf::stopEvVelFusion() { if (_control_status.flags.ev_vel) { - resetEstimatorAidStatus(_aid_src_ev_vel); _control_status.flags.ev_vel = false; } diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp index 3afb3b78fced..d974a5e87b81 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp @@ -43,11 +43,22 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common { static constexpr const char *AID_SRC_NAME = "EV yaw"; - resetEstimatorAidStatus(aid_src); - aid_src.timestamp_sample = ev_sample.time_us; - aid_src.observation = getEulerYaw(ev_sample.quat); - aid_src.observation_variance = math::max(ev_sample.orientation_var(2), _params.ev_att_noise, sq(0.01f)); - aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation); + float obs = getEulerYaw(ev_sample.quat); + float obs_var = math::max(ev_sample.orientation_var(2), _params.ev_att_noise, sq(0.01f)); + + float innov = wrap_pi(getEulerYaw(_R_to_earth) - obs); + float innov_var = 0.f; + + VectorState H_YAW; + computeYawInnovVarAndH(obs_var, innov_var, H_YAW); + + updateAidSourceStatus(aid_src, + ev_sample.time_us, // sample timestamp + obs, // observation + obs_var, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.heading_innov_gate, 1.f)); // innovation gate if (ev_reset) { _control_status.flags.ev_yaw_fault = false; @@ -65,10 +76,6 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common && (ev_sample.pos_frame != PositionFrame::LOCAL_FRAME_NED) ) { continuing_conditions_passing = false; - - // use delta yaw for innovation logging - aid_src.innovation = wrap_pi(wrap_pi(getEulerYaw(_R_to_earth) - _ev_yaw_pred_prev) - - wrap_pi(getEulerYaw(ev_sample.quat) - getEulerYaw(_ev_sample_prev.quat))); } const bool starting_conditions_passing = common_starting_conditions_passing @@ -94,7 +101,7 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common } } else if (quality_sufficient) { - fuseYaw(aid_src); + fuseYaw(aid_src, H_YAW); } else { aid_src.innovation_rejected = true; @@ -141,18 +148,25 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common if (ev_sample.pos_frame == PositionFrame::LOCAL_FRAME_NED) { if (_control_status.flags.yaw_align) { - ECL_INFO("starting %s fusion", AID_SRC_NAME); + + if (fuseYaw(aid_src, H_YAW)) { + ECL_INFO("starting %s fusion", AID_SRC_NAME); + _information_events.flags.starting_vision_yaw_fusion = true; + + _control_status.flags.ev_yaw = true; + } } else { // reset yaw to EV and set yaw_align ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME); + _information_events.flags.starting_vision_yaw_fusion = true; + resetQuatStateYaw(aid_src.observation, aid_src.observation_variance); _control_status.flags.yaw_align = true; - } + _control_status.flags.ev_yaw = true; - aid_src.time_last_fuse = _time_delayed_us; - _information_events.flags.starting_vision_yaw_fusion = true; - _control_status.flags.ev_yaw = true; + aid_src.time_last_fuse = _time_delayed_us; + } } else if (ev_sample.pos_frame == PositionFrame::LOCAL_FRAME_FRD) { // turn on fusion of external vision yaw measurements @@ -178,7 +192,6 @@ void Ekf::stopEvYawFusion() { #if defined(CONFIG_EKF2_EXTERNAL_VISION) if (_control_status.flags.ev_yaw) { - resetEstimatorAidStatus(_aid_src_ev_yaw); _control_status.flags.ev_yaw = false; } diff --git a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp index 8b7eba566413..4ecb5b532564 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp @@ -51,8 +51,7 @@ void Ekf::controlFakeHgtFusion() const float obs_var = sq(_params.pos_noaid_noise); const float innov_gate = 3.f; - updateVerticalPositionAidSrcStatus(_time_delayed_us, _last_known_pos(2), obs_var, innov_gate, aid_src); - + updateVerticalPositionAidStatus(aid_src, _time_delayed_us, _last_known_pos(2), obs_var, innov_gate); const bool continuing_conditions_passing = !isVerticalAidingActive(); const bool starting_conditions_passing = continuing_conditions_passing @@ -113,7 +112,5 @@ void Ekf::stopFakeHgtFusion() if (_control_status.flags.fake_hgt) { ECL_INFO("stop fake height fusion"); _control_status.flags.fake_hgt = false; - - resetEstimatorAidStatus(_aid_src_fake_hgt); } } diff --git a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp index cb3d246f235b..33f05ac68e8f 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp @@ -63,14 +63,21 @@ void Ekf::controlFakePosFusion() obs_var(0) = obs_var(1) = sq(0.5f); } - const float innov_gate = 3.f; + const Vector2f position(_last_known_pos); - updateHorizontalPositionAidSrcStatus(_time_delayed_us, Vector2f(_last_known_pos), obs_var, innov_gate, aid_src); + const float innov_gate = 3.f; + updateAidSourceStatus(aid_src, + _time_delayed_us, + position, // observation + obs_var, // observation variance + Vector2f(_state.pos) - position, // innovation + Vector2f(getStateVariance()) + obs_var, // innovation variance + innov_gate); // innovation gate const bool continuing_conditions_passing = !isHorizontalAidingActive() - && ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest) - && (!(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest); + && ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest) + && (!(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest); const bool starting_conditions_passing = continuing_conditions_passing && _horizontal_deadreckon_time_exceeded; @@ -131,7 +138,5 @@ void Ekf::stopFakePosFusion() if (_control_status.flags.fake_pos) { ECL_INFO("stop fake position fusion"); _control_status.flags.fake_pos = false; - - resetEstimatorAidStatus(_aid_src_fake_pos); } } diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index aafefd8bff1c..ff04cc3b3977 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -67,16 +67,14 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) const float measurement = gnss_alt - getEkfGlobalOriginAltitude(); const float measurement_var = sq(noise); - const float innov_gate = math::max(_params.gps_pos_innov_gate, 1.f); - const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); // GNSS position, vertical position GNSS measurement has opposite sign to earth z axis - updateVerticalPositionAidSrcStatus(gps_sample.time_us, - -(measurement - bias_est.getBias()), - measurement_var + bias_est.getBiasVar(), - innov_gate, - aid_src); + updateVerticalPositionAidStatus(aid_src, + gps_sample.time_us, + -(measurement - bias_est.getBias()), + measurement_var + bias_est.getBiasVar(), + math::max(_params.gps_pos_innov_gate, 1.f)); // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation @@ -171,7 +169,6 @@ void Ekf::stopGpsHgtFusion() } _gps_hgt_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_gnss_hgt); _control_status.flags.gps_hgt = false; } diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index ffa85706767b..a6bb067f4b73 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -52,8 +52,8 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) // run EKF-GSF yaw estimator once per imu_delayed update _yawEstimator.predict(imu_delayed.delta_ang, imu_delayed.delta_ang_dt, - imu_delayed.delta_vel, imu_delayed.delta_vel_dt, - (_control_status.flags.in_air && !_control_status.flags.vehicle_at_rest)); + imu_delayed.delta_vel, imu_delayed.delta_vel_dt, + (_control_status.flags.in_air && !_control_status.flags.vehicle_at_rest)); _gps_intermittent = !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GNSS_MAX_INTERVAL); @@ -183,13 +183,26 @@ void Ekf::updateGnssVel(const gnssSample &gnss_sample, estimator_aid_source3d_s const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body; const Vector3f velocity = gnss_sample.vel - vel_offset_earth; - const float vel_var = sq(math::max(gnss_sample.sacc, _params.gps_vel_noise)); + const float vel_var = sq(math::max(gnss_sample.sacc, _params.gps_vel_noise, 0.01f)); const Vector3f vel_obs_var(vel_var, vel_var, vel_var * sq(1.5f)); - updateVelocityAidSrcStatus(gnss_sample.time_us, - velocity, // observation - vel_obs_var, // observation variance - math::max(_params.gps_vel_innov_gate, 1.f), // innovation gate - aid_src); + + const float innovation_gate = math::max(_params.gps_vel_innov_gate, 1.f); + + updateAidSourceStatus(aid_src, + gnss_sample.time_us, // sample timestamp + velocity, // observation + vel_obs_var, // observation variance + _state.vel - velocity, // innovation + getVelocityVariance() + vel_obs_var, // innovation variance + innovation_gate); // innovation gate + + // vz special case if there is bad vertical acceleration data, then don't reject measurement if GNSS reports velocity accuracy is acceptable, + // but limit innovation to prevent spikes that could destabilise the filter + if (aid_src.innovation_rejected && _fault_status.flags.bad_acc_vertical && (gnss_sample.sacc < _params.req_sacc)) { + const float innov_limit = innovation_gate * sqrtf(aid_src.innovation_variance[2]); + aid_src.innovation[2] = math::constrain(aid_src.innovation[2], -innov_limit, innov_limit); + aid_src.innovation_rejected = false; + } } void Ekf::updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s &aid_src) @@ -210,13 +223,16 @@ void Ekf::updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s } } - const float pos_var = sq(pos_noise); + const float pos_var = math::max(sq(pos_noise), sq(0.01f)); const Vector2f pos_obs_var(pos_var, pos_var); - updateHorizontalPositionAidSrcStatus(gnss_sample.time_us, - position, // observation - pos_obs_var, // observation variance - math::max(_params.gps_pos_innov_gate, 1.f), // innovation gate - aid_src); + + updateAidSourceStatus(aid_src, + gnss_sample.time_us, // sample timestamp + position, // observation + pos_obs_var, // observation variance + Vector2f(_state.pos) - position, // innovation + Vector2f(getStateVariance()) + pos_obs_var, // innovation variance + math::max(_params.gps_pos_innov_gate, 1.f)); // innovation gate } void Ekf::controlGnssYawEstimator(estimator_aid_source3d_s &aid_src_vel) @@ -289,7 +305,8 @@ void Ekf::resetVelocityToGnss(estimator_aid_source3d_s &aid_src) { _information_events.flags.reset_vel_to_gps = true; resetVelocityTo(Vector3f(aid_src.observation), Vector3f(aid_src.observation_variance)); - aid_src.time_last_fuse = _time_delayed_us; + + resetAidSourceStatusZeroInnovation(aid_src); } void Ekf::resetHorizontalPositionToGnss(estimator_aid_source2d_s &aid_src) @@ -297,7 +314,8 @@ void Ekf::resetHorizontalPositionToGnss(estimator_aid_source2d_s &aid_src) _information_events.flags.reset_pos_to_gps = true; resetHorizontalPositionTo(Vector2f(aid_src.observation), Vector2f(aid_src.observation_variance)); _gpos_origin_eph = 0.f; // The uncertainty of the global origin is now contained in the local position uncertainty - aid_src.time_last_fuse = _time_delayed_us; + + resetAidSourceStatusZeroInnovation(aid_src); } bool Ekf::shouldResetGpsFusion() const @@ -342,12 +360,12 @@ void Ekf::controlGpsYawFusion(const gnssSample &gps_sample) return; } - updateGpsYaw(gps_sample); - const bool is_new_data_available = PX4_ISFINITE(gps_sample.yaw); if (is_new_data_available) { + updateGpsYaw(gps_sample); + const bool continuing_conditions_passing = _control_status.flags.tilt_align; const bool is_gps_yaw_data_intermittent = !isNewestSampleRecent(_time_last_gps_yaw_buffer_push, @@ -392,7 +410,9 @@ void Ekf::controlGpsYawFusion(const gnssSample &gps_sample) // Reset before starting the fusion if (resetYawToGps(gps_sample.yaw, gps_sample.yaw_offset)) { - _aid_src_gnss_yaw.time_last_fuse = _time_delayed_us; + + resetAidSourceStatusZeroInnovation(_aid_src_gnss_yaw); + _control_status.flags.gps_yaw = true; _control_status.flags.yaw_align = true; } @@ -422,7 +442,6 @@ void Ekf::stopGpsYawFusion() if (_control_status.flags.gps_yaw) { _control_status.flags.gps_yaw = false; - resetEstimatorAidStatus(_aid_src_gnss_yaw); ECL_INFO("stopping GPS yaw fusion"); } @@ -433,8 +452,7 @@ void Ekf::stopGpsFusion() { if (_control_status.flags.gps) { ECL_INFO("stopping GPS position and velocity fusion"); - resetEstimatorAidStatus(_aid_src_gnss_pos); - resetEstimatorAidStatus(_aid_src_gnss_vel); + _last_gps_fail_us = 0; _last_gps_pass_us = 0; diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp index 13c057f26653..2e135f357f20 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp @@ -48,44 +48,33 @@ void Ekf::updateGpsYaw(const gnssSample &gps_sample) { - if (PX4_ISFINITE(gps_sample.yaw)) { + // calculate the observed yaw angle of antenna array, converting a from body to antenna yaw measurement + const float measured_hdg = wrap_pi(gps_sample.yaw + gps_sample.yaw_offset); - auto &gnss_yaw = _aid_src_gnss_yaw; - resetEstimatorAidStatus(gnss_yaw); + const float yaw_acc = PX4_ISFINITE(gps_sample.yaw_acc) ? gps_sample.yaw_acc : 0.f; + const float R_YAW = sq(fmaxf(yaw_acc, _params.gps_heading_noise)); - // initially populate for estimator_aid_src_gnss_yaw logging - - // calculate the observed yaw angle of antenna array, converting a from body to antenna yaw measurement - const float measured_hdg = wrap_pi(gps_sample.yaw + gps_sample.yaw_offset); - - const float yaw_acc = PX4_ISFINITE(gps_sample.yaw_acc) ? gps_sample.yaw_acc : 0.f; - const float R_YAW = sq(fmaxf(yaw_acc, _params.gps_heading_noise)); - - float heading_pred; - float heading_innov_var; - - { - VectorState H; - sym::ComputeGnssYawPredInnovVarAndH(_state.vector(), P, gps_sample.yaw_offset, R_YAW, FLT_EPSILON, &heading_pred, &heading_innov_var, &H); - } - - gnss_yaw.observation = measured_hdg; - gnss_yaw.observation_variance = R_YAW; - gnss_yaw.innovation = wrap_pi(heading_pred - measured_hdg); - gnss_yaw.innovation_variance = heading_innov_var; - - gnss_yaw.timestamp_sample = gps_sample.time_us; + float heading_pred; + float heading_innov_var; - const float innov_gate = math::max(_params.heading_innov_gate, 1.0f); - setEstimatorAidStatusTestRatio(gnss_yaw, innov_gate); - } + VectorState H; + sym::ComputeGnssYawPredInnovVarAndH(_state.vector(), P, gps_sample.yaw_offset, R_YAW, FLT_EPSILON, + &heading_pred, &heading_innov_var, &H); + + updateAidSourceStatus(_aid_src_gnss_yaw, + gps_sample.time_us, // sample timestamp + measured_hdg, // observation + R_YAW, // observation variance + wrap_pi(heading_pred - measured_hdg), // innovation + heading_innov_var, // innovation variance + math::max(_params.heading_innov_gate, 1.f)); // innovation gate } void Ekf::fuseGpsYaw(float antenna_yaw_offset) { - auto &gnss_yaw = _aid_src_gnss_yaw; + auto &aid_src = _aid_src_gnss_yaw; - if (gnss_yaw.innovation_rejected) { + if (aid_src.innovation_rejected) { _innov_check_fail_status.flags.reject_yaw = true; return; } @@ -94,19 +83,17 @@ void Ekf::fuseGpsYaw(float antenna_yaw_offset) antenna_yaw_offset = 0.f; } - VectorState H; - - { float heading_pred; float heading_innov_var; + VectorState H; // Note: we recompute innov and innov_var because it doesn't cost much more than just computing H // making a separate function just for H uses more flash space without reducing CPU load significantly - sym::ComputeGnssYawPredInnovVarAndH(_state.vector(), P, antenna_yaw_offset, gnss_yaw.observation_variance, FLT_EPSILON, &heading_pred, &heading_innov_var, &H); - } + sym::ComputeGnssYawPredInnovVarAndH(_state.vector(), P, antenna_yaw_offset, aid_src.observation_variance, FLT_EPSILON, + &heading_pred, &heading_innov_var, &H); // check if the innovation variance calculation is badly conditioned - if (gnss_yaw.innovation_variance < gnss_yaw.observation_variance) { + if (aid_src.innovation_variance < aid_src.observation_variance) { // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned _fault_status.flags.bad_hdg = true; @@ -119,11 +106,9 @@ void Ekf::fuseGpsYaw(float antenna_yaw_offset) _fault_status.flags.bad_hdg = false; _innov_check_fail_status.flags.reject_yaw = false; - _gnss_yaw_signed_test_ratio_lpf.update(matrix::sign(gnss_yaw.innovation) * gnss_yaw.test_ratio); - - if ((fabsf(_gnss_yaw_signed_test_ratio_lpf.getState()) > 0.2f) - && !_control_status.flags.in_air && isTimedOut(gnss_yaw.time_last_fuse, (uint64_t)1e6)) { - + if ((fabsf(aid_src.test_ratio_filtered) > 0.2f) + && !_control_status.flags.in_air && isTimedOut(aid_src.time_last_fuse, (uint64_t)1e6) + ) { // A constant large signed test ratio is a sign of wrong gyro bias // Reset the yaw gyro variance to converge faster and avoid // being stuck on a previous bad estimate @@ -132,15 +117,15 @@ void Ekf::fuseGpsYaw(float antenna_yaw_offset) // calculate the Kalman gains // only calculate gains for states we are using - VectorState Kfusion = P * H / gnss_yaw.innovation_variance; + VectorState Kfusion = P * H / aid_src.innovation_variance; - const bool is_fused = measurementUpdate(Kfusion, H, gnss_yaw.observation_variance, gnss_yaw.innovation); + const bool is_fused = measurementUpdate(Kfusion, H, aid_src.observation_variance, aid_src.innovation); _fault_status.flags.bad_hdg = !is_fused; - gnss_yaw.fused = is_fused; + aid_src.fused = is_fused; if (is_fused) { _time_last_heading_fuse = _time_delayed_us; - gnss_yaw.time_last_fuse = _time_delayed_us; + aid_src.time_last_fuse = _time_delayed_us; } } @@ -161,8 +146,5 @@ bool Ekf::resetYawToGps(const float gnss_yaw, const float gnss_yaw_offset) const float yaw_variance = sq(fmaxf(_params.gps_heading_noise, 1.e-2f)); resetQuatStateYaw(measured_yaw, yaw_variance); - _aid_src_gnss_yaw.time_last_fuse = _time_delayed_us; - _gnss_yaw_signed_test_ratio_lpf.reset(0.f); - return true; } diff --git a/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp index 70a0a8ded200..40127a37548e 100644 --- a/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp @@ -69,19 +69,13 @@ void Ekf::controlGravityFusion(const imuSample &imu) sym::ComputeGravityXyzInnovVarAndHx(state_vector, P, measurement_var, &innovation_variance, &H); // fill estimator aid source status - resetEstimatorAidStatus(_aid_src_gravity); - _aid_src_gravity.timestamp_sample = imu.time_us; - measurement.copyTo(_aid_src_gravity.observation); - - for (auto &var : _aid_src_gravity.observation_variance) { - var = measurement_var; - } - - innovation.copyTo(_aid_src_gravity.innovation); - innovation_variance.copyTo(_aid_src_gravity.innovation_variance); - - float innovation_gate = 0.25f; - setEstimatorAidStatusTestRatio(_aid_src_gravity, innovation_gate); + updateAidSourceStatus(_aid_src_gravity, + imu.time_us, // sample timestamp + measurement, // observation + Vector3f{measurement_var, measurement_var, measurement_var}, // observation variance + innovation, // innovation + innovation_variance, // innovation variance + 0.25f); // innovation gate bool fused[3] {false, false, false}; 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 5bc5370f4859..8bf976b8fa5e 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -97,10 +97,6 @@ void Ekf::controlMagFusion() _fault_status.flags.bad_mag_y = false; _fault_status.flags.bad_mag_z = false; - - resetEstimatorAidStatus(aid_src); - aid_src.timestamp_sample = mag_sample.time_us; - // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); @@ -112,15 +108,13 @@ void Ekf::controlMagFusion() VectorState H; sym::ComputeMagInnovInnovVarAndHx(_state.vector(), P, mag_sample.mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); - for (int i = 0; i < 3; i++) { - aid_src.observation[i] = mag_sample.mag(i); - aid_src.observation_variance[i] = R_MAG; - aid_src.innovation[i] = mag_innov(i); - aid_src.innovation_variance[i] = innov_var(i); - } - - const float innov_gate = math::max(_params.mag_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(aid_src, innov_gate); + updateAidSourceStatus(aid_src, + mag_sample.time_us, // sample timestamp + mag_sample.mag, // observation + Vector3f(R_MAG, R_MAG, R_MAG), // observation variance + mag_innov, // innovation + innov_var, // innovation variance + math::max(_params.mag_innov_gate, 1.f)); // innovation gate // Perform an innovation consistency check and report the result _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); 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 160b0b24308e..7758a64da360 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 @@ -164,8 +164,6 @@ void Ekf::stopFlowFusion() if (_control_status.flags.opt_flow) { ECL_INFO("stopping optical flow fusion"); _control_status.flags.opt_flow = false; - - resetEstimatorAidStatus(_aid_src_optical_flow); } } diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 5dd257c7251d..38186ebadf25 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -50,9 +50,6 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) { - resetEstimatorAidStatus(aid_src); - aid_src.timestamp_sample = _flow_sample_delayed.time_us; - const Vector2f vel_body = predictFlowVelBody(); const float range = predictFlowRange(); @@ -66,24 +63,26 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) _flow_vel_body(1) = opt_flow_rate(0) * range; _flow_vel_ne = Vector2f(_R_to_earth * Vector3f(_flow_vel_body(0), _flow_vel_body(1), 0.f)); - aid_src.observation[0] = opt_flow_rate(0); // flow around the X axis - aid_src.observation[1] = opt_flow_rate(1); // flow around the Y axis - - aid_src.innovation[0] = (vel_body(1) / range) - aid_src.observation[0]; - aid_src.innovation[1] = (-vel_body(0) / range) - aid_src.observation[1]; + Vector2f innovation{ + (vel_body(1) / range) - opt_flow_rate(0), + (-vel_body(0) / range) - opt_flow_rate(1) + }; // calculate the optical flow observation variance const float R_LOS = calcOptFlowMeasVar(_flow_sample_delayed); - aid_src.observation_variance[0] = R_LOS; - aid_src.observation_variance[1] = R_LOS; Vector2f innov_var; VectorState H; sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, range, R_LOS, FLT_EPSILON, &innov_var, &H); - innov_var.copyTo(aid_src.innovation_variance); // run the innovation consistency check and record result - setEstimatorAidStatusTestRatio(aid_src, math::max(_params.flow_innov_gate, 1.f)); + updateAidSourceStatus(aid_src, + _flow_sample_delayed.time_us, // sample timestamp + opt_flow_rate, // observation + Vector2f{R_LOS, R_LOS}, // observation variance + innovation, // innovation + innov_var, // innovation variance + math::max(_params.flow_innov_gate, 1.f)); // innovation gate } void Ekf::fuseOptFlow() @@ -101,17 +100,13 @@ void Ekf::fuseOptFlow() sym::ComputeFlowXyInnovVarAndHx(state_vector, P, range, R_LOS, FLT_EPSILON, &innov_var, &H); innov_var.copyTo(_aid_src_optical_flow.innovation_variance); - if ((_aid_src_optical_flow.innovation_variance[0] < R_LOS) - || (_aid_src_optical_flow.innovation_variance[1] < R_LOS)) { + if ((innov_var(0) < R_LOS) || (innov_var(1) < R_LOS)) { // we need to reinitialise the covariance matrix and abort this fusion step ECL_ERR("Opt flow error - covariance reset"); initialiseCovariance(); return; } - // run the innovation consistency check and record result - setEstimatorAidStatusTestRatio(_aid_src_optical_flow, math::max(_params.flow_innov_gate, 1.f)); - _innov_check_fail_status.flags.reject_optflow_X = (_aid_src_optical_flow.test_ratio[0] > 1.f); _innov_check_fail_status.flags.reject_optflow_Y = (_aid_src_optical_flow.test_ratio[1] > 1.f); diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp index 8b4b96712d47..76e815ac738c 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 @@ -102,16 +102,14 @@ void Ekf::controlRangeHeightFusion() const float measurement = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance); const float measurement_var = sq(_params.range_noise) + sq(_params.range_noise_scaler * _range_sensor.getDistBottom()); - const float innov_gate = math::max(_params.range_innov_gate, 1.f); - const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); // vertical position innovation - baro measurement has opposite sign to earth z axis - updateVerticalPositionAidSrcStatus(_range_sensor.getSampleAddress()->time_us, - -(measurement - bias_est.getBias()), - measurement_var + bias_est.getBiasVar(), - innov_gate, - aid_src); + updateVerticalPositionAidStatus(aid_src, + _range_sensor.getSampleAddress()->time_us, // sample timestamp + -(measurement - bias_est.getBias()), // observation + measurement_var + bias_est.getBiasVar(), // observation variance + math::max(_params.range_innov_gate, 1.f)); // innovation gate // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation @@ -170,7 +168,7 @@ void Ekf::controlRangeHeightFusion() if (starting_conditions_passing) { if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) - ) { + ) { // Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference. ECL_INFO("starting conditional %s height fusion", HGT_SRC_NAME); _height_sensor_ref = HeightSensor::RANGE; @@ -178,7 +176,7 @@ void Ekf::controlRangeHeightFusion() } else if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) && (_params.rng_ctrl != static_cast(RngCtrl::CONDITIONAL)) - ) { + ) { // Range finder is the primary height source, the ground is now the datum used // to compute the local vertical position ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME); @@ -259,7 +257,6 @@ void Ekf::stopRngHgtFusion() } _rng_hgt_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_rng_hgt); _control_status.flags.rng_hgt = false; } diff --git a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp index c35501f241c9..997b474793b5 100644 --- a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp @@ -49,8 +49,10 @@ void Ekf::controlBetaFusion(const imuSample &imu_delayed) { - _control_status.flags.fuse_beta = _params.beta_fusion_enabled && _control_status.flags.fixed_wing - && _control_status.flags.in_air && !_control_status.flags.fake_pos; + _control_status.flags.fuse_beta = _params.beta_fusion_enabled + && _control_status.flags.fixed_wing + && _control_status.flags.in_air + && !_control_status.flags.fake_pos; if (_control_status.flags.fuse_beta) { @@ -76,26 +78,22 @@ void Ekf::controlBetaFusion(const imuSample &imu_delayed) } } -void Ekf::updateSideslip(estimator_aid_source1d_s &sideslip) const +void Ekf::updateSideslip(estimator_aid_source1d_s &aid_src) const { - // reset flags - resetEstimatorAidStatus(sideslip); + float observation = 0.f; + const float R = math::max(sq(_params.beta_noise), sq(0.01f)); // observation noise variance - const float R = sq(_params.beta_noise); // observation noise variance - - float innov = 0.f; - float innov_var = 0.f; + float innov; + float innov_var; sym::ComputeSideslipInnovAndInnovVar(_state.vector(), P, R, FLT_EPSILON, &innov, &innov_var); - sideslip.observation = 0.f; - sideslip.observation_variance = R; - sideslip.innovation = innov; - sideslip.innovation_variance = innov_var; - - sideslip.timestamp_sample = _time_delayed_us; - - const float innov_gate = fmaxf(_params.beta_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(sideslip, innov_gate); + updateAidSourceStatus(aid_src, + _time_delayed_us, // sample timestamp + observation, // observation + R, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.beta_innov_gate, 1.f)); // innovation gate } void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) @@ -103,6 +101,7 @@ void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) if (sideslip.innovation_rejected) { return; } + // determine if we need the sideslip fusion to correct states other than wind bool update_wind_only = !_control_status.flags.wind_dead_reckoning; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 7b75211edd7e..8dc7e35d6844 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -124,53 +124,6 @@ void Ekf::reset() _time_good_vert_accel = 0; _clip_counter = 0; -#if defined(CONFIG_EKF2_BAROMETER) - resetEstimatorAidStatus(_aid_src_baro_hgt); -#endif // CONFIG_EKF2_BAROMETER -#if defined(CONFIG_EKF2_AIRSPEED) - resetEstimatorAidStatus(_aid_src_airspeed); -#endif // CONFIG_EKF2_AIRSPEED -#if defined(CONFIG_EKF2_SIDESLIP) - resetEstimatorAidStatus(_aid_src_sideslip); -#endif // CONFIG_EKF2_SIDESLIP - - resetEstimatorAidStatus(_aid_src_fake_pos); - resetEstimatorAidStatus(_aid_src_fake_hgt); - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - resetEstimatorAidStatus(_aid_src_ev_hgt); - resetEstimatorAidStatus(_aid_src_ev_pos); - resetEstimatorAidStatus(_aid_src_ev_vel); - resetEstimatorAidStatus(_aid_src_ev_yaw); -#endif // CONFIG_EKF2_EXTERNAL_VISION - -#if defined(CONFIG_EKF2_GNSS) - resetEstimatorAidStatus(_aid_src_gnss_hgt); - resetEstimatorAidStatus(_aid_src_gnss_pos); - resetEstimatorAidStatus(_aid_src_gnss_vel); - -# if defined(CONFIG_EKF2_GNSS_YAW) - resetEstimatorAidStatus(_aid_src_gnss_yaw); -# endif // CONFIG_EKF2_GNSS_YAW -#endif // CONFIG_EKF2_GNSS - -#if defined(CONFIG_EKF2_MAGNETOMETER) - resetEstimatorAidStatus(_aid_src_mag); -#endif // CONFIG_EKF2_MAGNETOMETER - -#if defined(CONFIG_EKF2_AUXVEL) - resetEstimatorAidStatus(_aid_src_aux_vel); -#endif // CONFIG_EKF2_AUXVEL - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - resetEstimatorAidStatus(_aid_src_optical_flow); - resetEstimatorAidStatus(_aid_src_terrain_optical_flow); -#endif // CONFIG_EKF2_OPTICAL_FLOW - -#if defined(CONFIG_EKF2_RANGE_FINDER) - resetEstimatorAidStatus(_aid_src_rng_hgt); -#endif // CONFIG_EKF2_RANGE_FINDER - _zero_velocity_update.reset(); } @@ -332,7 +285,6 @@ void Ekf::predictState(const imuSample &imu_delayed) void Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation) { - if (!_pos_ref.isInitialized()) { return; } @@ -344,7 +296,10 @@ void Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl Vector2f pos_corrected = _pos_ref.project(lat_deg, lon_deg) + _state.vel.xy() * dt; - resetHorizontalPositionToExternal(pos_corrected, math::max(accuracy, FLT_EPSILON)); + resetHorizontalPositionTo(pos_corrected, sq(math::max(accuracy, 0.01f))); + + ECL_INFO("reset position to external observation"); + _information_events.flags.reset_pos_to_ext_obs = true; } void Ekf::updateParameters() diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 258ef6d7e865..bf62b542f42c 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -641,8 +641,6 @@ class Ekf final : public EstimatorInterface estimator_aid_source3d_s _aid_src_ev_vel{}; estimator_aid_source1d_s _aid_src_ev_yaw{}; - float _ev_yaw_pred_prev{}; ///< previous value of yaw state used by odometry fusion (m) - uint8_t _nb_ev_pos_reset_available{0}; uint8_t _nb_ev_vel_reset_available{0}; uint8_t _nb_ev_yaw_reset_available{0}; @@ -747,7 +745,6 @@ class Ekf final : public EstimatorInterface } // update quaternion states and covariances using an innovation, observation variance and Jacobian vector - bool fuseYaw(estimator_aid_source1d_s &aid_src_status); bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW); void computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const; @@ -802,8 +799,9 @@ class Ekf final : public EstimatorInterface void resetHorizontalVelocityToZero(); void resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var); + + void resetHorizontalPositionToLastKnown(); - void resetHorizontalPositionToExternal(const Vector2f &new_horiz_pos, float horiz_accuracy); void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var); void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const float pos_var = NAN) { resetHorizontalPositionTo(new_horz_pos, Vector2f(pos_var, pos_var)); } @@ -815,20 +813,15 @@ class Ekf final : public EstimatorInterface void resetVerticalVelocityToZero(); // horizontal and vertical position aid source - void updateHorizontalPositionAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, const float innov_gate, estimator_aid_source2d_s &aid_src) const; - void updateVerticalPositionAidSrcStatus(const uint64_t &time_us, const float obs, const float obs_var, const float innov_gate, estimator_aid_source1d_s &aid_src) const; - - // 2d & 3d velocity aid source - void updateHorizontalVelocityAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, const float innov_gate, estimator_aid_source2d_s &aid_src) const; - void updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector3f &obs, const Vector3f &obs_var, const float innov_gate, estimator_aid_source3d_s &aid_src) const; + void updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, const float observation, const float observation_variance, const float innovation_gate = 1.f) const; // horizontal and vertical position fusion - void fuseHorizontalPosition(estimator_aid_source2d_s &pos_aid_src); - void fuseVerticalPosition(estimator_aid_source1d_s &hgt_aid_src); + bool fuseHorizontalPosition(estimator_aid_source2d_s &pos_aid_src); + bool fuseVerticalPosition(estimator_aid_source1d_s &hgt_aid_src); // 2d & 3d velocity fusion - void fuseHorizontalVelocity(estimator_aid_source2d_s &vel_aid_src); - void fuseVelocity(estimator_aid_source3d_s &vel_aid_src); + bool fuseHorizontalVelocity(estimator_aid_source2d_s &vel_aid_src); + bool fuseVelocity(estimator_aid_source3d_s &vel_aid_src); #if defined(CONFIG_EKF2_TERRAIN) // terrain vertical position estimator @@ -1130,88 +1123,200 @@ class Ekf final : public EstimatorInterface bool _ev_q_error_initialized{false}; #endif // CONFIG_EKF2_EXTERNAL_VISION - void resetEstimatorAidStatus(estimator_aid_source1d_s &status) const + // state was reset to aid source, keep observation and update all other fields appropriately (zero innovation, etc) + void resetAidSourceStatusZeroInnovation(estimator_aid_source1d_s &status) const { - // only bother resetting if timestamp_sample is set - if (status.timestamp_sample != 0) { - status.timestamp_sample = 0; + status.time_last_fuse = _time_delayed_us; - // preserve status.time_last_fuse + status.innovation = 0.f; + status.innovation_filtered = 0.f; + status.innovation_variance = status.observation_variance; - status.observation = 0; - status.observation_variance = 0; + status.test_ratio = 0.f; + status.test_ratio_filtered = 0.f; - status.innovation = 0; - status.innovation_variance = 0; - status.test_ratio = INFINITY; - - status.innovation_rejected = true; - status.fused = false; - } + status.innovation_rejected = false; + status.fused = true; } - template - void resetEstimatorAidStatus(T &status) const + // helper used for populating and filtering estimator aid source struct for logging + void updateAidSourceStatus(estimator_aid_source1d_s &status, const uint64_t ×tamp_sample, + const float &observation, const float &observation_variance, + const float &innovation, const float &innovation_variance, + float innovation_gate = 1.f) const { - // only bother resetting if timestamp_sample is set - if (status.timestamp_sample != 0) { - status.timestamp_sample = 0; + bool innovation_rejected = false; - // preserve status.time_last_fuse + const float test_ratio = sq(innovation) / (sq(innovation_gate) * innovation_variance); - for (size_t i = 0; i < (sizeof(status.observation) / sizeof(status.observation[0])); i++) { - status.observation[i] = 0; - status.observation_variance[i] = 0; + if ((status.timestamp_sample > 0) && (timestamp_sample > status.timestamp_sample)) { - status.innovation[i] = 0; - status.innovation_variance[i] = 0; - status.test_ratio[i] = INFINITY; + const float dt_s = math::constrain((timestamp_sample - status.timestamp_sample) * 1e-6f, 0.001f, 1.f); + + static constexpr float tau = 0.5f; + const float alpha = math::constrain(dt_s / (dt_s + tau), 0.f, 1.f); + + // test_ratio_filtered + if (PX4_ISFINITE(status.test_ratio_filtered)) { + status.test_ratio_filtered += alpha * (matrix::sign(innovation) * test_ratio - status.test_ratio_filtered); + + } else { + // otherwise, init the filtered test ratio + status.test_ratio_filtered = test_ratio; + } + + // innovation_filtered + if (PX4_ISFINITE(status.innovation_filtered)) { + status.innovation_filtered += alpha * (innovation - status.innovation_filtered); + + } else { + // otherwise, init the filtered innovation + status.innovation_filtered = innovation; } - status.innovation_rejected = true; - status.fused = false; + + // limit extremes in filtered values + static constexpr float kNormalizedInnovationLimit = 2.f; + static constexpr float kTestRatioLimit = sq(kNormalizedInnovationLimit); + + if (test_ratio > kTestRatioLimit) { + + status.test_ratio_filtered = math::constrain(status.test_ratio_filtered, -kTestRatioLimit, kTestRatioLimit); + + const float innov_limit = kNormalizedInnovationLimit * innovation_gate * sqrtf(innovation_variance); + status.innovation_filtered = math::constrain(status.innovation_filtered, -innov_limit, innov_limit); + } + + } else { + // invalid timestamp_sample, reset + status.test_ratio_filtered = test_ratio; + status.innovation_filtered = innovation; } + + status.test_ratio = test_ratio; + + status.observation = observation; + status.observation_variance = observation_variance; + + status.innovation = innovation; + status.innovation_variance = innovation_variance; + + if ((test_ratio > 1.f) + || !PX4_ISFINITE(test_ratio) + || !PX4_ISFINITE(status.innovation) + || !PX4_ISFINITE(status.innovation_variance) + ) { + innovation_rejected = true; + } + + status.timestamp_sample = timestamp_sample; + + // if any of the innovations are rejected, then the overall innovation is rejected + status.innovation_rejected = innovation_rejected; + + // reset + status.fused = false; } - void setEstimatorAidStatusTestRatio(estimator_aid_source1d_s &status, float innovation_gate) const + // state was reset to aid source, keep observation and update all other fields appropriately (zero innovation, etc) + template + void resetAidSourceStatusZeroInnovation(T &status) const { - if (PX4_ISFINITE(status.innovation) - && PX4_ISFINITE(status.innovation_variance) - && (status.innovation_variance > 0.f) - ) { - status.test_ratio = sq(status.innovation) / (sq(innovation_gate) * status.innovation_variance); - status.innovation_rejected = (status.test_ratio > 1.f); + status.time_last_fuse = _time_delayed_us; - } else { - status.test_ratio = INFINITY; - status.innovation_rejected = true; + for (size_t i = 0; i < (sizeof(status.observation) / sizeof(status.observation[0])); i++) { + status.innovation[i] = 0.f; + status.innovation_filtered[i] = 0.f; + status.innovation_variance[i] = status.observation_variance[i]; + + status.test_ratio[i] = 0.f; + status.test_ratio_filtered[i] = 0.f; } + + status.innovation_rejected = false; + status.fused = true; } - template - void setEstimatorAidStatusTestRatio(T &status, float innovation_gate) const + // helper used for populating and filtering estimator aid source struct for logging + template + void updateAidSourceStatus(T &status, const uint64_t ×tamp_sample, + const S &observation, const S &observation_variance, + const S &innovation, const S &innovation_variance, + float innovation_gate = 1.f) const { bool innovation_rejected = false; - for (size_t i = 0; i < (sizeof(status.test_ratio) / sizeof(status.test_ratio[0])); i++) { - if (PX4_ISFINITE(status.innovation[i]) - && PX4_ISFINITE(status.innovation_variance[i]) - && (status.innovation_variance[i] > 0.f) - ) { - status.test_ratio[i] = sq(status.innovation[i]) / (sq(innovation_gate) * status.innovation_variance[i]); + const float dt_s = math::constrain((timestamp_sample - status.timestamp_sample) * 1e-6f, 0.001f, 1.f); + + static constexpr float tau = 0.5f; + const float alpha = math::constrain(dt_s / (dt_s + tau), 0.f, 1.f); + + for (size_t i = 0; i < (sizeof(status.observation) / sizeof(status.observation[0])); i++) { - if (status.test_ratio[i] > 1.f) { - innovation_rejected = true; + const float test_ratio = sq(innovation(i)) / (sq(innovation_gate) * innovation_variance(i)); + + if ((status.timestamp_sample > 0) && (timestamp_sample > status.timestamp_sample)) { + + // test_ratio_filtered + if (PX4_ISFINITE(status.test_ratio_filtered[i])) { + status.test_ratio_filtered[i] += alpha * (matrix::sign(innovation(i)) * test_ratio - status.test_ratio_filtered[i]); + + } else { + // otherwise, init the filtered test ratio + status.test_ratio_filtered[i] = test_ratio; + } + + // innovation_filtered + if (PX4_ISFINITE(status.innovation_filtered[i])) { + status.innovation_filtered[i] += alpha * (innovation(i) - status.innovation_filtered[i]); + + } else { + // otherwise, init the filtered innovation + status.innovation_filtered[i] = innovation(i); + } + + // limit extremes in filtered values + static constexpr float kNormalizedInnovationLimit = 2.f; + static constexpr float kTestRatioLimit = sq(kNormalizedInnovationLimit); + + if (test_ratio > kTestRatioLimit) { + + status.test_ratio_filtered[i] = math::constrain(status.test_ratio_filtered[i], -kTestRatioLimit, kTestRatioLimit); + + const float innov_limit = kNormalizedInnovationLimit * innovation_gate * sqrtf(innovation_variance(i)); + status.innovation_filtered[i] = math::constrain(status.innovation_filtered[i], -innov_limit, innov_limit); } } else { - status.test_ratio[i] = INFINITY; + // invalid timestamp_sample, reset + status.test_ratio_filtered[i] = test_ratio; + status.innovation_filtered[i] = innovation(i); + } + + status.test_ratio[i] = test_ratio; + + status.observation[i] = observation(i); + status.observation_variance[i] = observation_variance(i); + + status.innovation[i] = innovation(i); + status.innovation_variance[i] = innovation_variance(i); + + if ((test_ratio > 1.f) + || !PX4_ISFINITE(test_ratio) + || !PX4_ISFINITE(status.innovation[i]) + || !PX4_ISFINITE(status.innovation_variance[i]) + ) { innovation_rejected = true; } } + status.timestamp_sample = timestamp_sample; + // if any of the innovations are rejected, then the overall innovation is rejected status.innovation_rejected = innovation_rejected; + + // reset + status.fused = false; } ZeroGyroUpdate _zero_gyro_update{}; diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index b19936ff1ae8..e390f41ea1b1 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -401,7 +401,6 @@ class EstimatorInterface # if defined(CONFIG_EKF2_GNSS_YAW) // innovation consistency check monitoring ratios - AlphaFilter _gnss_yaw_signed_test_ratio_lpf{0.1f}; // average signed test ratio used to detect a bias in the state uint64_t _time_last_gps_yaw_buffer_push{0}; # endif // CONFIG_EKF2_GNSS_YAW #endif // CONFIG_EKF2_GNSS diff --git a/src/modules/ekf2/EKF/position_fusion.cpp b/src/modules/ekf2/EKF/position_fusion.cpp index a1d2f85c273d..d8362b5fceda 100644 --- a/src/modules/ekf2/EKF/position_fusion.cpp +++ b/src/modules/ekf2/EKF/position_fusion.cpp @@ -33,50 +33,27 @@ #include "ekf.h" -void Ekf::updateHorizontalPositionAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, - const float innov_gate, estimator_aid_source2d_s &aid_src) const +void Ekf::updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, + const float observation, const float observation_variance, const float innovation_gate) const { - resetEstimatorAidStatus(aid_src); + float innovation = _state.pos(2) - observation; + float innovation_variance = getStateVariance()(2) + observation_variance; - for (int i = 0; i < 2; i++) { - aid_src.observation[i] = obs(i); - aid_src.innovation[i] = _state.pos(i) - aid_src.observation[i]; - - aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i)); - const int state_index = State::pos.idx + i; - aid_src.innovation_variance[i] = P(state_index, state_index) + aid_src.observation_variance[i]; - } - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); - - aid_src.timestamp_sample = time_us; -} - -void Ekf::updateVerticalPositionAidSrcStatus(const uint64_t &time_us, const float obs, const float obs_var, - const float innov_gate, estimator_aid_source1d_s &aid_src) const -{ - resetEstimatorAidStatus(aid_src); - - aid_src.observation = obs; - aid_src.innovation = _state.pos(2) - aid_src.observation; - - aid_src.observation_variance = math::max(sq(0.01f), obs_var); - aid_src.innovation_variance = P(State::pos.idx + 2, State::pos.idx + 2) + aid_src.observation_variance; - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); + updateAidSourceStatus(aid_src, time_us, + observation, observation_variance, + innovation, innovation_variance, + innovation_gate); // z special case if there is bad vertical acceleration data, then don't reject measurement, // but limit innovation to prevent spikes that could destabilise the filter if (_fault_status.flags.bad_acc_vertical && aid_src.innovation_rejected) { - const float innov_limit = innov_gate * sqrtf(aid_src.innovation_variance); + const float innov_limit = innovation_gate * sqrtf(aid_src.innovation_variance); aid_src.innovation = math::constrain(aid_src.innovation, -innov_limit, innov_limit); aid_src.innovation_rejected = false; } - - aid_src.timestamp_sample = time_us; } -void Ekf::fuseHorizontalPosition(estimator_aid_source2d_s &aid_src) +bool Ekf::fuseHorizontalPosition(estimator_aid_source2d_s &aid_src) { // x & y if (!aid_src.innovation_rejected @@ -91,9 +68,11 @@ void Ekf::fuseHorizontalPosition(estimator_aid_source2d_s &aid_src) } else { aid_src.fused = false; } + + return aid_src.fused; } -void Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src) +bool Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src) { // z if (!aid_src.innovation_rejected @@ -107,6 +86,8 @@ void Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src) } else { aid_src.fused = false; } + + return aid_src.fused; } void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var) @@ -200,11 +181,3 @@ void Ekf::resetHorizontalPositionToLastKnown() // Used when falling back to non-aiding mode of operation resetHorizontalPositionTo(_last_known_pos.xy(), sq(_params.pos_noaid_noise)); } - -void Ekf::resetHorizontalPositionToExternal(const Vector2f &new_horiz_pos, float horiz_accuracy) -{ - ECL_INFO("reset position to external observation"); - _information_events.flags.reset_pos_to_ext_obs = true; - - resetHorizontalPositionTo(new_horiz_pos, sq(horiz_accuracy)); -} diff --git a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp index 64890cd14fa5..dad3c322f105 100644 --- a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp +++ b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp @@ -205,8 +205,6 @@ void Ekf::stopHaglRngFusion() ECL_INFO("stopping HAGL range fusion"); // reset flags - resetEstimatorAidStatus(_aid_src_terrain_range_finder); - _innov_check_fail_status.flags.reject_hagl = false; _hagl_sensor_status.flags.range_finder = false; @@ -221,30 +219,19 @@ void Ekf::updateHaglRng(estimator_aid_source1d_s &aid_src) const // predict the hagl from the vehicle position and terrain height const float pred_hagl = _terrain_vpos - _state.pos(2); - // calculate the innovation - const float hagl_innov = pred_hagl - meas_hagl; - // calculate the observation variance adding the variance of the vehicles own height uncertainty const float obs_variance = getRngVar(); // calculate the innovation variance - limiting it to prevent a badly conditioned fusion const float hagl_innov_var = fmaxf(_terrain_var + obs_variance, obs_variance); - // perform an innovation consistency check and only fuse data if it passes - const float innov_gate = fmaxf(_params.range_innov_gate, 1.0f); - - - aid_src.timestamp_sample = _time_delayed_us; // TODO - - aid_src.observation = meas_hagl; - aid_src.observation_variance = obs_variance; - - aid_src.innovation = hagl_innov; - aid_src.innovation_variance = hagl_innov_var; - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); - - aid_src.fused = false; + updateAidSourceStatus(aid_src, + _time_delayed_us, // sample timestamp + meas_hagl, // observation + obs_variance, // observation variance + pred_hagl - meas_hagl, // innovation + hagl_innov_var, // innovation variance + math::max(_params.range_innov_gate, 1.f)); // innovation gate } void Ekf::fuseHaglRng(estimator_aid_source1d_s &aid_src) @@ -329,7 +316,6 @@ void Ekf::stopHaglFlowFusion() ECL_INFO("stopping HAGL flow fusion"); _hagl_sensor_status.flags.flow = false; - resetEstimatorAidStatus(_aid_src_terrain_optical_flow); } } @@ -367,9 +353,6 @@ void Ekf::fuseFlowForTerrain(estimator_aid_source2d_s &flow) return; } - // run the innovation consistency check and record result - setEstimatorAidStatusTestRatio(flow, math::max(_params.flow_innov_gate, 1.f)); - _innov_check_fail_status.flags.reject_optflow_X = (flow.test_ratio[0] > 1.f); _innov_check_fail_status.flags.reject_optflow_Y = (flow.test_ratio[1] > 1.f); diff --git a/src/modules/ekf2/EKF/velocity_fusion.cpp b/src/modules/ekf2/EKF/velocity_fusion.cpp index fbb079c1fdee..07e590c2111a 100644 --- a/src/modules/ekf2/EKF/velocity_fusion.cpp +++ b/src/modules/ekf2/EKF/velocity_fusion.cpp @@ -33,53 +33,7 @@ #include "ekf.h" -void Ekf::updateHorizontalVelocityAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, - const float innov_gate, estimator_aid_source2d_s &aid_src) const -{ - resetEstimatorAidStatus(aid_src); - - for (int i = 0; i < 2; i++) { - aid_src.observation[i] = obs(i); - aid_src.innovation[i] = _state.vel(i) - aid_src.observation[i]; - - aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i)); - const int state_index = State::vel.idx + i; - aid_src.innovation_variance[i] = P(state_index, state_index) + aid_src.observation_variance[i]; - } - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); - - aid_src.timestamp_sample = time_us; -} - -void Ekf::updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector3f &obs, const Vector3f &obs_var, - const float innov_gate, estimator_aid_source3d_s &aid_src) const -{ - resetEstimatorAidStatus(aid_src); - - for (int i = 0; i < 3; i++) { - aid_src.observation[i] = obs(i); - aid_src.innovation[i] = _state.vel(i) - aid_src.observation[i]; - - aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i)); - const int state_index = State::vel.idx + i; - aid_src.innovation_variance[i] = P(state_index, state_index) + aid_src.observation_variance[i]; - } - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); - - // vz special case if there is bad vertical acceleration data, then don't reject measurement, - // but limit innovation to prevent spikes that could destabilise the filter - if (_fault_status.flags.bad_acc_vertical && aid_src.innovation_rejected) { - const float innov_limit = innov_gate * sqrtf(aid_src.innovation_variance[2]); - aid_src.innovation[2] = math::constrain(aid_src.innovation[2], -innov_limit, innov_limit); - aid_src.innovation_rejected = false; - } - - aid_src.timestamp_sample = time_us; -} - -void Ekf::fuseHorizontalVelocity(estimator_aid_source2d_s &aid_src) +bool Ekf::fuseHorizontalVelocity(estimator_aid_source2d_s &aid_src) { // vx, vy if (!aid_src.innovation_rejected @@ -94,9 +48,11 @@ void Ekf::fuseHorizontalVelocity(estimator_aid_source2d_s &aid_src) } else { aid_src.fused = false; } + + return aid_src.fused; } -void Ekf::fuseVelocity(estimator_aid_source3d_s &aid_src) +bool Ekf::fuseVelocity(estimator_aid_source3d_s &aid_src) { // vx, vy, vz if (!aid_src.innovation_rejected @@ -113,6 +69,8 @@ void Ekf::fuseVelocity(estimator_aid_source3d_s &aid_src) } else { aid_src.fused = false; } + + return aid_src.fused; } void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel, const Vector2f &new_horz_vel_var) diff --git a/src/modules/ekf2/EKF/yaw_fusion.cpp b/src/modules/ekf2/EKF/yaw_fusion.cpp index e843f782ea6e..7714170a62e0 100644 --- a/src/modules/ekf2/EKF/yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/yaw_fusion.cpp @@ -37,23 +37,8 @@ #include -// update quaternion states and covariances using the yaw innovation and yaw observation variance -bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status) -{ - VectorState H_YAW; - sym::ComputeYawInnovVarAndH(_state.vector(), P, aid_src_status.observation_variance, &aid_src_status.innovation_variance, &H_YAW); - - return fuseYaw(aid_src_status, H_YAW); -} - bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW) { - // define the innovation gate size - float gate_sigma = math::max(_params.heading_innov_gate, 1.f); - - // innovation test ratio - setEstimatorAidStatusTestRatio(aid_src_status, gate_sigma); - // check if the innovation variance calculation is badly conditioned if (aid_src_status.innovation_variance >= aid_src_status.observation_variance) { // the innovation variance contribution from the state covariances is not negative, no fault @@ -83,7 +68,7 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H Kfusion(row) *= heading_innov_var_inv; } - // set the magnetometer unhealthy if the test fails + // set the heading unhealthy if the test fails if (aid_src_status.innovation_rejected) { _innov_check_fail_status.flags.reject_yaw = true; @@ -91,13 +76,14 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H // we allow to use it when on the ground because the large innovation could be caused // by interference or a large initial gyro bias if (!_control_status.flags.in_air - && isTimedOut(_time_last_in_air, (uint64_t)5e6) - && isTimedOut(aid_src_status.time_last_fuse, (uint64_t)1e6) - ) { + && isTimedOut(_time_last_in_air, (uint64_t)5e6) + && isTimedOut(aid_src_status.time_last_fuse, (uint64_t)1e6) + ) { // constrain the innovation to the maximum set by the gate // we need to delay this forced fusion to avoid starting it // immediately after touchdown, when the drone is still armed - float gate_limit = sqrtf((sq(gate_sigma) * aid_src_status.innovation_variance)); + const float gate_sigma = math::max(_params.heading_innov_gate, 1.f); + const float gate_limit = sqrtf((sq(gate_sigma) * aid_src_status.innovation_variance)); aid_src_status.innovation = math::constrain(aid_src_status.innovation, -gate_limit, gate_limit); // also reset the yaw gyro variance to converge faster and avoid @@ -122,13 +108,10 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H _fault_status.flags.bad_hdg = false; return true; - - } else { - _fault_status.flags.bad_hdg = true; } // otherwise - aid_src_status.fused = false; + _fault_status.flags.bad_hdg = true; return false; } From 954225a5c0d373215666972855aacff33dfc0740 Mon Sep 17 00:00:00 2001 From: Nuno Marques Date: Wed, 15 May 2024 13:55:41 +0100 Subject: [PATCH 369/652] submodules: mavlink: bring latest definitions as per Thu, Jun 6 2024 --- src/modules/mavlink/mavlink | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index a3558d6b335d..9e0d01df69e2 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit a3558d6b335d930fc01816fd168d16b3f38ed434 +Subproject commit 9e0d01df69e2f659114070db5545a35ddf61cae8 From a8cb5a7715d605d80c812a810398c5060f1c8233 Mon Sep 17 00:00:00 2001 From: Nuno Marques Date: Wed, 15 May 2024 16:06:48 +0100 Subject: [PATCH 370/652] Add fuel tank status report support * Adds support to DroneCAN FuelTankStatus messages * Adds fuel_tank_status uORB message * Adds FUEL_STATUS MAVLink stream * Adds parameter to define max fuel tank capacity --- msg/CMakeLists.txt | 1 + msg/FuelTankStatus.msg | 17 ++++ src/drivers/uavcan/CMakeLists.txt | 1 + src/drivers/uavcan/Kconfig | 4 + .../uavcan/sensors/fuel_tank_status.cpp | 94 +++++++++++++++++++ .../uavcan/sensors/fuel_tank_status.hpp | 70 ++++++++++++++ src/drivers/uavcan/sensors/sensor_bridge.cpp | 14 +++ src/drivers/uavcan/uavcan_params.c | 25 +++++ src/lib/parameters/px4params/srcparser.py | 2 +- src/modules/logger/logged_topics.cpp | 1 + src/modules/mavlink/mavlink_main.cpp | 5 + src/modules/mavlink/mavlink_messages.cpp | 4 + src/modules/mavlink/streams/FUEL_STATUS.hpp | 86 +++++++++++++++++ 13 files changed, 323 insertions(+), 1 deletion(-) create mode 100644 msg/FuelTankStatus.msg create mode 100644 src/drivers/uavcan/sensors/fuel_tank_status.cpp create mode 100644 src/drivers/uavcan/sensors/fuel_tank_status.hpp create mode 100644 src/modules/mavlink/streams/FUEL_STATUS.hpp diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 53ec65cf9a55..a3df406a9cae 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -98,6 +98,7 @@ set(msg_files FollowTarget.msg FollowTargetEstimator.msg FollowTargetStatus.msg + FuelTankStatus.msg GeneratorStatus.msg GeofenceResult.msg GeofenceStatus.msg diff --git a/msg/FuelTankStatus.msg b/msg/FuelTankStatus.msg new file mode 100644 index 000000000000..cddd8b73d518 --- /dev/null +++ b/msg/FuelTankStatus.msg @@ -0,0 +1,17 @@ +uint64 timestamp # time since system start (microseconds) + +float32 maximum_fuel_capacity # maximum fuel capacity +float32 consumed_fuel # consumed fuel, NaN if unavailable +float32 fuel_consumption_rate # fuel consumption rate + +uint8 percent_remaining # percentage of remaining fuel +float32 remaining_fuel # remaining fuel + +uint8 fuel_tank_id # identifier for the fuel tank + +uint32 fuel_type # type of fuel based on MAV_FUEL_TYPE enum +uint8 MAV_FUEL_TYPE_UNKNOWN = 0 # fuel type not specified. Fuel levels are normalized (i.e., maximum is 1, and other levels are relative to 1). +uint8 MAV_FUEL_TYPE_LIQUID = 1 # represents generic liquid fuels, such as gasoline or diesel. Fuel levels are measured in millilitres (ml), and flow rates in millilitres per second (ml/s). +uint8 MAV_FUEL_TYPE_GAS = 2 # represents a gas fuel, such as hydrogen, methane, or propane. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s). + +float32 temperature # fuel temperature in Kelvin, NaN if not measured diff --git a/src/drivers/uavcan/CMakeLists.txt b/src/drivers/uavcan/CMakeLists.txt index 39a9bb3ff2ff..c70d029ea7e3 100644 --- a/src/drivers/uavcan/CMakeLists.txt +++ b/src/drivers/uavcan/CMakeLists.txt @@ -168,6 +168,7 @@ px4_add_module( sensors/battery.cpp sensors/airspeed.cpp sensors/flow.cpp + sensors/fuel_tank_status.cpp sensors/gnss_relative.cpp sensors/gnss.cpp sensors/mag.cpp diff --git a/src/drivers/uavcan/Kconfig b/src/drivers/uavcan/Kconfig index 015894eb6ed0..0076d36568f5 100644 --- a/src/drivers/uavcan/Kconfig +++ b/src/drivers/uavcan/Kconfig @@ -54,6 +54,10 @@ if DRIVERS_UAVCAN bool "Subscribe to Flow: com::hex::equipment::flow::Measurement" default y + config UAVCAN_SENSOR_FUEL_TANK_STATUS + bool "Subscribe to Fuel Tank Status: uavcan::equipment::ice::FuelTankStatus" + default y + config UAVCAN_SENSOR_GNSS bool "Subscribe to GPS: uavcan::equipment::gnss::Auxiliary | uavcan::equipment::gnss::Fix | uavcan::equipment::gnss::Fix2" default y diff --git a/src/drivers/uavcan/sensors/fuel_tank_status.cpp b/src/drivers/uavcan/sensors/fuel_tank_status.cpp new file mode 100644 index 000000000000..2f0fb484bb75 --- /dev/null +++ b/src/drivers/uavcan/sensors/fuel_tank_status.cpp @@ -0,0 +1,94 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file fuel_tank_status.cpp + * @author Nuno Marques + */ + +#include "fuel_tank_status.hpp" + +#include +#include + +const char *const UavcanFuelTankStatusBridge::NAME = "fuel_tank_status"; + +UavcanFuelTankStatusBridge::UavcanFuelTankStatusBridge(uavcan::INode &node) : + UavcanSensorBridgeBase("uavcan_fuel_tank_status", ORB_ID(fuel_tank_status)), + _sub_fuel_tank_status_data(node) +{ } + +int UavcanFuelTankStatusBridge::init() +{ + int res = _sub_fuel_tank_status_data.start(FuelTankStatusCbBinder(this, + &UavcanFuelTankStatusBridge::fuel_tank_status_sub_cb)); + + if (res < 0) { + DEVICE_LOG("failed to start uavcan sub: %d", res); + return res; + } + + return 0; +} + +void UavcanFuelTankStatusBridge::fuel_tank_status_sub_cb(const + uavcan::ReceivedDataStructure &msg) +{ + auto report = ::fuel_tank_status_s(); + report.timestamp = hrt_absolute_time(); + + // Fetching maximum fuel capacity (in liters) from a parameter + param_get(param_find("UAVCAN_ECU_MAXF"), &_max_fuel_capacity); + + _max_fuel_capacity *= 1000.0f; + report.maximum_fuel_capacity = _max_fuel_capacity; + report.fuel_type = fuel_tank_status_s::MAV_FUEL_TYPE_LIQUID; + + // Calculating consumed fuel based on available fuel + report.consumed_fuel = (_max_fuel_capacity > msg.available_fuel_volume_cm3) ? _max_fuel_capacity - + msg.available_fuel_volume_cm3 : NAN; + report.fuel_consumption_rate = msg.fuel_consumption_rate_cm3pm / 60.0f; // convert to ml/s + report.percent_remaining = msg.available_fuel_volume_percent; + report.remaining_fuel = msg.available_fuel_volume_cm3; + report.fuel_tank_id = msg.fuel_tank_id; + + // Optional temperature field, in Kelvin, set to NaN if not provided. + report.temperature = !PX4_ISFINITE(msg.fuel_temperature) ? NAN : msg.fuel_temperature; + + publish(msg.getSrcNodeID().get(), &report); +} + +int UavcanFuelTankStatusBridge::init_driver(uavcan_bridge::Channel *channel) +{ + return PX4_OK; +} diff --git a/src/drivers/uavcan/sensors/fuel_tank_status.hpp b/src/drivers/uavcan/sensors/fuel_tank_status.hpp new file mode 100644 index 000000000000..49f43efb687f --- /dev/null +++ b/src/drivers/uavcan/sensors/fuel_tank_status.hpp @@ -0,0 +1,70 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file fuel_tank_status.hpp + * @author Nuno Marques + * @brief UAVCAN bridge for Fuel Tank Status messages. + */ + +#pragma once + +#include "sensor_bridge.hpp" +#include + +class UavcanFuelTankStatusBridge : public UavcanSensorBridgeBase +{ +public: + static const char *const NAME; + + UavcanFuelTankStatusBridge(uavcan::INode &node); + + const char *get_name() const override { return NAME; } + + int init() override; + +private: + + void fuel_tank_status_sub_cb(const uavcan::ReceivedDataStructure &msg); + + int init_driver(uavcan_bridge::Channel *channel) override; + + typedef uavcan::MethodBinder &)> + FuelTankStatusCbBinder; + + uavcan::Subscriber _sub_fuel_tank_status_data; + + float _max_fuel_capacity{0.0f}; +}; diff --git a/src/drivers/uavcan/sensors/sensor_bridge.cpp b/src/drivers/uavcan/sensors/sensor_bridge.cpp index c219d90f3f04..1fa67050e1f2 100644 --- a/src/drivers/uavcan/sensors/sensor_bridge.cpp +++ b/src/drivers/uavcan/sensors/sensor_bridge.cpp @@ -57,6 +57,9 @@ #if defined(CONFIG_UAVCAN_SENSOR_FLOW) #include "flow.hpp" #endif +#if defined(CONFIG_UAVCAN_SENSOR_FUEL_TANK_STATUS) +#include "fuel_tank_status.hpp" +#endif #if defined(CONFIG_UAVCAN_SENSOR_GNSS) #include "gnss.hpp" #endif @@ -137,6 +140,17 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List(), #endif // FLIGHT_INFORMATION_HPP +#if defined(FUEL_STATUS_HPP) + create_stream_list_item(), +#endif // FUEL_STATUS_HPP #if defined(GPS_STATUS_HPP) create_stream_list_item(), #endif // GPS_STATUS_HPP diff --git a/src/modules/mavlink/streams/FUEL_STATUS.hpp b/src/modules/mavlink/streams/FUEL_STATUS.hpp new file mode 100644 index 000000000000..350f9c9fc7dc --- /dev/null +++ b/src/modules/mavlink/streams/FUEL_STATUS.hpp @@ -0,0 +1,86 @@ +/**************************************************************************** + * + * 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 FUEL_STATUS_HPP +#define FUEL_STATUS_HPP + +#include + +class MavlinkStreamFuelStatus : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamFuelStatus(mavlink); } + + static constexpr const char *get_name_static() { return "FUEL_STATUS"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_FUEL_STATUS; } + + const char *get_name() const override { return MavlinkStreamFuelStatus::get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + return _fuel_tank_status_sub.advertised() ? MAVLINK_MSG_ID_FUEL_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0; + } + +private: + explicit MavlinkStreamFuelStatus(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _fuel_tank_status_sub{ORB_ID(fuel_tank_status)}; + + bool send() override + { + fuel_tank_status_s fuel_status; + + if (_fuel_tank_status_sub.update(&fuel_status)) { + mavlink_fuel_status_t msg{}; + + msg.id = fuel_status.fuel_tank_id; + msg.maximum_fuel = fuel_status.maximum_fuel_capacity; + msg.consumed_fuel = fuel_status.consumed_fuel; + msg.remaining_fuel = fuel_status.remaining_fuel; + msg.percent_remaining = fuel_status.percent_remaining; + msg.flow_rate = fuel_status.fuel_consumption_rate; + msg.temperature = fuel_status.temperature; + msg.fuel_type = fuel_status.fuel_type; + + mavlink_msg_fuel_status_send_struct(_mavlink->get_channel(), &msg); + + return true; + } + + return false; + } + +}; + +#endif // FUEL_STATUS_HPP From 450ae033e44c53f04b988cbb7740d2dcc2740dc9 Mon Sep 17 00:00:00 2001 From: Nuno Marques Date: Wed, 15 May 2024 17:01:51 +0100 Subject: [PATCH 371/652] modules: mavlink: only include FUEL_STATUS stream if the dialect includes it --- src/modules/mavlink/mavlink_main.cpp | 20 +++++++++++++++----- src/modules/mavlink/mavlink_messages.cpp | 4 +++- 2 files changed, 18 insertions(+), 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 59e5ee48939c..54e1a8549eeb 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1413,7 +1413,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("ESC_STATUS", 1.0f); configure_stream_local("ESTIMATOR_STATUS", 0.5f); configure_stream_local("EXTENDED_SYS_STATE", 1.0f); - configure_stream_local("FUEL_STATUS", 1.0f); configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f); configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f); configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); @@ -1453,6 +1452,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) #if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS) configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f); #endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS +#if defined(MAVLINK_MSG_ID_FUEL_STATUS) + configure_stream_local("FUEL_STATUS", 1.0f); +#endif // MAVLINK_MSG_ID_FUEL_STATUS #endif // !CONSTRAINED_FLASH break; @@ -1483,7 +1485,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("EFI_STATUS", 2.0f); configure_stream_local("ESTIMATOR_STATUS", 1.0f); configure_stream_local("EXTENDED_SYS_STATE", 5.0f); - configure_stream_local("FUEL_STATUS", 1.0f); configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f); configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f); configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); @@ -1523,6 +1524,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) #if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS) configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f); #endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS +#if defined(MAVLINK_MSG_ID_FUEL_STATUS) + configure_stream_local("FUEL_STATUS", 1.0f); +#endif // MAVLINK_MSG_ID_FUEL_STATUS #endif // !CONSTRAINED_FLASH break; @@ -1558,7 +1562,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("CURRENT_MODE", 0.5f); configure_stream_local("ESTIMATOR_STATUS", 1.0f); configure_stream_local("EXTENDED_SYS_STATE", 1.0f); - configure_stream_local("FUEL_STATUS", 1.0f); configure_stream_local("GLOBAL_POSITION_INT", 5.0f); configure_stream_local("GPS2_RAW", 1.0f); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); @@ -1589,6 +1592,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) #if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS) configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 2.0f); #endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS +#if defined(MAVLINK_MSG_ID_FUEL_STATUS) + configure_stream_local("FUEL_STATUS", 1.0f); +#endif // MAVLINK_MSG_ID_FUEL_STATUS #endif // !CONSTRAINED_FLASH break; @@ -1645,7 +1651,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("ESC_STATUS", 10.0f); configure_stream_local("ESTIMATOR_STATUS", 5.0f); configure_stream_local("EXTENDED_SYS_STATE", 2.0f); - configure_stream_local("FUEL_STATUS", 2.0f); configure_stream_local("GLOBAL_POSITION_INT", 10.0f); configure_stream_local("GPS2_RAW", unlimited_rate); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); @@ -1690,6 +1695,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) #if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS) configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f); #endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS +#if defined(MAVLINK_MSG_ID_FUEL_STATUS) + configure_stream_local("FUEL_STATUS", 2.0f); +#endif // MAVLINK_MSG_ID_FUEL_STATUS #endif // !CONSTRAINED_FLASH break; @@ -1742,7 +1750,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("CURRENT_MODE", 0.5f); configure_stream_local("ESTIMATOR_STATUS", 1.0f); configure_stream_local("EXTENDED_SYS_STATE", 1.0f); - configure_stream_local("FUEL_STATUS", 1.0f); configure_stream_local("GLOBAL_POSITION_INT", 10.0f); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); configure_stream_local("GPS2_RAW", unlimited_rate); @@ -1774,6 +1781,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) #if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS) configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f); #endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS +#if defined(MAVLINK_MSG_ID_FUEL_STATUS) + configure_stream_local("FUEL_STATUS", 1.0f); +#endif // MAVLINK_MSG_ID_FUEL_STATUS #endif // !CONSTRAINED_FLASH break; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 7032b878949b..638de9cce5f4 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -75,7 +75,6 @@ #include "streams/ESC_STATUS.hpp" #include "streams/ESTIMATOR_STATUS.hpp" #include "streams/EXTENDED_SYS_STATE.hpp" -#include "streams/FUEL_STATUS.hpp" #include "streams/FLIGHT_INFORMATION.hpp" #include "streams/GLOBAL_POSITION_INT.hpp" #include "streams/GPS_GLOBAL_ORIGIN.hpp" @@ -124,6 +123,9 @@ #if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS) #include "streams/FIGURE_EIGHT_EXECUTION_STATUS.hpp" #endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS +#if defined(MAVLINK_MSG_ID_FUEL_STATUS) +#include "streams/FUEL_STATUS.hpp" +#endif // MAVLINK_MSG_ID_FUEL_STATUS #ifdef MAVLINK_MSG_ID_AVAILABLE_MODES // Only defined if development.xml is used #include "streams/AVAILABLE_MODES.hpp" From 03920f2ae3293c8c5c50bb5de391feea183dbde7 Mon Sep 17 00:00:00 2001 From: Nuno Marques Date: Thu, 16 May 2024 12:31:26 +0100 Subject: [PATCH 372/652] msg: FuelTankStatus: updated field descriptions for clarity, specified default values and handling of NaN and unknown cases --- msg/FuelTankStatus.msg | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/msg/FuelTankStatus.msg b/msg/FuelTankStatus.msg index cddd8b73d518..22d21e4a4a31 100644 --- a/msg/FuelTankStatus.msg +++ b/msg/FuelTankStatus.msg @@ -1,15 +1,15 @@ uint64 timestamp # time since system start (microseconds) -float32 maximum_fuel_capacity # maximum fuel capacity -float32 consumed_fuel # consumed fuel, NaN if unavailable -float32 fuel_consumption_rate # fuel consumption rate +float32 maximum_fuel_capacity # maximum fuel capacity. Must always be provided, either from the driver or a parameter +float32 consumed_fuel # consumed fuel, NaN if not measured. Should not be inferred from the max fuel capacity +float32 fuel_consumption_rate # fuel consumption rate, NaN if not measured -uint8 percent_remaining # percentage of remaining fuel -float32 remaining_fuel # remaining fuel +uint8 percent_remaining # percentage of remaining fuel, UINT8_MAX if not provided +float32 remaining_fuel # remaining fuel, NaN if not measured. Should not be inferred from the max fuel capacity -uint8 fuel_tank_id # identifier for the fuel tank +uint8 fuel_tank_id # identifier for the fuel tank. Must match ID of other messages for same fuel system. 0 by default when only a single tank exists -uint32 fuel_type # type of fuel based on MAV_FUEL_TYPE enum +uint32 fuel_type # type of fuel based on MAV_FUEL_TYPE enum. Set to MAV_FUEL_TYPE_UNKNOWN if unknown or it does not fit the provided types uint8 MAV_FUEL_TYPE_UNKNOWN = 0 # fuel type not specified. Fuel levels are normalized (i.e., maximum is 1, and other levels are relative to 1). uint8 MAV_FUEL_TYPE_LIQUID = 1 # represents generic liquid fuels, such as gasoline or diesel. Fuel levels are measured in millilitres (ml), and flow rates in millilitres per second (ml/s). uint8 MAV_FUEL_TYPE_GAS = 2 # represents a gas fuel, such as hydrogen, methane, or propane. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s). From 4067ff0a59acbf412e17a8cfed27a630f6b01bc7 Mon Sep 17 00:00:00 2001 From: Nuno Marques Date: Thu, 16 May 2024 12:50:08 +0100 Subject: [PATCH 373/652] fuel_tank_status: do not infer the consumed fuel, as the provided data is measured --- src/drivers/uavcan/sensors/fuel_tank_status.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/drivers/uavcan/sensors/fuel_tank_status.cpp b/src/drivers/uavcan/sensors/fuel_tank_status.cpp index 2f0fb484bb75..998b85c5fc5c 100644 --- a/src/drivers/uavcan/sensors/fuel_tank_status.cpp +++ b/src/drivers/uavcan/sensors/fuel_tank_status.cpp @@ -70,13 +70,11 @@ void UavcanFuelTankStatusBridge::fuel_tank_status_sub_cb(const // Fetching maximum fuel capacity (in liters) from a parameter param_get(param_find("UAVCAN_ECU_MAXF"), &_max_fuel_capacity); - _max_fuel_capacity *= 1000.0f; + _max_fuel_capacity *= 1000.0f; // convert to ml report.maximum_fuel_capacity = _max_fuel_capacity; report.fuel_type = fuel_tank_status_s::MAV_FUEL_TYPE_LIQUID; - // Calculating consumed fuel based on available fuel - report.consumed_fuel = (_max_fuel_capacity > msg.available_fuel_volume_cm3) ? _max_fuel_capacity - - msg.available_fuel_volume_cm3 : NAN; + report.consumed_fuel = NAN; // only the remaining fuel is measured report.fuel_consumption_rate = msg.fuel_consumption_rate_cm3pm / 60.0f; // convert to ml/s report.percent_remaining = msg.available_fuel_volume_percent; report.remaining_fuel = msg.available_fuel_volume_cm3; From cec0d7c66b20b00fcd5f29e3c0f20680a980f471 Mon Sep 17 00:00:00 2001 From: Nuno Marques Date: Mon, 10 Jun 2024 14:50:39 -0700 Subject: [PATCH 374/652] src: drivers: uavcan: allow to set the fuel type through a parameter --- .../uavcan/sensors/fuel_tank_status.cpp | 6 ++++-- .../uavcan/sensors/fuel_tank_status.hpp | 3 +++ src/drivers/uavcan/uavcan_params.c | 18 ++++++++++++++++++ 3 files changed, 25 insertions(+), 2 deletions(-) diff --git a/src/drivers/uavcan/sensors/fuel_tank_status.cpp b/src/drivers/uavcan/sensors/fuel_tank_status.cpp index 998b85c5fc5c..3a8e74344461 100644 --- a/src/drivers/uavcan/sensors/fuel_tank_status.cpp +++ b/src/drivers/uavcan/sensors/fuel_tank_status.cpp @@ -39,7 +39,6 @@ #include "fuel_tank_status.hpp" #include -#include const char *const UavcanFuelTankStatusBridge::NAME = "fuel_tank_status"; @@ -72,8 +71,11 @@ void UavcanFuelTankStatusBridge::fuel_tank_status_sub_cb(const _max_fuel_capacity *= 1000.0f; // convert to ml report.maximum_fuel_capacity = _max_fuel_capacity; - report.fuel_type = fuel_tank_status_s::MAV_FUEL_TYPE_LIQUID; + // Fetching fuel type + param_get(param_find("UAVCAN_ECU_FUELT"), &_fuel_type); + + report.fuel_type = static_cast(_fuel_type); report.consumed_fuel = NAN; // only the remaining fuel is measured report.fuel_consumption_rate = msg.fuel_consumption_rate_cm3pm / 60.0f; // convert to ml/s report.percent_remaining = msg.available_fuel_volume_percent; diff --git a/src/drivers/uavcan/sensors/fuel_tank_status.hpp b/src/drivers/uavcan/sensors/fuel_tank_status.hpp index 49f43efb687f..ca58666c3cc5 100644 --- a/src/drivers/uavcan/sensors/fuel_tank_status.hpp +++ b/src/drivers/uavcan/sensors/fuel_tank_status.hpp @@ -42,6 +42,8 @@ #include "sensor_bridge.hpp" #include +#include + class UavcanFuelTankStatusBridge : public UavcanSensorBridgeBase { public: @@ -67,4 +69,5 @@ class UavcanFuelTankStatusBridge : public UavcanSensorBridgeBase uavcan::Subscriber _sub_fuel_tank_status_data; float _max_fuel_capacity{0.0f}; + int32_t _fuel_type{fuel_tank_status_s::MAV_FUEL_TYPE_UNKNOWN}; }; diff --git a/src/drivers/uavcan/uavcan_params.c b/src/drivers/uavcan/uavcan_params.c index 36afcfb3322f..ad8765470c13 100644 --- a/src/drivers/uavcan/uavcan_params.c +++ b/src/drivers/uavcan/uavcan_params.c @@ -111,6 +111,24 @@ PARAM_DEFINE_FLOAT(UAVCAN_RNG_MAX, 200.0f); */ PARAM_DEFINE_FLOAT(UAVCAN_ECU_MAXF, 15.0f); +/** + * UAVCAN fuel tank fuel type + * + * This parameter defines the type of fuel used in the vehicle's fuel tank. + * + * 0: Unknown + * 1: Liquid (e.g., gasoline, diesel) + * 2: Gas (e.g., hydrogen, methane, propane) + * + * @min 0 + * @max 2 + * @value 0 Unknown + * @value 1 Liquid + * @value 2 Gas + * @group UAVCAN + */ +PARAM_DEFINE_INT32(UAVCAN_ECU_FUELT, 1); + /** * UAVCAN ANTI_COLLISION light operating mode * From 377e2d75238b5c96570c4e83adf794941832a01f Mon Sep 17 00:00:00 2001 From: Nuno Marques Date: Thu, 13 Jun 2024 09:10:53 -0700 Subject: [PATCH 375/652] src: drivers: uavcan: move UAVCAN_ECU_MAXF and UAVCAN_ECU_FUELT fetch to init and make reboot required --- src/drivers/uavcan/sensors/fuel_tank_status.cpp | 17 +++++++---------- src/drivers/uavcan/uavcan_params.c | 2 ++ 2 files changed, 9 insertions(+), 10 deletions(-) diff --git a/src/drivers/uavcan/sensors/fuel_tank_status.cpp b/src/drivers/uavcan/sensors/fuel_tank_status.cpp index 3a8e74344461..7834ef64258b 100644 --- a/src/drivers/uavcan/sensors/fuel_tank_status.cpp +++ b/src/drivers/uavcan/sensors/fuel_tank_status.cpp @@ -57,6 +57,12 @@ int UavcanFuelTankStatusBridge::init() return res; } + // Fetch maximum fuel capacity (in liters) + param_get(param_find("UAVCAN_ECU_MAXF"), &_max_fuel_capacity); + + // Fetching fuel type + param_get(param_find("UAVCAN_ECU_FUELT"), &_fuel_type); + return 0; } @@ -65,16 +71,7 @@ void UavcanFuelTankStatusBridge::fuel_tank_status_sub_cb(const { auto report = ::fuel_tank_status_s(); report.timestamp = hrt_absolute_time(); - - // Fetching maximum fuel capacity (in liters) from a parameter - param_get(param_find("UAVCAN_ECU_MAXF"), &_max_fuel_capacity); - - _max_fuel_capacity *= 1000.0f; // convert to ml - report.maximum_fuel_capacity = _max_fuel_capacity; - - // Fetching fuel type - param_get(param_find("UAVCAN_ECU_FUELT"), &_fuel_type); - + report.maximum_fuel_capacity = _max_fuel_capacity * 1000.0f; // convert to ml report.fuel_type = static_cast(_fuel_type); report.consumed_fuel = NAN; // only the remaining fuel is measured report.fuel_consumption_rate = msg.fuel_consumption_rate_cm3pm / 60.0f; // convert to ml/s diff --git a/src/drivers/uavcan/uavcan_params.c b/src/drivers/uavcan/uavcan_params.c index ad8765470c13..edd2c41ea4c3 100644 --- a/src/drivers/uavcan/uavcan_params.c +++ b/src/drivers/uavcan/uavcan_params.c @@ -107,6 +107,7 @@ PARAM_DEFINE_FLOAT(UAVCAN_RNG_MAX, 200.0f); * @unit liters * @decimal 1 * @increment 0.1 + * @reboot_required true * @group UAVCAN */ PARAM_DEFINE_FLOAT(UAVCAN_ECU_MAXF, 15.0f); @@ -125,6 +126,7 @@ PARAM_DEFINE_FLOAT(UAVCAN_ECU_MAXF, 15.0f); * @value 0 Unknown * @value 1 Liquid * @value 2 Gas + * @reboot_required true * @group UAVCAN */ PARAM_DEFINE_INT32(UAVCAN_ECU_FUELT, 1); From 8a08418a1f2a5e0fb3c2257f311c0088d50eefc9 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Mon, 17 Jun 2024 13:01:14 -0800 Subject: [PATCH 376/652] drivers/magnetometer: ist8310: more efficient probe() --- .../magnetometer/isentek/ist8310/IST8310.cpp | 28 ++++++++++++------- 1 file changed, 18 insertions(+), 10 deletions(-) diff --git a/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp b/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp index d48321d14845..e5baf14ac59c 100644 --- a/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp +++ b/src/drivers/magnetometer/isentek/ist8310/IST8310.cpp @@ -85,19 +85,27 @@ void IST8310::print_status() int IST8310::probe() { - // Apparently, the IST8310's WHOAMI register is writeable. Presumably, - // this can get corrupted by bus noise. It is only reset if powered off - // for 30s or by a reset. - // - // Therefore, we do a reset before doing the WHOAMI. - RegisterWrite(Register::CNTL2, CNTL2_BIT::SRST); + uint8_t id = RegisterRead(Register::WAI); - px4_usleep(10000); + if (id != Device_ID) { + DEVICE_DEBUG("unexpected WAI 0x%02x", id); - const uint8_t WAI = RegisterRead(Register::WAI); + // Apparently, the IST8310's WHOAMI register is writeable. Presumably, + // this can get corrupted by bus noise. It is only reset if powered off + // for 30s or by a reset. + RegisterWrite(Register::CNTL2, CNTL2_BIT::SRST); + + auto start_time = hrt_absolute_time(); + + while (hrt_elapsed_time(&start_time) < 50_ms) { + px4_usleep(10'000); + id = RegisterRead(Register::WAI); + + if (id == Device_ID) { + return PX4_OK; + } + } - if (WAI != Device_ID) { - DEVICE_DEBUG("unexpected WAI 0x%02x", WAI); return PX4_ERROR; } From 1bc006b4f5614d9bfa32e49c509e75e264187ede Mon Sep 17 00:00:00 2001 From: Sihyun Date: Mon, 13 May 2024 12:24:39 +0900 Subject: [PATCH 377/652] fmu-v6xrt: Fix redundant 'fi' --- boards/px4/fmu-v6xrt/init/rc.board_sensors | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/px4/fmu-v6xrt/init/rc.board_sensors b/boards/px4/fmu-v6xrt/init/rc.board_sensors index 8582c617a477..9271eab6549f 100644 --- a/boards/px4/fmu-v6xrt/init/rc.board_sensors +++ b/boards/px4/fmu-v6xrt/init/rc.board_sensors @@ -83,7 +83,6 @@ else fi fi fi -fi # Internal SPI bus ICM42686p (hard-mounted) icm42688p -6 -R 12 -b 1 -s start From ea72d56a00255ded237429b20995dbbfd98707b2 Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Mon, 17 Jun 2024 12:39:07 +0000 Subject: [PATCH 378/652] Update submodule gz to latest Mon Jun 17 12:39:07 UTC 2024 - gz in PX4/Firmware (0c18d43657b1b7279b8dce78a6014243cc14d1e2): https://github.com/PX4/PX4-gazebo-models/commit/d754381a1cecdd7f17050acd72bf5bf1327bced6 - gz current upstream: https://github.com/PX4/PX4-gazebo-models/commit/881558c8c274d0d9f21970de24333122e050b561 - Changes: https://github.com/PX4/PX4-gazebo-models/compare/d754381a1cecdd7f17050acd72bf5bf1327bced6...881558c8c274d0d9f21970de24333122e050b561 881558c 2024-05-29 Jacob Dahl - new lidar_v2 model and x500_lidar vehicle --- Tools/simulation/gz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/simulation/gz b/Tools/simulation/gz index d754381a1cec..881558c8c274 160000 --- a/Tools/simulation/gz +++ b/Tools/simulation/gz @@ -1 +1 @@ -Subproject commit d754381a1cecdd7f17050acd72bf5bf1327bced6 +Subproject commit 881558c8c274d0d9f21970de24333122e050b561 From 54c8f9e8c9e480d1c30c3df11ea2bf1a825998cb Mon Sep 17 00:00:00 2001 From: Jonas Eschmann Date: Thu, 21 Mar 2024 18:43:28 -0400 Subject: [PATCH 379/652] Adding vehicle_acceleration and actuator_motors to the logged topics for system identification --- src/modules/logger/logged_topics.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 26a7dfbfce9d..9452cebd2dfc 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -401,6 +401,8 @@ void LoggedTopics::add_system_identification_topics() add_topic("sensor_combined"); add_topic("vehicle_angular_velocity"); add_topic("vehicle_torque_setpoint"); + add_topic("vehicle_acceleration"); + add_topic("actuator_motors"); } void LoggedTopics::add_mavlink_tunnel() From 9c83f842bee11e3942e578377245b6a3fc9b5a7d Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 18 Jun 2024 09:32:51 +0200 Subject: [PATCH 380/652] autostart scripts: Reintroduce SYS_PARAM_VER (#22813) The case where the airframe maintainer wants to enforce a reset to airframe is not covered anymore with the `param set-default` mechanism. For products based on PX4 this is still required to ensure proper functionality after a major update. --- ROMFS/px4fmu_common/init.d/rcS | 26 +++++++++++++++++----- src/lib/systemlib/system_params.c | 13 +++++++++++ src/modules/mavlink/mavlink_parameters.cpp | 3 +++ 3 files changed, 37 insertions(+), 5 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 45efbfbc2b56..9986a3a75374 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -36,6 +36,12 @@ set SDCARD_FORMAT no set STARTUP_TUNE 1 set VEHICLE_TYPE none +# Airframe parameter versioning +# Value set to 1 by default but can optionally be overridden in the airframe configuration startup script. +# Airframe maintainers can ensure a reset to the airframe defaults during an update by increasing by one. +# e.g. add line "set PARAM_DEFAULTS_VER 2" in your airframe file to build the first update that enfoces a reset. +set PARAM_DEFAULTS_VER 1 + # # Print full system version. # @@ -182,13 +188,11 @@ else netman update -i eth0 fi - # - # If the airframe has been previously reset SYS_AUTCONFIG will have been set to 1 and other params will be reset on the next boot. - # + # To trigger a parameter reset during boot SYS_AUTCONFIG was set to 1 before if param greater SYS_AUTOCONFIG 0 then - # Reset params except Airframe, RC calibration, sensor calibration, flight modes, total flight time, and next flight UUID. - param reset_all SYS_AUTOSTART RC* CAL_* COM_FLTMODE* LND_FLIGHT* TC_* COM_FLIGHT* + # Reset parameters except airframe, parameter version, RC calibration, sensor calibration, flight modes, total flight time, flight UUID + param reset_all SYS_AUTOSTART SYS_PARAM_VER RC* CAL_* COM_FLTMODE* LND_FLIGHT* TC_* COM_FLIGHT* fi # @@ -233,6 +237,17 @@ else fi unset AUTOSTART_PATH + # Check parameter version and reset upon airframe configuration version mismatch. + # Reboot required because "param reset_all" would reset all "param set" lines from airframe. + if ! param compare SYS_PARAM_VER ${PARAM_DEFAULTS_VER} + then + echo "Switched to different parameter version. Resetting parameters." + param set SYS_PARAM_VER ${PARAM_DEFAULTS_VER} + param set SYS_AUTOCONFIG 1 + param save + reboot + fi + # # Start the tone_alarm driver. # Needs to be started after the parameters are loaded (for CBRK_BUZZER). @@ -598,6 +613,7 @@ unset LOGGER_ARGS unset LOGGER_BUF unset PARAM_FILE unset PARAM_BACKUP_FILE +unset PARAM_DEFAULTS_VER unset RC_INPUT_ARGS unset SDCARD_AVAILABLE unset SDCARD_EXT_PATH diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c index 23c0234380c9..1ca273be8473 100644 --- a/src/lib/systemlib/system_params.c +++ b/src/lib/systemlib/system_params.c @@ -83,6 +83,19 @@ PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0); */ PARAM_DEFINE_INT32(SYS_HITL, 0); +/** + * Parameter version + * + * This is used internally only: an airframe configuration might set an expected + * parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup + * against SYS_PARAM_VER, and if they do not match, parameters are reset and + * reloaded from the airframe configuration. + * + * @min 0 + * @group System + */ +PARAM_DEFINE_INT32(SYS_PARAM_VER, 1); + /** * Enable auto start of rate gyro thermal calibration at the next power up. * diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index d5d774696d68..2d8c47da823d 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -310,6 +310,9 @@ MavlinkParametersManager::send() param_find("TRIG_MODE"); param_find("UAVCAN_ENABLE"); + // parameter only used in startup script but should show on ground station + param_find("SYS_PARAM_VER"); + _first_send = true; } From 42cdf41d60d4c2f931887148eb5e1b5417d7b098 Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Tue, 18 Jun 2024 11:30:32 +0000 Subject: [PATCH 381/652] update all px4board kconfig --- boards/airmind/mindpx-v2/default.px4board | 2 +- boards/ark/fmu-v6x/default.px4board | 4 ++-- boards/ark/pi6x/default.px4board | 2 +- boards/beaglebone/blue/default.px4board | 1 - boards/bitcraze/crazyflie/default.px4board | 2 +- boards/cuav/nora/default.px4board | 2 +- boards/cuav/x7pro/default.px4board | 2 +- boards/emlid/navio2/default.px4board | 1 - boards/hkust/nxt-v1/default.px4board | 26 +++++----------------- boards/matek/h743/default.px4board | 2 +- boards/modalai/fc-v2/default.px4board | 3 +-- boards/modalai/voxl2-slpi/default.px4board | 4 ++-- boards/px4/fmu-v5/cryptotest.px4board | 1 - boards/px4/fmu-v5/debug.px4board | 1 - boards/px4/fmu-v5/default.px4board | 1 - boards/px4/fmu-v5/protected.px4board | 3 --- boards/px4/fmu-v5/rover.px4board | 1 - boards/px4/fmu-v5/stackcheck.px4board | 2 -- boards/px4/fmu-v5/test.px4board | 2 -- boards/px4/fmu-v5/uavcanv0periph.px4board | 3 --- boards/px4/fmu-v5x/rover.px4board | 1 - boards/siyi/n7/default.px4board | 2 +- 22 files changed, 18 insertions(+), 50 deletions(-) diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board index 5f4bcd2b0cfd..33ad75b6957b 100644 --- a/boards/airmind/mindpx-v2/default.px4board +++ b/boards/airmind/mindpx-v2/default.px4board @@ -10,9 +10,9 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 3433f245acc1..b75d468cfc03 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -8,21 +8,21 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3" CONFIG_DRIVERS_ADC_BOARD_ADC=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y -CONFIG_DRIVERS_IMU_MURATA_SCH16T=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y +CONFIG_DRIVERS_IMU_MURATA_SCH16T=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y CONFIG_COMMON_OPTICAL_FLOW=y diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 7d381c9f0730..4d07a0e8c44d 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -7,8 +7,8 @@ CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS2" CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP388=y -CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y diff --git a/boards/beaglebone/blue/default.px4board b/boards/beaglebone/blue/default.px4board index 34459e580634..79e0d80b9276 100644 --- a/boards/beaglebone/blue/default.px4board +++ b/boards/beaglebone/blue/default.px4board @@ -14,7 +14,6 @@ CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y -CONFIG_DRIVERS_LINUX_PWM_OUT=y CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y diff --git a/boards/bitcraze/crazyflie/default.px4board b/boards/bitcraze/crazyflie/default.px4board index 02b70b58c35d..9c90e55655c5 100644 --- a/boards/bitcraze/crazyflie/default.px4board +++ b/boards/bitcraze/crazyflie/default.px4board @@ -3,8 +3,8 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m4" CONFIG_BOARD_CONSTRAINED_FLASH=y CONFIG_BOARD_CONSTRAINED_MEMORY=y CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing" -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BAROMETER_LPS25H=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index 8c3e304856c3..20a306be6030 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -7,10 +7,10 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_COMMON_BAROMETERS=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index b2212d5f15f6..f72610fc65cf 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -6,11 +6,11 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/emlid/navio2/default.px4board b/boards/emlid/navio2/default.px4board index bc912f507ab9..722f42b410d0 100644 --- a/boards/emlid/navio2/default.px4board +++ b/boards/emlid/navio2/default.px4board @@ -15,7 +15,6 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y CONFIG_DRIVERS_IMU_ST_LSM9DS1=y -CONFIG_DRIVERS_LINUX_PWM_OUT=y CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y CONFIG_DRIVERS_MAGNETOMETER_LSM9DS1_MAG=y CONFIG_DRIVERS_RC_INPUT=y diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board index 6261079e0d9d..b72160775850 100644 --- a/boards/hkust/nxt-v1/default.px4board +++ b/boards/hkust/nxt-v1/default.px4board @@ -17,32 +17,25 @@ CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_BOSCH_BMI088=y -CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y -CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y -CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y CONFIG_DRIVERS_IRLOCK=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y CONFIG_COMMON_OPTICAL_FLOW=y CONFIG_DRIVERS_PWM_OUT=y -CONFIG_DRIVERS_PWM_OUT_SIM=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_ROBOCLAW=y -CONFIG_DRIVERS_RPM=y CONFIG_COMMON_TELEMETRY=y CONFIG_DRIVERS_TONE_ALARM=y -#CONFIG_DRIVERS_UAVCAN=y -#CONFIG_BOARD_UAVCAN_INTERFACES=1 -#CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y CONFIG_MODULES_BATTERY_STATUS=y CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_DATAMAN=y CONFIG_MODULES_EKF2=y -CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y CONFIG_MODULES_ESC_BATTERY=y CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y @@ -50,13 +43,13 @@ CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y -# CONFIG_MODULES_FW_POS_CONTROL_L1=y -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y @@ -66,18 +59,15 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y -CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_ROVER_POS_CONTROL=y -CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_SENSORS=y -CONFIG_MODULES_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y -CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y -CONFIG_SYSTEMCMDS_BL_UPDATE=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y CONFIG_SYSTEMCMDS_DMESG=y CONFIG_SYSTEMCMDS_DUMPFILE=y CONFIG_SYSTEMCMDS_GPIO=y @@ -85,13 +75,9 @@ CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y CONFIG_SYSTEMCMDS_I2CDETECT=y CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_MFT=y -CONFIG_SYSTEMCMDS_MIXER=y -CONFIG_SYSTEMCMDS_MOTOR_TEST=y -#CONFIG_SYSTEMCMDS_MTD=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y diff --git a/boards/matek/h743/default.px4board b/boards/matek/h743/default.px4board index dcd9fad5aef1..71024fea5ceb 100644 --- a/boards/matek/h743/default.px4board +++ b/boards/matek/h743/default.px4board @@ -7,8 +7,8 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_DPS310=y -CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index 15b94d5dc8c2..f95c859e8c52 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -10,9 +10,9 @@ CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y @@ -62,7 +62,6 @@ CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y -# CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y diff --git a/boards/modalai/voxl2-slpi/default.px4board b/boards/modalai/voxl2-slpi/default.px4board index 477ed59e73e5..db58d4e28a55 100644 --- a/boards/modalai/voxl2-slpi/default.px4board +++ b/boards/modalai/voxl2-slpi/default.px4board @@ -11,8 +11,8 @@ CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y -CONFIG_DRIVERS_RC_CRSF_RC=y CONFIG_DRIVERS_QSHELL_QURT=y +CONFIG_DRIVERS_RC_CRSF_RC=y CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_EKF2=y @@ -29,7 +29,7 @@ CONFIG_MODULES_MUORB_SLPI=y CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y -CONFIG_SYSTEMCMDS_UORB=y CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_UORB=y CONFIG_ORB_COMMUNICATOR=y CONFIG_PARAM_REMOTE=y diff --git a/boards/px4/fmu-v5/cryptotest.px4board b/boards/px4/fmu-v5/cryptotest.px4board index c023a5cb754c..831abbb824ab 100644 --- a/boards/px4/fmu-v5/cryptotest.px4board +++ b/boards/px4/fmu-v5/cryptotest.px4board @@ -1,5 +1,4 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_BOARD_CRYPTO=y CONFIG_DRIVERS_STUB_KEYSTORE=y CONFIG_DRIVERS_SW_CRYPTO=y diff --git a/boards/px4/fmu-v5/debug.px4board b/boards/px4/fmu-v5/debug.px4board index 99b978fc4af3..557590ea180f 100644 --- a/boards/px4/fmu-v5/debug.px4board +++ b/boards/px4/fmu-v5/debug.px4board @@ -22,7 +22,6 @@ CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_GIMBAL=n CONFIG_MODULES_GYRO_CALIBRATION=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_MODULES_TEMPERATURE_COMPENSATION=n diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index f2944c3e374b..1132a48bbfb4 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -62,7 +62,6 @@ CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y diff --git a/boards/px4/fmu-v5/protected.px4board b/boards/px4/fmu-v5/protected.px4board index fd3b7bb5222f..7ea307124c37 100644 --- a/boards/px4/fmu-v5/protected.px4board +++ b/boards/px4/fmu-v5/protected.px4board @@ -11,7 +11,6 @@ CONFIG_DRIVERS_IRLOCK=n CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_DRIVERS_PWM_INPUT=n CONFIG_DRIVERS_UAVCAN=n -CONFIG_EXAMPLES_FAKE_GPS=n CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n CONFIG_MODULES_CAMERA_FEEDBACK=n @@ -19,7 +18,6 @@ CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_MODULES_TEMPERATURE_COMPENSATION=n @@ -36,7 +34,6 @@ CONFIG_SYSTEMCMDS_LED_CONTROL=n CONFIG_SYSTEMCMDS_MTD=n CONFIG_SYSTEMCMDS_NSHTERM=n CONFIG_SYSTEMCMDS_REFLECT=n -CONFIG_SYSTEMCMDS_SD_BENCH=n CONFIG_SYSTEMCMDS_SYSTEM_TIME=n CONFIG_SYSTEMCMDS_USB_CONNECTED=n CONFIG_BOARD_PROTECTED=y diff --git a/boards/px4/fmu-v5/rover.px4board b/boards/px4/fmu-v5/rover.px4board index a0d173f4918d..92c265280ab9 100644 --- a/boards/px4/fmu-v5/rover.px4board +++ b/boards/px4/fmu-v5/rover.px4board @@ -7,7 +7,6 @@ CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n diff --git a/boards/px4/fmu-v5/stackcheck.px4board b/boards/px4/fmu-v5/stackcheck.px4board index 0dd66dc3e483..03acb1eef06f 100644 --- a/boards/px4/fmu-v5/stackcheck.px4board +++ b/boards/px4/fmu-v5/stackcheck.px4board @@ -22,7 +22,6 @@ CONFIG_DRIVERS_PWM_INPUT=n CONFIG_DRIVERS_SMART_BATTERY_BATMON=n CONFIG_DRIVERS_TONE_ALARM=n CONFIG_DRIVERS_UAVCAN=n -CONFIG_EXAMPLES_FAKE_GPS=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n CONFIG_MODULES_CAMERA_FEEDBACK=n CONFIG_MODULES_ESC_BATTERY=n @@ -30,7 +29,6 @@ CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_GIMBAL=n CONFIG_MODULES_GYRO_CALIBRATION=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n diff --git a/boards/px4/fmu-v5/test.px4board b/boards/px4/fmu-v5/test.px4board index 2dcd6925f2f3..ea3fa6bf0b06 100644 --- a/boards/px4/fmu-v5/test.px4board +++ b/boards/px4/fmu-v5/test.px4board @@ -9,10 +9,8 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n CONFIG_DRIVERS_IRLOCK=n CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_DRIVERS_UAVCAN=n -CONFIG_EXAMPLES_FAKE_GPS=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_BOARD_TESTING=y diff --git a/boards/px4/fmu-v5/uavcanv0periph.px4board b/boards/px4/fmu-v5/uavcanv0periph.px4board index c9e9823c036f..7b89c5f0c9bf 100644 --- a/boards/px4/fmu-v5/uavcanv0periph.px4board +++ b/boards/px4/fmu-v5/uavcanv0periph.px4board @@ -12,12 +12,10 @@ CONFIG_DRIVERS_IRLOCK=n CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_DRIVERS_PWM_INPUT=n CONFIG_DRIVERS_SMART_BATTERY_BATMON=n -CONFIG_EXAMPLES_FAKE_GPS=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n CONFIG_MODULES_CAMERA_FEEDBACK=n CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n @@ -31,7 +29,6 @@ CONFIG_SYSTEMCMDS_GPIO=n CONFIG_SYSTEMCMDS_I2CDETECT=n CONFIG_SYSTEMCMDS_LED_CONTROL=n CONFIG_SYSTEMCMDS_REFLECT=n -CONFIG_SYSTEMCMDS_SD_BENCH=n CONFIG_SYSTEMCMDS_SYSTEM_TIME=n CONFIG_SYSTEMCMDS_TOPIC_LISTENER=n CONFIG_BOARD_UAVCAN_PERIPHERALS="cuav_can-gps-v1_default" diff --git a/boards/px4/fmu-v5x/rover.px4board b/boards/px4/fmu-v5x/rover.px4board index 3e2b69dfac1b..738e6d9b0d0a 100644 --- a/boards/px4/fmu-v5x/rover.px4board +++ b/boards/px4/fmu-v5x/rover.px4board @@ -14,5 +14,4 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y CONFIG_MODULES_ROVER_ACKERMANN=y diff --git a/boards/siyi/n7/default.px4board b/boards/siyi/n7/default.px4board index 3364cf55f7be..2a7a23258186 100644 --- a/boards/siyi/n7/default.px4board +++ b/boards/siyi/n7/default.px4board @@ -8,9 +8,9 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y From ac13fb77a950ea6f96ac31f94548f7579035a347 Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Tue, 18 Jun 2024 11:55:22 +0000 Subject: [PATCH 382/652] boards: update all NuttX defconfigs --- boards/ark/pi6x/nuttx-config/nsh/defconfig | 4 -- .../nuttx-config/bootloader/defconfig | 8 +-- .../hkust/nxt-dual/nuttx-config/nsh/defconfig | 67 +++++++------------ .../nxt-v1/nuttx-config/bootloader/defconfig | 2 - .../hkust/nxt-v1/nuttx-config/nsh/defconfig | 53 +++++---------- .../h743/nuttx-config/bootloader/defconfig | 4 -- .../nuttx-config/nsh/defconfig | 6 +- .../fmu-v5/nuttx-config/stackcheck/defconfig | 2 - src/modules/zenoh/Kconfig.topics | 10 +++ 9 files changed, 58 insertions(+), 98 deletions(-) diff --git a/boards/ark/pi6x/nuttx-config/nsh/defconfig b/boards/ark/pi6x/nuttx-config/nsh/defconfig index 947fee32b15f..0e944e53c999 100644 --- a/boards/ark/pi6x/nuttx-config/nsh/defconfig +++ b/boards/ark/pi6x/nuttx-config/nsh/defconfig @@ -14,7 +14,6 @@ # CONFIG_MMCSD_SPI is not set # CONFIG_NSH_DISABLEBG is not set # CONFIG_NSH_DISABLESCRIPT is not set -# CONFIG_NSH_DISABLE_ARP is not set # CONFIG_NSH_DISABLE_CAT is not set # CONFIG_NSH_DISABLE_CD is not set # CONFIG_NSH_DISABLE_CP is not set @@ -37,7 +36,6 @@ # CONFIG_NSH_DISABLE_MKFATFS is not set # CONFIG_NSH_DISABLE_MOUNT is not set # CONFIG_NSH_DISABLE_MV is not set -# CONFIG_NSH_DISABLE_NSLOOKUP is not set # CONFIG_NSH_DISABLE_PS is not set # CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set # CONFIG_NSH_DISABLE_PWD is not set @@ -117,8 +115,6 @@ CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_INIT_ENTRYPOINT="nsh_main" CONFIG_INIT_STACKSIZE=3194 -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_THROTTLE=0 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 diff --git a/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig b/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig index 42a2a2bcf1f9..ea894db106e4 100644 --- a/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig +++ b/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig @@ -29,14 +29,12 @@ CONFIG_BOARD_INITTHREAD_PRIORITY=254 CONFIG_BOARD_LATE_INITIALIZE=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x004b CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 -#TODO:ally for VENDOR ID in the future CONFIG_CDCACM_VENDORID=0x3162 CONFIG_CDCACM_VENDORSTR="Matek" CONFIG_DEBUG_FULLOPT=y @@ -77,15 +75,15 @@ CONFIG_STM32H7_OTGFS=y CONFIG_STM32H7_PROGMEM=y CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y CONFIG_STM32H7_TIM1=y -CONFIG_STM32H7_USART6=y #debug port, can be modified to UART8 -CONFIG_USART6_RXBUFSIZE=600 -CONFIG_USART6_TXBUFSIZE=300 +CONFIG_STM32H7_USART6=y CONFIG_SYSTEMTICK_HOOK=y CONFIG_SYSTEM_CDCACM=y CONFIG_TASK_NAME_SIZE=24 CONFIG_TTY_SIGINT=y CONFIG_TTY_SIGINT_CHAR=0x03 CONFIG_TTY_SIGTSTP=y +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=300 CONFIG_USBDEV=y CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 diff --git a/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig b/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig index 8dc5c7cf5790..e1e35f96def1 100644 --- a/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig +++ b/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig @@ -73,7 +73,6 @@ CONFIG_BOARD_CRASHDUMP=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 CONFIG_BUILTIN=y -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x0036 @@ -82,12 +81,10 @@ CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 CONFIG_CDCACM_VENDORID=0x1B8C CONFIG_CDCACM_VENDORSTR="Matek" -CONFIG_CLOCK_MONOTONIC=y CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_HARDFAULT_ALERT=y CONFIG_DEBUG_MEMFAULT=y CONFIG_DEBUG_SYMBOLS=y -CONFIG_DEBUG_TCBINFO=n CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 CONFIG_DEV_PIPE_MAXSIZE=1024 @@ -114,10 +111,10 @@ CONFIG_HAVE_CXXINITIALIZE=y CONFIG_I2C=y CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=750 -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_NCHAINS=24 CONFIG_INIT_ENTRYPOINT="nsh_main" CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 @@ -129,7 +126,6 @@ CONFIG_MMCSD_SDIO=y CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y CONFIG_MM_IOB=y CONFIG_MM_REGIONS=4 -# Avaible in Dual Version TODO: MTD IO error CONFIG_MTD=y CONFIG_MTD_BYTE_WRITE=y CONFIG_MTD_PARTITION=y @@ -164,7 +160,6 @@ CONFIG_RAW_BINARY=y CONFIG_READLINE_CMD_HISTORY=y CONFIG_READLINE_TABCOMPLETION=y CONFIG_RTC_DATETIME=y -CONFIG_SCHED_ATEXIT=y CONFIG_SCHED_HPWORK=y CONFIG_SCHED_HPWORKPRIORITY=249 CONFIG_SCHED_HPWORKSTACKSIZE=1280 @@ -175,7 +170,6 @@ CONFIG_SCHED_LPWORK=y CONFIG_SCHED_LPWORKPRIORITY=50 CONFIG_SCHED_LPWORKSTACKSIZE=1632 CONFIG_SCHED_WAITPID=y -CONFIG_SDCLONE_DISABLE=y CONFIG_SDMMC1_SDIO_PULLUP=y CONFIG_SEM_PREALLOCHOLDERS=32 CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y @@ -191,7 +185,7 @@ CONFIG_START_MONTH=11 CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STM32H7_ADC1=y CONFIG_STM32H7_ADC2=y -CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae +CONFIG_STM32H7_ADC3=y CONFIG_STM32H7_BBSRAM=y CONFIG_STM32H7_BBSRAM_FILES=5 CONFIG_STM32H7_BDMA=y @@ -212,40 +206,28 @@ CONFIG_STM32H7_RTC_HSECLOCK=y CONFIG_STM32H7_RTC_MAGIC_REG=1 CONFIG_STM32H7_SAVE_CRASHDUMP=y CONFIG_STM32H7_SDMMC1=y -CONFIG_STM32H7_SDMMC1_DMA=y -CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024 CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y CONFIG_STM32H7_SPI1=y -# CONFIG_STM32H7_SPI1_DMA=y -# CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 CONFIG_STM32H7_SPI2=y CONFIG_STM32H7_SPI2_DMA=y CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 CONFIG_STM32H7_SPI3=y -# CONFIG_STM32H7_SPI3_DMA=y -# CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 CONFIG_STM32H7_SPI4=y -# CONFIG_STM32H7_SPI4_DMA=y -# CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 -CONFIG_STM32H7_SPI_DMA=y CONFIG_STM32H7_SPI_DMATHRESHOLD=8 CONFIG_STM32H7_TIM1=y CONFIG_STM32H7_TIM2=y CONFIG_STM32H7_TIM3=y CONFIG_STM32H7_TIM4=y -# CONFIG_STM32H7_TIM5=y -# CONFIG_STM32H7_TIM6=y -# CONFIG_STM32H7_TIM7=y CONFIG_STM32H7_TIM8=y -CONFIG_STM32H7_USART1=y #ttyS0 -CONFIG_STM32H7_USART2=y #ttyS1 -CONFIG_STM32H7_USART3=y #ttyS2 -CONFIG_STM32H7_UART4=y #ttyS3 -CONFIG_STM32H7_UART5=y #ttyS4 -CONFIG_STM32H7_USART6=y #ttyS5 NC -CONFIG_STM32H7_UART7=y #ttyS6 -CONFIG_STM32H7_UART8=y #ttyS7 +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y CONFIG_STM32H7_USART_BREAKS=y CONFIG_STM32H7_USART_INVERT=y CONFIG_STM32H7_USART_SINGLEWIRE=y @@ -253,36 +235,35 @@ CONFIG_STM32H7_USART_SWAP=y CONFIG_SYSTEM_CDCACM=y CONFIG_SYSTEM_NSH=y CONFIG_TASK_NAME_SIZE=24 -CONFIG_USART1_BAUD=57600 -CONFIG_USART1_RXBUFSIZE=600 -CONFIG_USART1_TXBUFSIZE=1500 -CONFIG_USART2_BAUD=57600 -CONFIG_USART2_RXBUFSIZE=600 -CONFIG_USART2_TXBUFSIZE=3000 -CONFIG_USART3_BAUD=57600 -CONFIG_USART3_RXBUFSIZE=180 -CONFIG_USART3_TXBUFSIZE=1500 CONFIG_UART4_BAUD=921600 CONFIG_UART4_RXBUFSIZE=3000 -CONFIG_UART4_TXBUFSIZE=3000 CONFIG_UART4_RXDMA=y +CONFIG_UART4_TXBUFSIZE=3000 CONFIG_UART4_TXDMA=y CONFIG_UART5_BAUD=57600 CONFIG_UART5_RXBUFSIZE=600 CONFIG_UART5_TXBUFSIZE=1500 -CONFIG_USART6_BAUD=57600 -CONFIG_USART6_RXBUFSIZE=180 -CONFIG_USART6_SERIAL_CONSOLE=y CONFIG_UART7_BAUD=57600 CONFIG_UART7_RXBUFSIZE=600 CONFIG_UART7_TXBUFSIZE=3000 CONFIG_UART8_BAUD=57600 CONFIG_UART8_RXBUFSIZE=600 CONFIG_UART8_TXBUFSIZE=3000 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=180 +CONFIG_USART6_SERIAL_CONSOLE=y CONFIG_USBDEV=y CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 CONFIG_USEC_PER_TICK=1000 -CONFIG_USERMAIN_STACKSIZE=2944 CONFIG_WATCHDOG=y CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig b/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig index e051eadacd4f..6cf4a40708fa 100644 --- a/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig +++ b/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig @@ -29,14 +29,12 @@ CONFIG_BOARD_INITTHREAD_PRIORITY=254 CONFIG_BOARD_LATE_INITIALIZE=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x004b CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 -#TODO:ally for VENDOR ID in the future CONFIG_CDCACM_VENDORID=0x3162 CONFIG_CDCACM_VENDORSTR="Matek" CONFIG_DEBUG_FULLOPT=y diff --git a/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig b/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig index 202258c5c6cc..21c65a81ee65 100644 --- a/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig +++ b/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig @@ -73,7 +73,6 @@ CONFIG_BOARD_CRASHDUMP=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 CONFIG_BUILTIN=y -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x0036 @@ -82,12 +81,10 @@ CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 CONFIG_CDCACM_VENDORID=0x1B8C CONFIG_CDCACM_VENDORSTR="Matek" -CONFIG_CLOCK_MONOTONIC=y CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_HARDFAULT_ALERT=y CONFIG_DEBUG_MEMFAULT=y CONFIG_DEBUG_SYMBOLS=y -CONFIG_DEBUG_TCBINFO=n CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 CONFIG_DEV_PIPE_MAXSIZE=1024 @@ -114,10 +111,10 @@ CONFIG_HAVE_CXXINITIALIZE=y CONFIG_I2C=y CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=750 -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_NCHAINS=24 CONFIG_INIT_ENTRYPOINT="nsh_main" CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 @@ -129,12 +126,6 @@ CONFIG_MMCSD_SDIO=y CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y CONFIG_MM_IOB=y CONFIG_MM_REGIONS=4 -# Avaible in Dual Version -# CONFIG_MTD=y -# CONFIG_MTD_BYTE_WRITE=y -# CONFIG_MTD_PARTITION=y -# CONFIG_MTD_PROGMEM=y -# CONFIG_MTD_RAMTRON=y CONFIG_NAME_MAX=40 CONFIG_NSH_ARCHINIT=y CONFIG_NSH_ARGCAT=y @@ -155,14 +146,12 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 -CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 CONFIG_RAW_BINARY=y CONFIG_READLINE_CMD_HISTORY=y CONFIG_READLINE_TABCOMPLETION=y CONFIG_RTC_DATETIME=y -CONFIG_SCHED_ATEXIT=y CONFIG_SCHED_HPWORK=y CONFIG_SCHED_HPWORKPRIORITY=249 CONFIG_SCHED_HPWORKSTACKSIZE=1280 @@ -173,7 +162,6 @@ CONFIG_SCHED_LPWORK=y CONFIG_SCHED_LPWORKPRIORITY=50 CONFIG_SCHED_LPWORKSTACKSIZE=1632 CONFIG_SCHED_WAITPID=y -CONFIG_SDCLONE_DISABLE=y CONFIG_SDMMC1_SDIO_PULLUP=y CONFIG_SEM_PREALLOCHOLDERS=32 CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y @@ -189,7 +177,7 @@ CONFIG_START_MONTH=11 CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STM32H7_ADC1=y CONFIG_STM32H7_ADC2=y -CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae +CONFIG_STM32H7_ADC3=y CONFIG_STM32H7_BBSRAM=y CONFIG_STM32H7_BBSRAM_FILES=5 CONFIG_STM32H7_BDMA=y @@ -210,8 +198,6 @@ CONFIG_STM32H7_RTC_HSECLOCK=y CONFIG_STM32H7_RTC_MAGIC_REG=1 CONFIG_STM32H7_SAVE_CRASHDUMP=y CONFIG_STM32H7_SDMMC1=y -CONFIG_STM32H7_SDMMC1_DMA=y -CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024 CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y CONFIG_STM32H7_SPI1=y @@ -223,19 +209,18 @@ CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 CONFIG_STM32H7_SPI3=y CONFIG_STM32H7_SPI3_DMA=y CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 -CONFIG_STM32H7_SPI_DMA=y CONFIG_STM32H7_SPI_DMATHRESHOLD=8 CONFIG_STM32H7_TIM1=y CONFIG_STM32H7_TIM3=y CONFIG_STM32H7_TIM4=y CONFIG_STM32H7_TIM5=y CONFIG_STM32H7_TIM8=y -CONFIG_STM32H7_USART1=y #ttyS0 -CONFIG_STM32H7_USART2=y #ttyS1 -CONFIG_STM32H7_USART3=y #ttyS2 -CONFIG_STM32H7_UART4=y #ttyS3 -CONFIG_STM32H7_UART5=y #ttyS4 -CONFIG_STM32H7_UART7=y #ttyS5 +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y CONFIG_STM32H7_USART_BREAKS=y CONFIG_STM32H7_USART_INVERT=y CONFIG_STM32H7_USART_SINGLEWIRE=y @@ -243,6 +228,15 @@ CONFIG_STM32H7_USART_SWAP=y CONFIG_SYSTEM_CDCACM=y CONFIG_SYSTEM_NSH=y CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=921600 +CONFIG_UART4_RXBUFSIZE=3000 +CONFIG_UART4_TXBUFSIZE=1200 +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=3000 CONFIG_USART1_BAUD=57600 CONFIG_USART1_RXBUFSIZE=600 CONFIG_USART1_TXBUFSIZE=1500 @@ -253,20 +247,9 @@ CONFIG_USART3_BAUD=57600 CONFIG_USART3_RXBUFSIZE=180 CONFIG_USART3_SERIAL_CONSOLE=y CONFIG_USART3_TXBUFSIZE=1500 -CONFIG_UART4_BAUD=921600 -CONFIG_UART4_RXBUFSIZE=3000 -CONFIG_UART4_TXBUFSIZE=1200 -CONFIG_UART5_BAUD=57600 -CONFIG_UART5_RXBUFSIZE=600 -CONFIG_UART5_TXBUFSIZE=1500 -CONFIG_UART7_BAUD=57600 -CONFIG_UART7_RXBUFSIZE=600 -CONFIG_UART7_TXBUFSIZE=3000 CONFIG_USBDEV=y CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 CONFIG_USEC_PER_TICK=1000 -CONFIG_USERMAIN_STACKSIZE=2944 -CONFIG_USER_ENTRYPOINT="nsh_main" CONFIG_WATCHDOG=y CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/micoair/h743/nuttx-config/bootloader/defconfig b/boards/micoair/h743/nuttx-config/bootloader/defconfig index 76254f132727..81e907784ecf 100644 --- a/boards/micoair/h743/nuttx-config/bootloader/defconfig +++ b/boards/micoair/h743/nuttx-config/bootloader/defconfig @@ -29,14 +29,12 @@ CONFIG_BOARD_INITTHREAD_PRIORITY=254 CONFIG_BOARD_LATE_INITIALIZE=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x004b CONFIG_CDCACM_PRODUCTSTR="MicoAir743" CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 -#TODO:ally for VENDOR ID in the future CONFIG_CDCACM_VENDORID=0x3162 CONFIG_CDCACM_VENDORSTR="MicoAir" CONFIG_DEBUG_FULLOPT=y @@ -61,7 +59,6 @@ CONFIG_PTHREAD_STACK_MIN=512 CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 CONFIG_RAW_BINARY=y -CONFIG_SERIAL_TERMIOS=y CONFIG_SIG_DEFAULT=y CONFIG_SIG_SIGALRM_ACTION=y CONFIG_SIG_SIGUSR1_ACTION=y @@ -75,7 +72,6 @@ CONFIG_STM32H7_BKPSRAM=y CONFIG_STM32H7_DMA1=y CONFIG_STM32H7_OTGFS=y CONFIG_STM32H7_PROGMEM=y -CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y CONFIG_STM32H7_TIM1=y CONFIG_SYSTEMTICK_HOOK=y CONFIG_SYSTEM_CDCACM=y diff --git a/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig index 7e56401723d0..1d75bb419dba 100644 --- a/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig @@ -219,12 +219,12 @@ CONFIG_STM32H7_TIM2=y CONFIG_STM32H7_TIM3=y CONFIG_STM32H7_TIM4=y CONFIG_STM32H7_TIM8=y -CONFIG_STM32H7_USART1=y -CONFIG_STM32H7_USART2=y -CONFIG_STM32H7_USART3=y CONFIG_STM32H7_UART4=y CONFIG_STM32H7_UART7=y CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y CONFIG_STM32H7_USART_BREAKS=y CONFIG_STM32H7_USART_INVERT=y CONFIG_STM32H7_USART_SINGLEWIRE=y diff --git a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig index 59fc09865501..8435ec217bce 100644 --- a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig @@ -116,7 +116,6 @@ CONFIG_INIT_STACKSIZE=3194 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 -CONFIG_LIBC_STRERROR=n CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y @@ -139,7 +138,6 @@ CONFIG_NSH_NESTDEPTH=8 CONFIG_NSH_QUOTE=y CONFIG_NSH_ROMFSETC=y CONFIG_NSH_ROMFSSECTSIZE=128 -CONFIG_NSH_STRERROR=y CONFIG_NSH_VARS=y CONFIG_OTG_ID_GPIO_DISABLE=y CONFIG_PIPES=y diff --git a/src/modules/zenoh/Kconfig.topics b/src/modules/zenoh/Kconfig.topics index 58e5e522cda7..e1c2ea4ada5b 100644 --- a/src/modules/zenoh/Kconfig.topics +++ b/src/modules/zenoh/Kconfig.topics @@ -245,6 +245,10 @@ menu "Zenoh publishers/subscribers" bool "follow_target_status" default n + config ZENOH_PUBSUB_FUEL_TANK_STATUS + bool "fuel_tank_status" + default n + config ZENOH_PUBSUB_GENERATOR_STATUS bool "generator_status" default n @@ -565,6 +569,10 @@ menu "Zenoh publishers/subscribers" bool "register_ext_component_request" default n + config ZENOH_PUBSUB_ROVER_ACKERMANN_GUIDANCE_STATUS + bool "rover_ackermann_guidance_status" + default n + config ZENOH_PUBSUB_RPM bool "rpm" default n @@ -919,6 +927,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_FOLLOW_TARGET select ZENOH_PUBSUB_FOLLOW_TARGET_ESTIMATOR select ZENOH_PUBSUB_FOLLOW_TARGET_STATUS + select ZENOH_PUBSUB_FUEL_TANK_STATUS select ZENOH_PUBSUB_GENERATOR_STATUS select ZENOH_PUBSUB_GEOFENCE_RESULT select ZENOH_PUBSUB_GEOFENCE_STATUS @@ -999,6 +1008,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_RC_PARAMETER_MAP select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REPLY select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REQUEST + select ZENOH_PUBSUB_ROVER_ACKERMANN_GUIDANCE_STATUS select ZENOH_PUBSUB_RPM select ZENOH_PUBSUB_RTL_STATUS select ZENOH_PUBSUB_RTL_TIME_ESTIMATE From 8b9900cce3f8e365039ae9fe80072be8ab425ec5 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 18 Jun 2024 11:47:19 -0400 Subject: [PATCH 383/652] mc_pos_control: new velocity low pass and notch filter (optional, disabled by default) - MPC_VEL_LP: new velocity first order low pass filter (off by default) - MPC_VEL_NF_FRQ/MPC_VEL_NF_BW: new velocity notch filter (off by default) - MPC_VELD_LP: existing velocity derivative low pass filter, but I've dropped the remaining controllib usage --- src/lib/mathlib/math/Functions.hpp | 5 + .../MulticopterPositionControl.cpp | 91 ++++++++++++++----- .../MulticopterPositionControl.hpp | 28 ++++-- .../multicopter_position_control_params.c | 49 +++++++++- 4 files changed, 141 insertions(+), 32 deletions(-) diff --git a/src/lib/mathlib/math/Functions.hpp b/src/lib/mathlib/math/Functions.hpp index 7fb54442d9b4..77cdb33c3475 100644 --- a/src/lib/mathlib/math/Functions.hpp +++ b/src/lib/mathlib/math/Functions.hpp @@ -290,6 +290,11 @@ inline bool isFinite(const float &value) return PX4_ISFINITE(value); } +inline bool isFinite(const matrix::Vector2f &value) +{ + return value.isAllFinite(); +} + inline bool isFinite(const matrix::Vector3f &value) { return value.isAllFinite(); diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.cpp b/src/modules/mc_pos_control/MulticopterPositionControl.cpp index 90928921835d..5f8e5f680b5e 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.cpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.cpp @@ -42,14 +42,11 @@ using namespace matrix; MulticopterPositionControl::MulticopterPositionControl(bool vtol) : - SuperBlock(nullptr, "MPC"), ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers), - _vehicle_attitude_setpoint_pub(vtol ? ORB_ID(mc_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)), - _vel_x_deriv(this, "VELD"), - _vel_y_deriv(this, "VELD"), - _vel_z_deriv(this, "VELD") + _vehicle_attitude_setpoint_pub(vtol ? ORB_ID(mc_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)) { + _sample_interval_s.update(0.01f); // 100 Hz default parameters_update(true); _tilt_limit_slew_rate.setSlewRate(.2f); _takeoff_status_pub.advertise(); @@ -83,7 +80,42 @@ void MulticopterPositionControl::parameters_update(bool force) // update parameters from storage ModuleParams::updateParams(); - SuperBlock::updateParams(); + + float sample_freq_hz = 1.f / _sample_interval_s.mean(); + + // velocity notch filter + if ((_param_mpc_vel_nf_frq.get() > 0.f) && (_param_mpc_vel_nf_bw.get() > 0.f)) { + _vel_xy_notch_filter.setParameters(sample_freq_hz, _param_mpc_vel_nf_frq.get(), _param_mpc_vel_nf_bw.get()); + _vel_z_notch_filter.setParameters(sample_freq_hz, _param_mpc_vel_nf_frq.get(), _param_mpc_vel_nf_bw.get()); + + } else { + _vel_xy_notch_filter.disable(); + _vel_z_notch_filter.disable(); + } + + // velocity xy/z low pass filter + if (_param_mpc_vel_lp.get() > 0.f) { + _vel_xy_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_vel_lp.get()); + _vel_z_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_vel_lp.get()); + + } else { + // disable filtering + _vel_xy_lp_filter.setAlpha(1.f); + _vel_z_lp_filter.setAlpha(1.f); + } + + // velocity derivative xy/z low pass filter + if (_param_mpc_veld_lp.get() > 0.f) { + _vel_deriv_xy_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_veld_lp.get()); + _vel_deriv_z_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_veld_lp.get()); + + } else { + // disable filtering + _vel_deriv_xy_lp_filter.setAlpha(1.f); + _vel_deriv_z_lp_filter.setAlpha(1.f); + } + + int num_changed = 0; @@ -276,7 +308,7 @@ void MulticopterPositionControl::parameters_update(bool force) } PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehicle_local_position_s - &vehicle_local_position) + &vehicle_local_position, const float dt_s) { PositionControlStates states; @@ -300,29 +332,42 @@ PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehic const Vector2f velocity_xy(vehicle_local_position.vx, vehicle_local_position.vy); if (vehicle_local_position.v_xy_valid && velocity_xy.isAllFinite()) { - states.velocity.xy() = velocity_xy; - states.acceleration(0) = _vel_x_deriv.update(velocity_xy(0)); - states.acceleration(1) = _vel_y_deriv.update(velocity_xy(1)); + const Vector2f vel_xy_prev = _vel_xy_lp_filter.getState(); + + // vel xy notch filter, then low pass filter + states.velocity.xy() = _vel_xy_lp_filter.update(_vel_xy_notch_filter.apply(velocity_xy)); + + // vel xy derivative low pass filter + states.acceleration.xy() = _vel_deriv_xy_lp_filter.update((_vel_xy_lp_filter.getState() - vel_xy_prev) / dt_s); } else { states.velocity(0) = states.velocity(1) = NAN; states.acceleration(0) = states.acceleration(1) = NAN; - // reset derivatives to prevent acceleration spikes when regaining velocity - _vel_x_deriv.reset(); - _vel_y_deriv.reset(); + // reset filters to prevent acceleration spikes when regaining velocity + _vel_xy_lp_filter.reset({}); + _vel_xy_notch_filter.reset(); + _vel_deriv_xy_lp_filter.reset({}); } if (PX4_ISFINITE(vehicle_local_position.vz) && vehicle_local_position.v_z_valid) { - states.velocity(2) = vehicle_local_position.vz; - states.acceleration(2) = _vel_z_deriv.update(states.velocity(2)); + + const float vel_z_prev = _vel_z_lp_filter.getState(); + + // vel z notch filter, then low pass filter + states.velocity(2) = _vel_z_lp_filter.update(_vel_z_notch_filter.apply(vehicle_local_position.vz)); + + // vel z derivative low pass filter + states.acceleration(2) = _vel_deriv_z_lp_filter.update((_vel_z_lp_filter.getState() - vel_z_prev) / dt_s); } else { states.velocity(2) = NAN; states.acceleration(2) = NAN; - // reset derivative to prevent acceleration spikes when regaining velocity - _vel_z_deriv.reset(); + // reset filters to prevent acceleration spikes when regaining velocity + _vel_z_lp_filter.reset({}); + _vel_z_notch_filter.reset(); + _vel_deriv_z_lp_filter.reset({}); } states.yaw = vehicle_local_position.heading; @@ -351,8 +396,7 @@ void MulticopterPositionControl::Run() math::constrain(((vehicle_local_position.timestamp_sample - _time_stamp_last_loop) * 1e-6f), 0.002f, 0.04f); _time_stamp_last_loop = vehicle_local_position.timestamp_sample; - // set _dt in controllib Block for BlockDerivative - setDt(dt); + _sample_interval_s.update(dt); if (_vehicle_control_mode_sub.updated()) { const bool previous_position_control_enabled = _vehicle_control_mode.flag_multicopter_position_control_enabled; @@ -380,7 +424,7 @@ void MulticopterPositionControl::Run() } } - PositionControlStates states{set_vehicle_states(vehicle_local_position)}; + PositionControlStates states{set_vehicle_states(vehicle_local_position, dt)}; // if a goto setpoint available this publishes a trajectory setpoint to go there if (_goto_control.checkForSetpoint(vehicle_local_position.timestamp_sample, @@ -638,12 +682,13 @@ void MulticopterPositionControl::adjustSetpointForEKFResets(const vehicle_local_ } if (vehicle_local_position.vxy_reset_counter != _vxy_reset_counter) { - _vel_x_deriv.reset(); - _vel_y_deriv.reset(); + _vel_xy_lp_filter.reset(_vel_xy_lp_filter.getState() + Vector2f(vehicle_local_position.delta_vxy)); + _vel_xy_notch_filter.reset(); } if (vehicle_local_position.vz_reset_counter != _vz_reset_counter) { - _vel_z_deriv.reset(); + _vel_z_lp_filter.reset(_vel_z_lp_filter.getState() + vehicle_local_position.delta_vz); + _vel_z_notch_filter.reset(); } // save latest reset counters diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.hpp b/src/modules/mc_pos_control/MulticopterPositionControl.hpp index 3dac59bc1b89..f7cd9bbbe09a 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.hpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.hpp @@ -42,7 +42,9 @@ #include "GotoControl/GotoControl.hpp" #include -#include +#include +#include +#include #include #include #include @@ -68,8 +70,8 @@ using namespace time_literals; -class MulticopterPositionControl : public ModuleBase, public control::SuperBlock, - public ModuleParams, public px4::ScheduledWorkItem +class MulticopterPositionControl : public ModuleBase, public ModuleParams, + public px4::ScheduledWorkItem { public: MulticopterPositionControl(bool vtol = false); @@ -148,6 +150,11 @@ class MulticopterPositionControl : public ModuleBase (ParamBool) _param_mpc_use_hte, (ParamBool) _param_mpc_acc_decouple, + (ParamFloat) _param_mpc_vel_lp, + (ParamFloat) _param_mpc_vel_nf_frq, + (ParamFloat) _param_mpc_vel_nf_bw, + (ParamFloat) _param_mpc_veld_lp, + // Takeoff / Land (ParamFloat) _param_com_spoolup_time, /**< time to let motors spool up after arming */ (ParamBool) _param_com_throw_en, /**< throw launch enabled */ @@ -185,9 +192,16 @@ class MulticopterPositionControl : public ModuleBase (ParamFloat) _param_mpc_yawrauto_acc ); - control::BlockDerivative _vel_x_deriv; /**< velocity derivative in x */ - control::BlockDerivative _vel_y_deriv; /**< velocity derivative in y */ - control::BlockDerivative _vel_z_deriv; /**< velocity derivative in z */ + math::WelfordMean _sample_interval_s{}; + + AlphaFilter _vel_xy_lp_filter{}; + AlphaFilter _vel_z_lp_filter{}; + + math::NotchFilter _vel_xy_notch_filter{}; + math::NotchFilter _vel_z_notch_filter{}; + + AlphaFilter _vel_deriv_xy_lp_filter{}; + AlphaFilter _vel_deriv_z_lp_filter{}; GotoControl _goto_control; ///< class for handling smooth goto position setpoints PositionControl _control; ///< class for core PID position control @@ -224,7 +238,7 @@ class MulticopterPositionControl : public ModuleBase /** * Check for validity of positon/velocity states. */ - PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos); + PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos, const float dt_s); /** * Generate setpoint to bridge no executable setpoint being available. diff --git a/src/modules/mc_pos_control/multicopter_position_control_params.c b/src/modules/mc_pos_control/multicopter_position_control_params.c index a8c00fb16738..94435b1b3352 100644 --- a/src/modules/mc_pos_control/multicopter_position_control_params.c +++ b/src/modules/mc_pos_control/multicopter_position_control_params.c @@ -75,11 +75,56 @@ PARAM_DEFINE_INT32(MPC_USE_HTE, 1); PARAM_DEFINE_FLOAT(MPC_THR_XY_MARG, 0.3f); /** - * Numerical velocity derivative low pass cutoff frequency + * Velocity low pass cutoff frequency + * + * A value of 0 disables the filter. + * + * @unit Hz + * @min 0 + * @max 50 + * @decimal 1 + * @increment 0.5 + * @group Multicopter Position Control + */ +PARAM_DEFINE_FLOAT(MPC_VEL_LP, 0.0f); + +/** + * Velocity notch filter frequency + * + * The center frequency for the 2nd order notch filter on the velocity. + * A value of 0 disables the filter. + * + * @unit Hz + * @min 0 + * @max 50 + * @decimal 1 + * @increment 0.5 + * @group Multicopter Position Control + */ +PARAM_DEFINE_FLOAT(MPC_VEL_NF_FRQ, 0.0f); + +/** + * Velocity notch filter bandwidth + * + * A value of 0 disables the filter. + * + * @unit Hz + * @min 0 + * @max 50 + * @decimal 1 + * @increment 0.5 + * @group Multicopter Position Control + */ +PARAM_DEFINE_FLOAT(MPC_VEL_NF_BW, 5.0f); + +/** + * Velocity derivative low pass cutoff frequency + * + * A value of 0 disables the filter. * * @unit Hz * @min 0 - * @max 10 + * @max 50 * @decimal 1 * @increment 0.5 * @group Multicopter Position Control From 38956e50cef7179f5f15a3bf860869b6f04f5c8f Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Tue, 18 Jun 2024 12:39:42 +0000 Subject: [PATCH 384/652] Update submodule mavlink to latest Tue Jun 18 12:39:42 UTC 2024 - mavlink in PX4/Firmware (7d9b119283b5aff3976431bd48e4308a0bce7b56): https://github.com/mavlink/mavlink/commit/9e0d01df69e2f659114070db5545a35ddf61cae8 - mavlink current upstream: https://github.com/mavlink/mavlink/commit/da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3 - Changes: https://github.com/mavlink/mavlink/compare/9e0d01df69e2f659114070db5545a35ddf61cae8...da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3 da3223ff 2024-06-13 Thomas Frans - gps: add status and integrity information (#2110) --- src/modules/mavlink/mavlink | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index 9e0d01df69e2..da3223ff9380 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit 9e0d01df69e2f659114070db5545a35ddf61cae8 +Subproject commit da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3 From 81f26be846499cc43172147d75809cbd1e030371 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 18 Jun 2024 13:55:02 -0400 Subject: [PATCH 385/652] Update submodule GPS drivers to latest Tue Jun 18 12:39:32 UTC 2024 - GPS drivers in PX4/Firmware (c29d189788090f6994e488f65789a8fe6b835d8d): https://github.com/PX4/PX4-GPSDrivers/commit/d92cf3a2b2704d5509b651bfca33cdfea3a7a18a - GPS drivers current upstream: https://github.com/PX4/PX4-GPSDrivers/commit/0b79ec4dbe3e5ac5925c011067e7e294033a0a32 - Changes: https://github.com/PX4/PX4-GPSDrivers/compare/d92cf3a2b2704d5509b651bfca33cdfea3a7a18a...0b79ec4dbe3e5ac5925c011067e7e294033a0a32 0b79ec4 2024-04-12 Thomas Frans - sbf: fix issue with automatic base config in QGC 5810dac 2024-04-12 Thomas Frans - style: add editorconfig file for consistent style 915024c 2024-03-26 Julian Oes - sbf: fix subsequent init in QGC 3ea1d76 2024-03-04 Julian Oes - sbf: don't foget to configure RTCM c6da592 2024-03-04 Julian Oes - sbf: don't change baudrate of USB port Co-authored-by: PX4 BuildBot --- src/drivers/gps/devices | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gps/devices b/src/drivers/gps/devices index d92cf3a2b270..0b79ec4dbe3e 160000 --- a/src/drivers/gps/devices +++ b/src/drivers/gps/devices @@ -1 +1 @@ -Subproject commit d92cf3a2b2704d5509b651bfca33cdfea3a7a18a +Subproject commit 0b79ec4dbe3e5ac5925c011067e7e294033a0a32 From 69a4a11c7ff9649dbd24ffdd6c228cf1385642fb Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 18 Jun 2024 18:43:16 -0400 Subject: [PATCH 386/652] boards: cuav/nora disable modules to fix flash overflow --- boards/cuav/nora/default.px4board | 4 ---- 1 file changed, 4 deletions(-) diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index 20a306be6030..675ffa54cb3e 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -39,7 +39,6 @@ CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_UAVCAN=y CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 CONFIG_MODULES_AIRSPEED_SELECTOR=y -CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y CONFIG_MODULES_BATTERY_STATUS=y CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_COMMANDER=y @@ -58,7 +57,6 @@ CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y -CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y @@ -70,7 +68,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y @@ -98,4 +95,3 @@ CONFIG_SYSTEMCMDS_UORB=y CONFIG_SYSTEMCMDS_USB_CONNECTED=y CONFIG_SYSTEMCMDS_VER=y CONFIG_SYSTEMCMDS_WORK_QUEUE=y -CONFIG_EXAMPLES_FAKE_GPS=y From e33ba810e9a56b043b98de13f4bccbe3de3ba549 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 18 Jun 2024 18:46:43 -0400 Subject: [PATCH 387/652] boards: px4_fmu-v5x_test disable differential_drive module to fix flash overflow --- boards/px4/fmu-v5x/test.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/px4/fmu-v5x/test.px4board b/boards/px4/fmu-v5x/test.px4board index 083f7e7e118e..9440ac8b271e 100644 --- a/boards/px4/fmu-v5x/test.px4board +++ b/boards/px4/fmu-v5x/test.px4board @@ -6,6 +6,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=n CONFIG_DRIVERS_CAMERA_TRIGGER=n CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n CONFIG_DRIVERS_IRLOCK=n +CONFIG_MODULES_DIFFERENTIAL_DRIVE=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_PAYLOAD_DELIVERER=n From c334e488e46acf949304279034607405451f94bc Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Tue, 18 Jun 2024 09:18:58 -0700 Subject: [PATCH 388/652] Changed Serial readAtLeast timeout from microseconds to milliseconds --- platforms/common/Serial.cpp | 4 ++-- platforms/common/include/px4_platform_common/Serial.hpp | 2 +- platforms/nuttx/src/px4/common/SerialImpl.cpp | 3 ++- platforms/posix/src/px4/common/SerialImpl.cpp | 3 ++- platforms/qurt/src/px4/SerialImpl.cpp | 3 ++- 5 files changed, 9 insertions(+), 6 deletions(-) diff --git a/platforms/common/Serial.cpp b/platforms/common/Serial.cpp index 9c957fde3747..ca338eb190e6 100644 --- a/platforms/common/Serial.cpp +++ b/platforms/common/Serial.cpp @@ -74,9 +74,9 @@ ssize_t Serial::read(uint8_t *buffer, size_t buffer_size) return _impl.read(buffer, buffer_size); } -ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms) { - return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_us); + return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_ms); } ssize_t Serial::write(const void *buffer, size_t buffer_size) diff --git a/platforms/common/include/px4_platform_common/Serial.hpp b/platforms/common/include/px4_platform_common/Serial.hpp index 8b2f5e8f1a06..fb45b5238502 100644 --- a/platforms/common/include/px4_platform_common/Serial.hpp +++ b/platforms/common/include/px4_platform_common/Serial.hpp @@ -62,7 +62,7 @@ class Serial bool close(); ssize_t read(uint8_t *buffer, size_t buffer_size); - ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); + ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_ms = 0); ssize_t write(const void *buffer, size_t buffer_size); diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index 19533659d01e..7fc5ea7520a2 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -251,7 +251,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) return ret; } -ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms) { if (!_open) { PX4_ERR("Cannot readAtLeast from serial device until it has been opened"); @@ -264,6 +264,7 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char } const hrt_abstime start_time_us = hrt_absolute_time(); + hrt_abstime timeout_us = timeout_ms * 1000; int total_bytes_read = 0; while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) { diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index f92e1e308f51..822ed4255ec0 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -244,7 +244,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) return ret; } -ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms) { if (!_open) { PX4_ERR("Cannot readAtLeast from serial device until it has been opened"); @@ -257,6 +257,7 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char } const hrt_abstime start_time_us = hrt_absolute_time(); + hrt_abstime timeout_us = timeout_ms * 1000; int total_bytes_read = 0; while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) { diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp index 294cf34daba0..73f8ce8cc4ba 100644 --- a/platforms/qurt/src/px4/SerialImpl.cpp +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -173,7 +173,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) return ret_read; } -ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us) +ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms) { if (!_open) { PX4_ERR("Cannot readAtLeast from serial device until it has been opened"); @@ -186,6 +186,7 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char } const hrt_abstime start_time_us = hrt_absolute_time(); + hrt_abstime timeout_us = timeout_ms * 1000; int total_bytes_read = 0; while (total_bytes_read < (int) character_count) { From 741c7ab610a6365abe6aced7d1f0ae192d660bcf Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 18 Jun 2024 21:03:27 -0400 Subject: [PATCH 389/652] Update submodule GPS drivers to latest Wed Jun 19 00:38:26 UTC 2024 - GPS drivers in PX4/Firmware (e5d44cc1ba691f075bc2bce52dea7ec88af9e6cd): https://github.com/PX4/PX4-GPSDrivers/commit/0b79ec4dbe3e5ac5925c011067e7e294033a0a32 - GPS drivers current upstream: https://github.com/PX4/PX4-GPSDrivers/commit/a41210ede8c2d22dd8e9fdcf388fca927c1fc5e1 - Changes: https://github.com/PX4/PX4-GPSDrivers/compare/0b79ec4dbe3e5ac5925c011067e7e294033a0a32...a41210ede8c2d22dd8e9fdcf388fca927c1fc5e1 a41210e 2024-06-18 Daniel Agar - sbf: fix code style --- src/drivers/gps/devices | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gps/devices b/src/drivers/gps/devices index 0b79ec4dbe3e..a41210ede8c2 160000 --- a/src/drivers/gps/devices +++ b/src/drivers/gps/devices @@ -1 +1 @@ -Subproject commit 0b79ec4dbe3e5ac5925c011067e7e294033a0a32 +Subproject commit a41210ede8c2d22dd8e9fdcf388fca927c1fc5e1 From e4fc3022f2f32d30aa324cb39fc7d2556d4325e4 Mon Sep 17 00:00:00 2001 From: fury1895 Date: Tue, 18 Jun 2024 10:20:17 +0200 Subject: [PATCH 390/652] gimbal - input_mavlink: return NoUpdate by default --- src/modules/gimbal/input_mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/gimbal/input_mavlink.cpp b/src/modules/gimbal/input_mavlink.cpp index 101ebf1e2716..ebfde30d2a73 100644 --- a/src/modules/gimbal/input_mavlink.cpp +++ b/src/modules/gimbal/input_mavlink.cpp @@ -518,7 +518,7 @@ InputMavlinkGimbalV2::update(unsigned int timeout_ms, ControlData &control_data, // We can't return early instead because we need to copy all topics that triggered poll. bool exit_loop = false; - UpdateResult update_result = already_active ? UpdateResult::UpdatedActive : UpdateResult::NoUpdate; + UpdateResult update_result = UpdateResult::NoUpdate; while (!exit_loop && poll_timeout >= 0) { From dcb1103299a66e1d3b2ffc24cd3801cb3c654fb4 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 17 Jun 2024 18:09:48 -0400 Subject: [PATCH 391/652] ekf2: move estimator_status test ratios to filtered values --- Tools/ecl_ekf/plotting/pdf_report.py | 2 +- .../scripts/itcm_functions_includes.ld | 1 - msg/EstimatorStatus.msg | 27 +--- .../aux_global_position.cpp | 2 + .../aux_global_position.hpp | 4 + src/modules/ekf2/EKF/ekf.h | 18 ++- src/modules/ekf2/EKF/ekf_helper.cpp | 153 +++++++++++++----- src/modules/ekf2/EKF2.cpp | 16 +- src/modules/mavlink/streams/HIGH_LATENCY2.hpp | 3 +- 9 files changed, 142 insertions(+), 84 deletions(-) diff --git a/Tools/ecl_ekf/plotting/pdf_report.py b/Tools/ecl_ekf/plotting/pdf_report.py index db5d4fdd508a..029589ba56ed 100644 --- a/Tools/ecl_ekf/plotting/pdf_report.py +++ b/Tools/ecl_ekf/plotting/pdf_report.py @@ -223,7 +223,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str data_plot.save() data_plot.close() - # plot innovation_check_flags summary + # plot innovation flags summary data_plot = CheckFlagsPlot( status_flags_time, estimator_status_flags, [['reject_hor_vel', 'reject_hor_pos'], ['reject_ver_vel', 'reject_ver_pos', 'reject_hagl'], 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 477cc835bafb..2b32ba473ac3 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 @@ -154,7 +154,6 @@ *(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE) *(.text._ZN9Commander13dataLinkCheckEv) *(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex) -*(.text._ZNK3Ekf26get_innovation_test_statusERtRfS1_S1_S1_S1_S1_S1_) *(.text._ZN12PX4Gyroscope9set_scaleEf) *(.text._ZN12FailsafeBase6updateERKyRKNS_5StateEbbRK16failsafe_flags_s) *(.text._ZN18MavlinkStreamDebug4sendEv) diff --git a/msg/EstimatorStatus.msg b/msg/EstimatorStatus.msg index 5491734b1d8e..ac13b59ea7ee 100644 --- a/msg/EstimatorStatus.msg +++ b/msg/EstimatorStatus.msg @@ -69,27 +69,14 @@ uint32 filter_fault_flags # Bitmask to indicate EKF internal faults float32 pos_horiz_accuracy # 1-Sigma estimated horizontal position accuracy relative to the estimators origin (m) float32 pos_vert_accuracy # 1-Sigma estimated vertical position accuracy relative to the estimators origin (m) -uint16 innovation_check_flags # Bitmask to indicate pass/fail status of innovation consistency checks -# 0 - true if velocity observations have been rejected -# 1 - true if horizontal position observations have been rejected -# 2 - true if true if vertical position observations have been rejected -# 3 - true if the X magnetometer observation has been rejected -# 4 - true if the Y magnetometer observation has been rejected -# 5 - true if the Z magnetometer observation has been rejected -# 6 - true if the yaw observation has been rejected -# 7 - true if the airspeed observation has been rejected -# 8 - true if the synthetic sideslip observation has been rejected -# 9 - true if the height above ground observation has been rejected -# 10 - true if the X optical flow observation has been rejected -# 11 - true if the Y optical flow observation has been rejected -float32 mag_test_ratio # ratio of the largest magnetometer innovation component to the innovation test limit -float32 vel_test_ratio # ratio of the largest velocity innovation component to the innovation test limit -float32 pos_test_ratio # ratio of the largest horizontal position innovation component to the innovation test limit -float32 hgt_test_ratio # ratio of the vertical position innovation to the innovation test limit -float32 tas_test_ratio # ratio of the true airspeed innovation to the innovation test limit -float32 hagl_test_ratio # ratio of the height above ground innovation to the innovation test limit -float32 beta_test_ratio # ratio of the synthetic sideslip innovation to the innovation test limit +float32 mag_test_ratio # low-pass filtered ratio of the largest magnetometer innovation component to the innovation test limit +float32 vel_test_ratio # low-pass filtered ratio of the largest velocity innovation component to the innovation test limit +float32 pos_test_ratio # low-pass filtered ratio of the largest horizontal position innovation component to the innovation test limit +float32 hgt_test_ratio # low-pass filtered ratio of the vertical position innovation to the innovation test limit +float32 tas_test_ratio # low-pass filtered ratio of the true airspeed innovation to the innovation test limit +float32 hagl_test_ratio # low-pass filtered ratio of the height above ground innovation to the innovation test limit +float32 beta_test_ratio # low-pass filtered ratio of the synthetic sideslip innovation to the innovation test limit uint16 solution_status_flags # Bitmask indicating which filter kinematic state outputs are valid for flight control use. # 0 - True if the attitude estimate is good 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 15be1c3ce6b4..fe313315b597 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 @@ -151,6 +151,8 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed #if defined(MODULE_NAME) aid_src.timestamp = hrt_absolute_time(); _estimator_aid_src_aux_global_position_pub.publish(aid_src); + + _test_ratio_filtered = math::max(fabsf(aid_src.test_ratio_filtered[0]), fabsf(aid_src.test_ratio_filtered[1])); #endif // MODULE_NAME } else if ((_state != State::stopped) && isTimedOut(_time_last_buffer_push, imu_delayed.time_us, (uint64_t)5e6)) { diff --git a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp index 056840c033c7..bd63f7245605 100644 --- a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp +++ b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp @@ -74,6 +74,8 @@ class AuxGlobalPosition : public ModuleParams updateParams(); } + float test_ratio_filtered() const { return _test_ratio_filtered; } + private: bool isTimedOut(uint64_t last_sensor_timestamp, uint64_t time_delayed_us, uint64_t timeout_period) const { @@ -106,6 +108,8 @@ class AuxGlobalPosition : public ModuleParams State _state{State::stopped}; + float _test_ratio_filtered{INFINITY}; + #if defined(MODULE_NAME) struct reset_counters_s { uint8_t lat_lon{}; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index bf62b542f42c..88789fa1b2f6 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -383,13 +383,17 @@ class Ekf final : public EstimatorInterface *counter = _state_reset_status.reset_count.quat; } - // get EKF innovation consistency check status information comprising of: - // status - a bitmask integer containing the pass/fail status for each EKF measurement innovation consistency check - // Innovation Test Ratios - these are the ratio of the innovation to the acceptance threshold. - // A value > 1 indicates that the sensor measurement has exceeded the maximum acceptable level and has been rejected by the EKF - // Where a measurement type is a vector quantity, eg magnetometer, GPS position, etc, the maximum value is returned. - void get_innovation_test_status(uint16_t &status, float &mag, float &vel, float &pos, float &hgt, float &tas, - float &hagl, float &beta) const; + float getHeadingInnovationTestRatio() const; + + float getVelocityInnovationTestRatio() const; + + float getHorizontalPositionInnovationTestRatio() const; + float getVerticalPositionInnovationTestRatio() const; + + float getAirspeedInnovationTestRatio() const; + float getSyntheticSideslipInnovationTestRatio() const; + + float getHeightAboveGroundInnovationTestRatio() const; // return a bitmask integer that describes which state estimates are valid void get_ekf_soln_status(uint16_t *status) const; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 7b6b0b0cace7..ab416d81da4c 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -301,131 +301,196 @@ void Ekf::resetAccelBias() resetAccelBiasCov(); } -void Ekf::get_innovation_test_status(uint16_t &status, float &mag, float &vel, float &pos, float &hgt, float &tas, - float &hagl, float &beta) const +float Ekf::getHeadingInnovationTestRatio() const { - // return the integer bitmask containing the consistency check pass/fail status - status = _innov_check_fail_status.value; - - // return the largest magnetometer innovation test ratio - mag = 0.f; + // return the largest heading innovation test ratio + float test_ratio = 0.f; #if defined(CONFIG_EKF2_MAGNETOMETER) if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) { - mag = math::max(mag, sqrtf(Vector3f(_aid_src_mag.test_ratio).max())); + for (auto &test_ratio_filtered : _aid_src_mag.test_ratio_filtered) { + test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); + } } #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_GNSS_YAW) if (_control_status.flags.gps_yaw) { - mag = math::max(mag, sqrtf(_aid_src_gnss_yaw.test_ratio)); + test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_yaw.test_ratio_filtered)); } #endif // CONFIG_EKF2_GNSS_YAW #if defined(CONFIG_EKF2_EXTERNAL_VISION) if (_control_status.flags.ev_yaw) { - mag = math::max(mag, sqrtf(_aid_src_ev_yaw.test_ratio)); + test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_yaw.test_ratio_filtered)); } #endif // CONFIG_EKF2_EXTERNAL_VISION - // return the largest velocity and position innovation test ratio - vel = NAN; - pos = NAN; + return sqrtf(test_ratio); +} + +float Ekf::getVelocityInnovationTestRatio() const +{ + // return the largest velocity innovation test ratio + float test_ratio = -1.f; #if defined(CONFIG_EKF2_GNSS) if (_control_status.flags.gps) { - float gps_vel = sqrtf(Vector3f(_aid_src_gnss_vel.test_ratio).max()); - vel = math::max(gps_vel, FLT_MIN); - - float gps_pos = sqrtf(Vector2f(_aid_src_gnss_pos.test_ratio).max()); - pos = math::max(gps_pos, FLT_MIN); + for (int i = 0; i < 3; i++) { + test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_vel.test_ratio_filtered[i])); + } } #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_EXTERNAL_VISION) if (_control_status.flags.ev_vel) { - float ev_vel = sqrtf(Vector3f(_aid_src_ev_vel.test_ratio).max()); - vel = math::max(vel, ev_vel, FLT_MIN); - } - - if (_control_status.flags.ev_pos) { - float ev_pos = sqrtf(Vector2f(_aid_src_ev_pos.test_ratio).max()); - pos = math::max(pos, ev_pos, FLT_MIN); + for (int i = 0; i < 3; i++) { + test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_vel.test_ratio_filtered[i])); + } } #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_OPTICAL_FLOW) if (isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)) { - float of_vel = sqrtf(Vector2f(_aid_src_optical_flow.test_ratio).max()); - vel = math::max(of_vel, FLT_MIN); + for (auto &test_ratio_filtered : _aid_src_optical_flow.test_ratio_filtered) { + test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); + } } #endif // CONFIG_EKF2_OPTICAL_FLOW + if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { + return sqrtf(test_ratio); + } + + return NAN; +} + +float Ekf::getHorizontalPositionInnovationTestRatio() const +{ + // return the largest position innovation test ratio + float test_ratio = -1.f; + +#if defined(CONFIG_EKF2_GNSS) + if (_control_status.flags.gps) { + for (auto &test_ratio_filtered : _aid_src_gnss_pos.test_ratio_filtered) { + test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); + } + } +#endif // CONFIG_EKF2_GNSS + +#if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_pos) { + for (auto &test_ratio_filtered : _aid_src_ev_pos.test_ratio_filtered) { + test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); + } + } +#endif // CONFIG_EKF2_EXTERNAL_VISION + +#if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME) + if (_control_status.flags.aux_gpos) { + test_ratio = math::max(test_ratio, fabsf(_aux_global_position.test_ratio_filtered())); + } +#endif // CONFIG_EKF2_AUX_GLOBAL_POSITION + + if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { + return sqrtf(test_ratio); + } + + return NAN; +} + +float Ekf::getVerticalPositionInnovationTestRatio() const +{ // return the combined vertical position innovation test ratio float hgt_sum = 0.f; int n_hgt_sources = 0; #if defined(CONFIG_EKF2_BAROMETER) if (_control_status.flags.baro_hgt) { - hgt_sum += sqrtf(_aid_src_baro_hgt.test_ratio); + hgt_sum += sqrtf(fabsf(_aid_src_baro_hgt.test_ratio_filtered)); n_hgt_sources++; } #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_GNSS) if (_control_status.flags.gps_hgt) { - hgt_sum += sqrtf(_aid_src_gnss_hgt.test_ratio); + hgt_sum += sqrtf(fabsf(_aid_src_gnss_hgt.test_ratio_filtered)); n_hgt_sources++; } #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_RANGE_FINDER) if (_control_status.flags.rng_hgt) { - hgt_sum += sqrtf(_aid_src_rng_hgt.test_ratio); + hgt_sum += sqrtf(fabsf(_aid_src_rng_hgt.test_ratio_filtered)); n_hgt_sources++; } #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_EXTERNAL_VISION) if (_control_status.flags.ev_hgt) { - hgt_sum += sqrtf(_aid_src_ev_hgt.test_ratio); + hgt_sum += sqrtf(fabsf(_aid_src_ev_hgt.test_ratio_filtered)); n_hgt_sources++; } #endif // CONFIG_EKF2_EXTERNAL_VISION if (n_hgt_sources > 0) { - hgt = math::max(hgt_sum / static_cast(n_hgt_sources), FLT_MIN); - - } else { - hgt = NAN; + return math::max(hgt_sum / static_cast(n_hgt_sources), FLT_MIN); } + return NAN; +} + +float Ekf::getAirspeedInnovationTestRatio() const +{ #if defined(CONFIG_EKF2_AIRSPEED) - // return the airspeed fusion innovation test ratio - tas = sqrtf(_aid_src_airspeed.test_ratio); + if (_control_status.flags.fuse_aspd) { + // return the airspeed fusion innovation test ratio + return sqrtf(fabsf(_aid_src_airspeed.test_ratio_filtered)); + } #endif // CONFIG_EKF2_AIRSPEED - hagl = NAN; + return NAN; +} + +float Ekf::getSyntheticSideslipInnovationTestRatio() const +{ +#if defined(CONFIG_EKF2_SIDESLIP) + if (_control_status.flags.fuse_beta) { + // return the synthetic sideslip innovation test ratio + return sqrtf(fabsf(_aid_src_sideslip.test_ratio_filtered)); + } +#endif // CONFIG_EKF2_SIDESLIP + + return NAN; +} + +float Ekf::getHeightAboveGroundInnovationTestRatio() const +{ + float test_ratio = -1.f; + #if defined(CONFIG_EKF2_TERRAIN) # if defined(CONFIG_EKF2_RANGE_FINDER) if (_hagl_sensor_status.flags.range_finder) { // return the terrain height innovation test ratio - hagl = sqrtf(_aid_src_terrain_range_finder.test_ratio); + test_ratio = math::max(test_ratio, fabsf(_aid_src_terrain_range_finder.test_ratio_filtered)); } #endif // CONFIG_EKF2_RANGE_FINDER # if defined(CONFIG_EKF2_OPTICAL_FLOW) if (_hagl_sensor_status.flags.flow) { // return the terrain height innovation test ratio - hagl = sqrtf(math::max(_aid_src_terrain_optical_flow.test_ratio[0], _aid_src_terrain_optical_flow.test_ratio[1])); + for (auto &test_ratio_filtered : _aid_src_terrain_optical_flow.test_ratio_filtered) { + test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); + } } # endif // CONFIG_EKF2_OPTICAL_FLOW #endif // CONFIG_EKF2_TERRAIN -#if defined(CONFIG_EKF2_SIDESLIP) - // return the synthetic sideslip innovation test ratio - beta = sqrtf(_aid_src_sideslip.test_ratio); -#endif // CONFIG_EKF2_SIDESLIP + if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { + return sqrtf(test_ratio); + } + + return NAN; } void Ekf::get_ekf_soln_status(uint16_t *status) const diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 2d15b7262cc9..166293453a1d 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1802,15 +1802,13 @@ void EKF2::PublishStatus(const hrt_abstime ×tamp) status.control_mode_flags = _ekf.control_status().value; status.filter_fault_flags = _ekf.fault_status().value; - uint16_t innov_check_flags_temp = 0; - _ekf.get_innovation_test_status(innov_check_flags_temp, status.mag_test_ratio, - status.vel_test_ratio, status.pos_test_ratio, - status.hgt_test_ratio, status.tas_test_ratio, - status.hagl_test_ratio, status.beta_test_ratio); - - // Bit mismatch between ecl and Firmware, combine the 2 first bits to preserve msg definition - // TODO: legacy use only, those flags are also in estimator_status_flags - status.innovation_check_flags = (innov_check_flags_temp >> 1) | (innov_check_flags_temp & 0x1); + status.mag_test_ratio = _ekf.getHeadingInnovationTestRatio(); + status.vel_test_ratio = _ekf.getVelocityInnovationTestRatio(); + status.pos_test_ratio = _ekf.getHorizontalPositionInnovationTestRatio(); + status.hgt_test_ratio = _ekf.getVerticalPositionInnovationTestRatio(); + status.tas_test_ratio = _ekf.getAirspeedInnovationTestRatio(); + status.hagl_test_ratio = _ekf.getHeightAboveGroundInnovationTestRatio(); + status.beta_test_ratio = _ekf.getSyntheticSideslipInnovationTestRatio(); _ekf.get_ekf_lpos_accuracy(&status.pos_horiz_accuracy, &status.pos_vert_accuracy); _ekf.get_ekf_soln_status(&status.solution_status_flags); diff --git a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp index 6ce85a2e7583..32d244b138da 100644 --- a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp +++ b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp @@ -309,8 +309,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream if (_estimator_status_sub.update(&estimator_status)) { if (estimator_status.gps_check_fail_flags > 0 || - estimator_status.filter_fault_flags > 0 || - estimator_status.innovation_check_flags > 0) { + estimator_status.filter_fault_flags > 0) { msg->failure_flags |= HL_FAILURE_FLAG_ESTIMATOR; } From 30ce560e3a406fd0084ae52e6ce0d9ef36f4cd3d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 20 Jun 2024 13:38:28 -0400 Subject: [PATCH 392/652] ekf2: mag control reset filtered test ratio on start (if aligning yaw) --- src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 1 + 1 file changed, 1 insertion(+) 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 8bf976b8fa5e..74d017add5f9 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -245,6 +245,7 @@ void Ekf::controlMagFusion() if (reset_heading) { _control_status.flags.yaw_align = true; + resetAidSourceStatusZeroInnovation(aid_src); } _control_status.flags.mag = true; From 8cc7c99b591b0369baa35ef42273f10d894c026e Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 24 Jun 2024 10:00:03 +0200 Subject: [PATCH 393/652] mavlink: report generator error (#23313) Without this flag the command silently succeeds even though the logs contains an error. It's much more developer friendly to fail early in case of an error. The log path is then also shown in the console output. --- src/modules/mavlink/CMakeLists.txt | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index d295d43744bf..3038a0f705cc 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -44,8 +44,7 @@ add_custom_command( COMMAND ${PYTHON_EXECUTABLE} ${MAVLINK_GIT_DIR}/pymavlink/tools/mavgen.py --lang C --wire-protocol 2.0 - #--no-validate - #--strict-units + --exit-code --output ${MAVLINK_LIBRARY_DIR} ${MAVLINK_GIT_DIR}/message_definitions/v1.0/${MAVLINK_DIALECT_UAVIONIX}.xml > ${CMAKE_CURRENT_BINARY_DIR}/mavgen_${MAVLINK_DIALECT_UAVIONIX}.log DEPENDS @@ -64,8 +63,7 @@ add_custom_command( COMMAND ${PYTHON_EXECUTABLE} ${MAVLINK_GIT_DIR}/pymavlink/tools/mavgen.py --lang C --wire-protocol 2.0 - #--no-validate - #--strict-units + --exit-code --output ${MAVLINK_LIBRARY_DIR} ${MAVLINK_GIT_DIR}/message_definitions/v1.0/${CONFIG_MAVLINK_DIALECT}.xml > ${CMAKE_CURRENT_BINARY_DIR}/mavgen_${CONFIG_MAVLINK_DIALECT}.log DEPENDS From e8e8a60ca8744e7ac35484e4ecfbe87083fd73f1 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 21 Jun 2024 03:55:36 -0700 Subject: [PATCH 394/652] NuttX with backport of stm32h7 No phy --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index f6ecf7c5664e..9583e2d9cec7 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit f6ecf7c5664e2beb155d3eb5df07cf837013d73c +Subproject commit 9583e2d9cec78c45a183d764a2fa206756ee3a3f From 6fd0e98a69cfe2058bb1bb111f58323c917c7f95 Mon Sep 17 00:00:00 2001 From: Nate <76884910+n-snyder@users.noreply.github.com> Date: Fri, 21 Jun 2024 08:09:18 -0400 Subject: [PATCH 395/652] Correct units of CRSF GPS altitude Bug fix to correct returning mm units of altitude to m. --- src/drivers/rc/crsf_rc/CrsfRc.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/rc/crsf_rc/CrsfRc.cpp b/src/drivers/rc/crsf_rc/CrsfRc.cpp index 42b61ea66ff6..119e24b07ca4 100644 --- a/src/drivers/rc/crsf_rc/CrsfRc.cpp +++ b/src/drivers/rc/crsf_rc/CrsfRc.cpp @@ -241,7 +241,7 @@ void CrsfRc::Run() int32_t longitude = static_cast(round(sensor_gps.longitude_deg * 1e7)); uint16_t groundspeed = sensor_gps.vel_d_m_s / 3.6f * 10.f; uint16_t gps_heading = math::degrees(sensor_gps.cog_rad) * 100.f; - uint16_t altitude = static_cast(sensor_gps.altitude_msl_m * 1e3) + 1000; + uint16_t altitude = static_cast(sensor_gps.altitude_msl_m) + 1000; uint8_t num_satellites = sensor_gps.satellites_used; this->SendTelemetryGps(latitude, longitude, groundspeed, gps_heading, altitude, num_satellites); } From 09f066a73ae1eb9e1d39afc1c444a1f3264b0a17 Mon Sep 17 00:00:00 2001 From: KonradRudin <98741601+KonradRudin@users.noreply.github.com> Date: Tue, 25 Jun 2024 16:33:45 +0200 Subject: [PATCH 396/652] mission: skip a vtol takoff mission item if already in air (#23319) * mission: skip a vtol takoff mission item if already in air and a fixed wing * MissionBase: also skip FW takeoff when already in-air Signed-off-by: Silvan Fuhrer * mission: use setNextMissionItem to skip vtol takeoff when already in air * mission: Only skip the VTOL takeoff in air for mission and rtl mission If flying RTL mission reverse it must still include the takeoff point. --------- Signed-off-by: Silvan Fuhrer Co-authored-by: Silvan Fuhrer --- src/modules/navigator/mission.cpp | 17 +++++++++++++++++ src/modules/navigator/rtl_mission_fast.cpp | 17 +++++++++++++++++ 2 files changed, 34 insertions(+) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 06b4151bdb9b..2949c88d62b3 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -216,6 +216,23 @@ void Mission::setActiveMissionItems() position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); const position_setpoint_s current_setpoint_copy = pos_sp_triplet->current; + /* Skip VTOL/FW Takeoff item if in air, fixed-wing and didn't start the takeoff already*/ + if ((_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF || _mission_item.nav_cmd == NAV_CMD_TAKEOFF) && + (_work_item_type == WorkItemType::WORK_ITEM_TYPE_DEFAULT) && + (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) && + !_land_detected_sub.get().landed) { + if (setNextMissionItem()) { + if (!loadCurrentMissionItem()) { + setEndOfMissionItems(); + return; + } + + } else { + setEndOfMissionItems(); + return; + } + } + if (item_contains_position(_mission_item)) { handleTakeoff(new_work_item_type, next_mission_items, num_found_items); diff --git a/src/modules/navigator/rtl_mission_fast.cpp b/src/modules/navigator/rtl_mission_fast.cpp index 1da091ce1bd1..0bcafd94e8fb 100644 --- a/src/modules/navigator/rtl_mission_fast.cpp +++ b/src/modules/navigator/rtl_mission_fast.cpp @@ -92,6 +92,23 @@ void RtlMissionFast::setActiveMissionItems() WorkItemType new_work_item_type{WorkItemType::WORK_ITEM_TYPE_DEFAULT}; position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + /* Skip VTOL/FW Takeoff item if in air, fixed-wing and didn't start the takeoff already*/ + if ((_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF || _mission_item.nav_cmd == NAV_CMD_TAKEOFF) && + (_work_item_type == WorkItemType::WORK_ITEM_TYPE_DEFAULT) && + (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) && + !_land_detected_sub.get().landed) { + if (setNextMissionItem()) { + if (!loadCurrentMissionItem()) { + setEndOfMissionItems(); + return; + } + + } else { + setEndOfMissionItems(); + return; + } + } + // Transition to fixed wing if necessary. if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && _vehicle_status_sub.get().is_vtol && From 68980b59e2631a11282b72e3090251f868375411 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 27 May 2024 17:26:45 +0200 Subject: [PATCH 397/652] ekf2: add terrain state --- msg/EstimatorAidSource1d.msg | 1 - msg/EstimatorAidSource2d.msg | 2 +- msg/EstimatorBias.msg | 2 +- msg/EstimatorInnovations.msg | 1 - msg/EstimatorStates.msg | 4 +- src/modules/ekf2/CMakeLists.txt | 1 + src/modules/ekf2/EKF/CMakeLists.txt | 1 + .../optical_flow/optical_flow_control.cpp | 66 +- .../optical_flow/optical_flow_fusion.cpp | 23 +- .../range_finder/range_height_control.cpp | 246 ++++-- .../range_finder/range_height_fusion.cpp | 70 ++ src/modules/ekf2/EKF/common.h | 10 +- src/modules/ekf2/EKF/covariance.cpp | 15 + src/modules/ekf2/EKF/ekf.cpp | 11 +- src/modules/ekf2/EKF/ekf.h | 45 +- src/modules/ekf2/EKF/ekf_helper.cpp | 23 +- src/modules/ekf2/EKF/height_control.cpp | 3 +- src/modules/ekf2/EKF/position_fusion.cpp | 5 +- .../EKF/python/ekf_derivation/derivation.py | 51 +- .../generated/compute_airspeed_h_and_k.h | 24 +- .../compute_airspeed_innov_and_innov_var.h | 8 +- .../compute_drag_x_innov_var_and_h.h | 14 +- .../compute_drag_y_innov_var_and_h.h | 14 +- .../compute_flow_xy_innov_var_and_hx.h | 214 +++-- .../compute_flow_y_innov_var_and_h.h | 129 +-- .../compute_gnss_yaw_pred_innov_var_and_h.h | 14 +- .../compute_gravity_xyz_innov_var_and_hx.h | 14 +- .../compute_gravity_y_innov_var_and_h.h | 14 +- .../compute_gravity_z_innov_var_and_h.h | 14 +- .../ekf_derivation/generated/compute_hagl_h.h | 43 + .../generated/compute_hagl_innov_var.h | 43 + ...ute_mag_declination_pred_innov_var_and_h.h | 14 +- .../compute_mag_innov_innov_var_and_hx.h | 14 +- .../generated/compute_mag_y_innov_var_and_h.h | 14 +- .../generated/compute_mag_z_innov_var_and_h.h | 14 +- .../generated/compute_sideslip_h_and_k.h | 235 +++--- .../compute_sideslip_innov_and_innov_var.h | 8 +- .../generated/compute_yaw_innov_var_and_h.h | 14 +- .../generated/predict_covariance.h | 305 +++---- .../python/ekf_derivation/generated/state.h | 15 +- .../terrain_estimator/terrain_estimator.cpp | 361 +------- src/modules/ekf2/EKF2.cpp | 57 +- src/modules/ekf2/EKF2.hpp | 15 - src/modules/ekf2/test/CMakeLists.txt | 1 + .../test/change_indication/ekf_gsf_reset.csv | 780 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 700 ++++++++-------- .../test/sensor_simulator/ekf_wrapper.cpp | 20 - .../ekf2/test/sensor_simulator/ekf_wrapper.h | 4 - src/modules/ekf2/test/test_EKF_flow.cpp | 24 +- .../ekf2/test/test_EKF_flow_generated.cpp | 73 ++ .../ekf2/test/test_EKF_height_fusion.cpp | 17 +- .../ekf2/test/test_EKF_terrain_estimator.cpp | 40 +- src/modules/logger/logged_topics.cpp | 6 - 53 files changed, 1931 insertions(+), 1925 deletions(-) create mode 100644 src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp create mode 100644 src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_h.h create mode 100644 src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_innov_var.h create mode 100644 src/modules/ekf2/test/test_EKF_flow_generated.cpp diff --git a/msg/EstimatorAidSource1d.msg b/msg/EstimatorAidSource1d.msg index 56ef5cfb991f..7bd8ea765827 100644 --- a/msg/EstimatorAidSource1d.msg +++ b/msg/EstimatorAidSource1d.msg @@ -25,4 +25,3 @@ bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_airspeed estimator_aid_src_sideslip # TOPICS estimator_aid_src_fake_hgt # TOPICS estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw -# TOPICS estimator_aid_src_terrain_range_finder diff --git a/msg/EstimatorAidSource2d.msg b/msg/EstimatorAidSource2d.msg index 069030eb15fd..14e3ac3f846d 100644 --- a/msg/EstimatorAidSource2d.msg +++ b/msg/EstimatorAidSource2d.msg @@ -22,5 +22,5 @@ bool innovation_rejected # true if the observation has been rejected bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_ev_pos estimator_aid_src_fake_pos estimator_aid_src_gnss_pos estimator_aid_src_aux_global_position -# TOPICS estimator_aid_src_aux_vel estimator_aid_src_optical_flow estimator_aid_src_terrain_optical_flow +# TOPICS estimator_aid_src_aux_vel estimator_aid_src_optical_flow # TOPICS estimator_aid_src_drag diff --git a/msg/EstimatorBias.msg b/msg/EstimatorBias.msg index 10dbca87bda7..bb65e47bc7d1 100644 --- a/msg/EstimatorBias.msg +++ b/msg/EstimatorBias.msg @@ -9,4 +9,4 @@ float32 innov # innovation of the last measurement fusion (m) float32 innov_var # innovation variance of the last measurement fusion (m^2) float32 innov_test_ratio # normalized innovation squared test ratio -# TOPICS estimator_baro_bias estimator_gnss_hgt_bias estimator_rng_hgt_bias +# TOPICS estimator_baro_bias estimator_gnss_hgt_bias diff --git a/msg/EstimatorInnovations.msg b/msg/EstimatorInnovations.msg index ecf637478d41..11cc6a58adb9 100644 --- a/msg/EstimatorInnovations.msg +++ b/msg/EstimatorInnovations.msg @@ -22,7 +22,6 @@ float32[2] aux_hvel # horizontal auxiliary velocity innovation from landing targ # Optical flow float32[2] flow # flow innvoation (rad/sec) and innovation variance ((rad/sec)**2) -float32[2] terr_flow # flow innvoation (rad/sec) and innovation variance computed by the terrain estimator ((rad/sec)**2) # Various float32 heading # heading innovation (rad) and innovation variance (rad**2) diff --git a/msg/EstimatorStates.msg b/msg/EstimatorStates.msg index 787a005f8797..885246d8a5b9 100644 --- a/msg/EstimatorStates.msg +++ b/msg/EstimatorStates.msg @@ -1,7 +1,7 @@ uint64 timestamp # time since system start (microseconds) uint64 timestamp_sample # the timestamp of the raw data (microseconds) -float32[24] states # Internal filter states +float32[25] states # Internal filter states uint8 n_states # Number of states effectively used -float32[23] covariances # Diagonal Elements of Covariance Matrix +float32[24] covariances # Diagonal Elements of Covariance Matrix diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index f21ce26d1142..6d0f72dcbd68 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -203,6 +203,7 @@ if(CONFIG_EKF2_RANGE_FINDER) list(APPEND EKF_SRCS EKF/aid_sources/range_finder/range_finder_consistency_check.cpp EKF/aid_sources/range_finder/range_height_control.cpp + EKF/aid_sources/range_finder/range_height_fusion.cpp EKF/aid_sources/range_finder/sensor_range_finder.cpp ) endif() diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index fa57df04c735..bd9770c9014f 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -125,6 +125,7 @@ if(CONFIG_EKF2_RANGE_FINDER) list(APPEND EKF_SRCS aid_sources/range_finder/range_finder_consistency_check.cpp aid_sources/range_finder/range_height_control.cpp + aid_sources/range_finder/range_height_fusion.cpp aid_sources/range_finder/sensor_range_finder.cpp ) endif() 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 7758a64da360..ec2aec1ba4fd 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 @@ -55,13 +55,9 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && !_flow_sample_delayed.flow_rate.longerThan(_flow_max_rate); const bool is_tilt_good = (_R_to_earth(2, 2) > _params.range_cos_max_tilt); - // don't enforce this condition if terrain estimate is not valid as we have logic below to coast through bad range finder data - const bool is_within_max_sensor_dist = isTerrainEstimateValid() ? (_terrain_vpos - _state.pos(2) <= _flow_max_distance) : true; - if (is_quality_good && is_magnitude_good - && is_tilt_good - && is_within_max_sensor_dist) { + && is_tilt_good) { // compensate for body motion to give a LOS rate calcOptFlowBodyRateComp(imu_delayed); _flow_rate_compensated = _flow_sample_delayed.flow_rate - _flow_sample_delayed.gyro_rate.xy(); @@ -81,20 +77,21 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && (_control_status.flags.inertial_dead_reckoning // is doing inertial dead-reckoning so must constrain drift urgently || isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)); - // Fuse optical flow LOS rate observations into the main filter only if height above ground has been updated recently - // use a relaxed time criteria to enable it to coast through bad range finder data - const bool terrain_available = isTerrainEstimateValid() || isRecent(_aid_src_terrain_range_finder.time_last_fuse, (uint64_t)10e6); + const bool is_within_max_sensor_dist = getHagl() <= _flow_max_distance; const bool continuing_conditions_passing = (_params.flow_ctrl == 1) && _control_status.flags.tilt_align - && (terrain_available || is_flow_required); + && is_within_max_sensor_dist; const bool starting_conditions_passing = continuing_conditions_passing && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching + // If the height is relative to the ground, terrain height cannot be observed. + _hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); + if (_control_status.flags.opt_flow) { if (continuing_conditions_passing) { - fuseOptFlow(); + fuseOptFlow(_hagl_sensor_status.flags.flow); // 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)) { @@ -125,19 +122,35 @@ void Ekf::startFlowFusion() { ECL_INFO("starting optical flow fusion"); - if (!_aid_src_optical_flow.innovation_rejected && isHorizontalAidingActive()) { - // Consistent with the current velocity state, simply fuse the data without reset - fuseOptFlow(); - _control_status.flags.opt_flow = true; + if (_height_sensor_ref != HeightSensor::RANGE) { + // If the height is relative to the ground, terrain height cannot be observed. + _hagl_sensor_status.flags.flow = true; + } + + if (isHorizontalAidingActive()) { + if (!_aid_src_optical_flow.innovation_rejected) { + ECL_INFO("starting optical flow no reset"); + fuseOptFlow(_hagl_sensor_status.flags.flow); + + } else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) { + resetHaglFlow(); - } else if (!isHorizontalAidingActive()) { - resetFlowFusion(); - _control_status.flags.opt_flow = true; + } else { + ECL_INFO("optical flow fusion failed to start"); + _control_status.flags.opt_flow = false; + _hagl_sensor_status.flags.flow = false; + } } else { - ECL_INFO("optical flow fusion failed to start"); - _control_status.flags.opt_flow = false; + if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) { + resetFlowFusion(); + + } else if (_hagl_sensor_status.flags.flow) { + resetHaglFlow(); + } } + + _control_status.flags.opt_flow = true; // needs to be here because of isHorizontalAidingActive } void Ekf::resetFlowFusion() @@ -159,11 +172,26 @@ void Ekf::resetFlowFusion() _aid_src_optical_flow.time_last_fuse = _time_delayed_us; } +void Ekf::resetHaglFlow() +{ + ECL_INFO("reset hagl to flow"); + // TODO: use the flow data + _state.terrain = fmaxf(0.0f, _state.pos(2)); + P.uncorrelateCovarianceSetVariance(State::terrain.idx, 100.f); + _terrain_vpos_reset_counter++; + + _innov_check_fail_status.flags.reject_optflow_X = false; + _innov_check_fail_status.flags.reject_optflow_Y = false; + + _aid_src_optical_flow.time_last_fuse = _time_delayed_us; +} + void Ekf::stopFlowFusion() { if (_control_status.flags.opt_flow) { ECL_INFO("stopping optical flow fusion"); _control_status.flags.opt_flow = false; + _hagl_sensor_status.flags.flow = false; } } diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 38186ebadf25..bfed5a7fa1b4 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -73,7 +73,7 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) Vector2f innov_var; VectorState H; - sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, range, R_LOS, FLT_EPSILON, &innov_var, &H); + sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, R_LOS, FLT_EPSILON, &innov_var, &H); // run the innovation consistency check and record result updateAidSourceStatus(aid_src, @@ -85,7 +85,7 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) math::max(_params.flow_innov_gate, 1.f)); // innovation gate } -void Ekf::fuseOptFlow() +void Ekf::fuseOptFlow(const bool update_terrain) { const float R_LOS = _aid_src_optical_flow.observation_variance[0]; @@ -97,7 +97,7 @@ void Ekf::fuseOptFlow() Vector2f innov_var; VectorState H; - sym::ComputeFlowXyInnovVarAndHx(state_vector, P, range, R_LOS, FLT_EPSILON, &innov_var, &H); + sym::ComputeFlowXyInnovVarAndHx(state_vector, P, R_LOS, FLT_EPSILON, &innov_var, &H); innov_var.copyTo(_aid_src_optical_flow.innovation_variance); if ((innov_var(0) < R_LOS) || (innov_var(1) < R_LOS)) { @@ -124,7 +124,7 @@ void Ekf::fuseOptFlow() } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::ComputeFlowYInnovVarAndH(state_vector, P, range, R_LOS, FLT_EPSILON, &_aid_src_optical_flow.innovation_variance[1], &H); + sym::ComputeFlowYInnovVarAndH(state_vector, P, R_LOS, FLT_EPSILON, &_aid_src_optical_flow.innovation_variance[1], &H); // recalculate the innovation using the updated state const Vector2f vel_body = predictFlowVelBody(); @@ -141,6 +141,10 @@ void Ekf::fuseOptFlow() VectorState Kfusion = P * H / _aid_src_optical_flow.innovation_variance[index]; + if (!update_terrain) { + Kfusion(State::terrain.idx) = 0.f; + } + if (measurementUpdate(Kfusion, H, _aid_src_optical_flow.observation_variance[index], _aid_src_optical_flow.innovation[index])) { fused[index] = true; } @@ -165,10 +169,17 @@ float Ekf::predictFlowRange() // calculate the height above the ground of the optical flow camera. Since earth frame is NED // a positive offset in earth frame leads to a smaller height above the ground. - const float height_above_gnd_est = math::max(_terrain_vpos - _state.pos(2) - pos_offset_earth(2), fmaxf(_params.rng_gnd_clearance, 0.01f)); + const float height_above_gnd_est = getHagl() - pos_offset_earth(2); // calculate range from focal point to centre of image - return height_above_gnd_est / _R_to_earth(2, 2); // absolute distance to the frame region in view + float flow_range = height_above_gnd_est / _R_to_earth(2, 2); // absolute distance to the frame region in view + + // avoid the flow prediction singularity at range = 0 + if (fabsf(flow_range) < FLT_EPSILON) { + flow_range = signNoZero(flow_range) * FLT_EPSILON; + } + + return flow_range; } Vector2f Ekf::predictFlowVelBody() 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 76e815ac738c..d085579956bc 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 @@ -37,6 +37,7 @@ */ #include "ekf.h" +#include "ekf_derivation/generated/compute_hagl_innov_var.h" void Ekf::controlRangeHeightFusion() { @@ -93,58 +94,91 @@ void Ekf::controlRangeHeightFusion() } auto &aid_src = _aid_src_rng_hgt; - HeightBiasEstimator &bias_est = _rng_hgt_b_est; - - bias_est.predict(_dt_ekf_avg); if (rng_data_ready && _range_sensor.getSampleAddress()) { - const float measurement = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance); - const float measurement_var = sq(_params.range_noise) + sq(_params.range_noise_scaler * _range_sensor.getDistBottom()); + updateRangeHeight(aid_src); + const bool measurement_valid = PX4_ISFINITE(aid_src.observation) && PX4_ISFINITE(aid_src.observation_variance); - const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); + const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast(RngCtrl::ENABLED)) + || (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL))) + && _control_status.flags.tilt_align + && measurement_valid + && _range_sensor.isDataHealthy() + && _rng_consistency_check.isKinematicallyConsistent(); - // vertical position innovation - baro measurement has opposite sign to earth z axis - updateVerticalPositionAidStatus(aid_src, - _range_sensor.getSampleAddress()->time_us, // sample timestamp - -(measurement - bias_est.getBias()), // observation - measurement_var + bias_est.getBiasVar(), // observation variance - math::max(_params.range_innov_gate, 1.f)); // innovation gate + const bool starting_conditions_passing = continuing_conditions_passing + && isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL) + && _range_sensor.isRegularlySendingData(); - // update the bias estimator before updating the main filter but after - // using its current state to compute the vertical position innovation - if (measurement_valid && _range_sensor.isDataHealthy()) { - bias_est.setMaxStateNoise(sqrtf(measurement_var)); - bias_est.setProcessNoiseSpectralDensity(_params.rng_hgt_bias_nsd); - bias_est.fuseBias(measurement - (-_state.pos(2)), measurement_var + P(State::pos.idx + 2, State::pos.idx + 2)); - } - // determine if we should use height aiding - const bool do_conditional_range_aid = (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) + const bool do_conditional_range_aid = (_hagl_sensor_status.flags.range_finder || _control_status.flags.rng_hgt) + && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) && isConditionalRangeAidSuitable(); - const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast(RngCtrl::ENABLED)) || do_conditional_range_aid) - && measurement_valid - && _range_sensor.isDataHealthy(); - - const bool starting_conditions_passing = continuing_conditions_passing - && isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL) - && _range_sensor.isRegularlySendingData(); + const bool do_range_aid = (_hagl_sensor_status.flags.range_finder || _control_status.flags.rng_hgt) + && (_params.rng_ctrl == static_cast(RngCtrl::ENABLED)); if (_control_status.flags.rng_hgt) { + if (!(do_conditional_range_aid || do_range_aid)) { + ECL_INFO("stopping %s fusion", HGT_SRC_NAME); + stopRngHgtFusion(); + } + + } else { + if (_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) { + if (do_conditional_range_aid) { + // Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference. + ECL_INFO("starting conditional %s height fusion", HGT_SRC_NAME); + _height_sensor_ref = HeightSensor::RANGE; + + _control_status.flags.rng_hgt = true; + stopRngTerrFusion(); + + if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) { + resetHaglRng(aid_src); + } + + } else if (do_range_aid) { + // Range finder is the primary height source, the ground is now the datum used + // to compute the local vertical position + ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME); + _height_sensor_ref = HeightSensor::RANGE; + + _information_events.flags.reset_hgt_to_rng = true; + resetVerticalPositionTo(-aid_src.observation, aid_src.observation_variance); + _state.terrain = 0.f; + _control_status.flags.rng_hgt = true; + stopRngTerrFusion(); + + aid_src.time_last_fuse = _time_delayed_us; + } + + } else { + if (do_conditional_range_aid || do_range_aid) { + ECL_INFO("starting %s height fusion", HGT_SRC_NAME); + _control_status.flags.rng_hgt = true; + + if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) { + resetHaglRng(aid_src); + } + } + } + } + + if (_control_status.flags.rng_hgt || _hagl_sensor_status.flags.range_finder) { if (continuing_conditions_passing) { - fuseVerticalPosition(aid_src); + fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _hagl_sensor_status.flags.range_finder); const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max); - if (isHeightResetRequired()) { + if (isHeightResetRequired() && _control_status.flags.rng_hgt) { // All height sources are failing ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_rng = true; - resetVerticalPositionTo(-(measurement - bias_est.getBias())); - bias_est.setBias(_state.pos(2) + measurement); + resetVerticalPositionTo(-(aid_src.observation - _state.terrain)); // reset vertical velocity resetVerticalVelocityToZero(); @@ -153,96 +187,123 @@ void Ekf::controlRangeHeightFusion() } else if (is_fusion_failing) { // Some other height source is still working - ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME); - stopRngHgtFusion(); - _control_status.flags.rng_fault = true; - _range_sensor.setFaulty(); + if (_hagl_sensor_status.flags.flow) { + ECL_WARN("stopping %s fusion, fusion failing", HGT_SRC_NAME); + stopRngHgtFusion(); + stopRngTerrFusion(); + + } else { + resetHaglRng(aid_src); + } } } else { - ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME); + ECL_WARN("stopping %s fusion, continuing conditions failing", HGT_SRC_NAME); stopRngHgtFusion(); + stopRngTerrFusion(); } } else { if (starting_conditions_passing) { - if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) - && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) - ) { - // Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference. - ECL_INFO("starting conditional %s height fusion", HGT_SRC_NAME); - _height_sensor_ref = HeightSensor::RANGE; - bias_est.setBias(_state.pos(2) + measurement); - - } else if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) - && (_params.rng_ctrl != static_cast(RngCtrl::CONDITIONAL)) - ) { - // Range finder is the primary height source, the ground is now the datum used - // to compute the local vertical position - ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME); - _height_sensor_ref = HeightSensor::RANGE; - - _information_events.flags.reset_hgt_to_rng = true; - resetVerticalPositionTo(-measurement, measurement_var); - bias_est.reset(); + if (_hagl_sensor_status.flags.flow) { + if (!aid_src.innovation_rejected) { + _hagl_sensor_status.flags.range_finder = true; + fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _hagl_sensor_status.flags.range_finder); + } } else { - ECL_INFO("starting %s height fusion", HGT_SRC_NAME); - bias_est.setBias(_state.pos(2) + measurement); - } + if (aid_src.innovation_rejected) { + resetHaglRng(aid_src); + } - aid_src.time_last_fuse = _time_delayed_us; - bias_est.setFusionActive(); - _control_status.flags.rng_hgt = true; + _hagl_sensor_status.flags.range_finder = true; + } } } - } else if (_control_status.flags.rng_hgt + } else if ((_control_status.flags.rng_hgt || _hagl_sensor_status.flags.range_finder) && !isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. - ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME); + ECL_WARN("stopping %s fusion, no data", HGT_SRC_NAME); stopRngHgtFusion(); + stopRngTerrFusion(); } } -bool Ekf::isConditionalRangeAidSuitable() +void Ekf::updateRangeHeight(estimator_aid_source1d_s &aid_src) { -#if defined(CONFIG_EKF2_TERRAIN) + aid_src.observation = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance); + aid_src.innovation = getHagl() - aid_src.observation; + + const float observation_variance = getRngVar(); + float innovation_variance; + sym::ComputeHaglInnovVar(P, observation_variance, &innovation_variance); + + const float innov_gate = math::max(_params.range_innov_gate, 1.f); + updateAidSourceStatus(aid_src, + _range_sensor.getSampleAddress()->time_us, // sample timestamp + math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance), // observation + observation_variance, // observation variance + getHagl() - aid_src.observation, // innovation + innovation_variance, // innovation variance + math::max(_params.range_innov_gate, 1.f)); // innovation gate + + // z special case if there is bad vertical acceleration data, then don't reject measurement, + // but limit innovation to prevent spikes that could destabilise the filter + if (_fault_status.flags.bad_acc_vertical && aid_src.innovation_rejected) { + const float innov_limit = innov_gate * sqrtf(aid_src.innovation_variance); + aid_src.innovation = math::constrain(aid_src.innovation, -innov_limit, innov_limit); + aid_src.innovation_rejected = false; + } +} - if (_control_status.flags.in_air - && _range_sensor.isHealthy() - && isTerrainEstimateValid()) { - // check if we can use range finder measurements to estimate height, use hysteresis to avoid rapid switching - // Note that the 0.7 coefficients and the innovation check are arbitrary values but work well in practice - float range_hagl_max = _params.max_hagl_for_range_aid; - float max_vel_xy = _params.max_vel_for_range_aid; +float Ekf::getRngVar() const +{ + return fmaxf( + P(State::pos.idx + 2, State::pos.idx + 2) + + sq(_params.range_noise) + + sq(_params.range_noise_scaler * _range_sensor.getRange()), + 0.f); +} - const float hagl_innov = _aid_src_terrain_range_finder.innovation; - const float hagl_innov_var = _aid_src_terrain_range_finder.innovation_variance; +void Ekf::resetHaglRng(estimator_aid_source1d_s &aid_src) +{ + _state.terrain = _state.pos(2) + aid_src.observation; + P.uncorrelateCovarianceSetVariance(State::terrain.idx, aid_src.observation_variance); + _terrain_vpos_reset_counter++; - const float hagl_test_ratio = (hagl_innov * hagl_innov / (sq(_params.range_aid_innov_gate) * hagl_innov_var)); + aid_src.time_last_fuse = _time_delayed_us; +} - bool is_hagl_stable = (hagl_test_ratio < 1.f); +bool Ekf::isConditionalRangeAidSuitable() +{ +#if defined(CONFIG_EKF2_TERRAIN) - if (!_control_status.flags.rng_hgt) { - range_hagl_max = 0.7f * _params.max_hagl_for_range_aid; - max_vel_xy = 0.7f * _params.max_vel_for_range_aid; - is_hagl_stable = (hagl_test_ratio < 0.01f); - } + // check if we can use range finder measurements to estimate height, use hysteresis to avoid rapid switching + // Note that the 0.7 coefficients and the innovation check are arbitrary values but work well in practice + float range_hagl_max = _params.max_hagl_for_range_aid; + float max_vel_xy = _params.max_vel_for_range_aid; - const float range_hagl = _terrain_vpos - _state.pos(2); + const float hagl_test_ratio = _aid_src_rng_hgt.test_ratio; - const bool is_in_range = (range_hagl < range_hagl_max); + bool is_hagl_stable = (hagl_test_ratio < 1.f); - bool is_below_max_speed = true; + if (!_control_status.flags.rng_hgt) { + range_hagl_max = 0.7f * _params.max_hagl_for_range_aid; + max_vel_xy = 0.7f * _params.max_vel_for_range_aid; + is_hagl_stable = (hagl_test_ratio < 0.01f); + } - if (isHorizontalAidingActive()) { - is_below_max_speed = !_state.vel.xy().longerThan(max_vel_xy); - } + const bool is_in_range = (getHagl() < range_hagl_max); - return is_in_range && is_hagl_stable && is_below_max_speed; + bool is_below_max_speed = true; + + if (isHorizontalAidingActive()) { + is_below_max_speed = !_state.vel.xy().longerThan(max_vel_xy); } + return is_in_range && is_hagl_stable && is_below_max_speed; + #endif // CONFIG_EKF2_TERRAIN return false; @@ -256,8 +317,11 @@ void Ekf::stopRngHgtFusion() _height_sensor_ref = HeightSensor::UNKNOWN; } - _rng_hgt_b_est.setFusionInactive(); - _control_status.flags.rng_hgt = false; } } + +void Ekf::stopRngTerrFusion() +{ + _hagl_sensor_status.flags.range_finder = false; +} diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp new file mode 100644 index 000000000000..a06bdb9478b8 --- /dev/null +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp @@ -0,0 +1,70 @@ +/**************************************************************************** + * + * 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 "ekf.h" +#include "ekf_derivation/generated/compute_hagl_h.h" + +bool Ekf::fuseHaglRng(estimator_aid_source1d_s &aid_src, bool update_height, bool update_terrain) +{ + if (aid_src.innovation_rejected) { + _innov_check_fail_status.flags.reject_hagl = true; + return false; + } + + VectorState H; + + sym::ComputeHaglH(&H); + + // calculate the Kalman gain + VectorState K = P * H / aid_src.innovation_variance; + + if (!update_terrain) { + K(State::terrain.idx) = 0.f; + } + + if (!update_height) { + const float k_terrain = K(State::terrain.idx); + K.zero(); + K(State::terrain.idx) = k_terrain; + } + + measurementUpdate(K, H, aid_src.observation_variance, aid_src.innovation); + + // record last successful fusion event + _innov_check_fail_status.flags.reject_hagl = false; + + aid_src.time_last_fuse = _time_delayed_us; + aid_src.fused = true; + + return true; +} diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 845c2d4edbfb..70be1885720f 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -107,7 +107,7 @@ enum MagFuseType : uint8_t { #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_TERRAIN) -enum TerrainFusionMask : uint8_t { +enum class TerrainFusionMask : uint8_t { TerrainFuseRangeFinder = (1 << 0), TerrainFuseOpticalFlow = (1 << 1) }; @@ -382,8 +382,8 @@ struct parameters { #endif // CONFIG_EKF2_SIDESLIP #if defined(CONFIG_EKF2_TERRAIN) - int32_t terrain_fusion_mode{TerrainFusionMask::TerrainFuseRangeFinder | - TerrainFusionMask::TerrainFuseOpticalFlow}; ///< aiding source(s) selection bitmask for the terrain estimator + int32_t terrain_fusion_mode{static_cast(TerrainFusionMask::TerrainFuseRangeFinder) + | static_cast(TerrainFusionMask::TerrainFuseOpticalFlow)}; ///< aiding source(s) selection bitmask for the terrain estimation float terrain_p_noise{5.0f}; ///< process noise for terrain offset (m/sec) float terrain_gradient{0.5f}; ///< gradient of terrain used to estimate process noise due to changing position (m/m) @@ -401,10 +401,8 @@ struct parameters { float range_delay_ms{5.0f}; ///< range finder measurement delay relative to the IMU (mSec) float range_noise{0.1f}; ///< observation noise for range finder measurements (m) float range_innov_gate{5.0f}; ///< range finder fusion innovation consistency gate size (STD) - float rng_hgt_bias_nsd{0.13f}; ///< process noise for range height bias estimation (m/s/sqrt(Hz)) float rng_sens_pitch{0.0f}; ///< Pitch offset of the range sensor (rad). Sensor points out along Z axis when offset is zero. Positive rotation is RH about Y axis. float range_noise_scaler{0.0f}; ///< scaling from range measurement to noise (m/m) - const float vehicle_variance_scaler{0.0f}; ///< gain applied to vehicle height variance used in calculation of height above ground observation variance float max_hagl_for_range_aid{5.0f}; ///< maximum height above ground for which we allow to use the range finder as height source (if rng_control == 1) float max_vel_for_range_aid{1.0f}; ///< maximum ground velocity for which we allow to use the range finder as height source (if rng_control == 1) float range_aid_innov_gate{1.0f}; ///< gate size used for innovation consistency checks for range aid fusion @@ -521,7 +519,7 @@ union innovation_fault_status_u { bool reject_yaw : 1; ///< 7 - true if the yaw observation has been rejected bool reject_airspeed : 1; ///< 8 - true if the airspeed observation has been rejected bool reject_sideslip : 1; ///< 9 - true if the synthetic sideslip observation has been rejected - bool reject_hagl : 1; ///< 10 - true if the height above ground observation has been rejected + bool reject_hagl : 1; ///< 10 - unused bool reject_optflow_X : 1; ///< 11 - true if the X optical flow observation has been rejected bool reject_optflow_Y : 1; ///< 12 - true if the Y optical flow observation has been rejected } flags; diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index a086a11700d3..2310e644a036 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -202,6 +202,17 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) } #endif // CONFIG_EKF2_WIND +#if defined(CONFIG_EKF2_TERRAIN) + if (_height_sensor_ref != HeightSensor::RANGE) { + // predict the state variance growth where the state is the vertical position of the terrain underneath the vehicle + // process noise due to errors in vehicle height estimate + float terrain_process_noise = sq(imu_delayed.delta_vel_dt * _params.terrain_p_noise); + + // process noise due to terrain gradient + terrain_process_noise += sq(imu_delayed.delta_vel_dt * _params.terrain_gradient) * (sq(_state.vel(0)) + sq(_state.vel(1))); + P(State::terrain.idx, State::terrain.idx) += terrain_process_noise; + } +#endif // CONFIG_EKF2_TERRAIN // covariance matrix is symmetrical, so copy upper half to lower half for (unsigned row = 0; row < State::size; row++) { @@ -239,6 +250,10 @@ void Ekf::constrainStateVariances() constrainStateVarLimitRatio(State::wind_vel, 1e-6f, 1e6f); } #endif // CONFIG_EKF2_WIND + +#if defined(CONFIG_EKF2_TERRAIN) + constrainStateVarLimitRatio(State::terrain, 0.f, 1e4f); +#endif // CONFIG_EKF2_TERRAIN } void Ekf::constrainStateVar(const IdxDof &state, float min, float max) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 8dc7e35d6844..61036e4bc7fb 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -161,7 +161,6 @@ bool Ekf::update() controlFusionModes(imu_sample_delayed); #if defined(CONFIG_EKF2_TERRAIN) - // run a separate filter for terrain estimation runTerrainEstimator(imu_sample_delayed); #endif // CONFIG_EKF2_TERRAIN @@ -201,7 +200,7 @@ bool Ekf::initialiseFilter() initialiseCovariance(); #if defined(CONFIG_EKF2_TERRAIN) - // Initialise the terrain estimator + // Initialise the terrain state initHagl(); #endif // CONFIG_EKF2_TERRAIN @@ -377,6 +376,14 @@ void Ekf::print_status() ); #endif // CONFIG_EKF2_WIND +#if defined(CONFIG_EKF2_TERRAIN) + printf("Terrain position (%d): %.3f var: %.1e\n", + State::terrain.idx, + (double)_state.terrain, + (double)getStateVariance()(0) + ); +#endif // CONFIG_EKF2_TERRAIN + printf("\nP:\n"); P.print(); diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 88789fa1b2f6..ac953e570bc3 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -104,27 +104,19 @@ class Ekf final : public EstimatorInterface uint8_t getTerrainEstimateSensorBitfield() const { return _hagl_sensor_status.value; } // get the estimated terrain vertical position relative to the NED origin - float getTerrainVertPos() const { return _terrain_vpos; }; + float getTerrainVertPos() const { return _state.terrain; }; + float getHagl() const { return _state.terrain - _state.pos(2); } // get the number of times the vertical terrain position has been reset uint8_t getTerrainVertPosResetCounter() const { return _terrain_vpos_reset_counter; }; // get the terrain variance - float get_terrain_var() const { return _terrain_var; } - -# if defined(CONFIG_EKF2_RANGE_FINDER) - const auto &aid_src_terrain_range_finder() const { return _aid_src_terrain_range_finder; } -# endif // CONFIG_EKF2_RANGE_FINDER - -# if defined(CONFIG_EKF2_OPTICAL_FLOW) - const auto &aid_src_terrain_optical_flow() const { return _aid_src_terrain_optical_flow; } -# endif // CONFIG_EKF2_OPTICAL_FLOW + float getTerrainVariance() const { return P(State::terrain.idx, State::terrain.idx); } #endif // CONFIG_EKF2_TERRAIN #if defined(CONFIG_EKF2_RANGE_FINDER) // range height - const BiasEstimator::status &getRngHgtBiasEstimatorStatus() const { return _rng_hgt_b_est.getStatus(); } const auto &aid_src_rng_hgt() const { return _aid_src_rng_hgt; } float getHaglRateInnov() const { return _rng_consistency_check.getInnov(); } @@ -592,27 +584,14 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_TERRAIN) // Terrain height state estimation - float _terrain_vpos{0.0f}; ///< estimated vertical position of the terrain underneath the vehicle in local NED frame (m) - float _terrain_var{1e4f}; ///< variance of terrain position estimate (m**2) uint8_t _terrain_vpos_reset_counter{0}; ///< number of times _terrain_vpos has been reset terrain_fusion_status_u _hagl_sensor_status{}; ///< Struct indicating type of sensor used to estimate height above ground float _last_on_ground_posD{0.0f}; ///< last vertical position when the in_air status was false (m) - -# if defined(CONFIG_EKF2_RANGE_FINDER) - estimator_aid_source1d_s _aid_src_terrain_range_finder{}; - uint64_t _time_last_healthy_rng_data{0}; -# endif // CONFIG_EKF2_RANGE_FINDER - -# if defined(CONFIG_EKF2_OPTICAL_FLOW) - estimator_aid_source2d_s _aid_src_terrain_optical_flow{}; -# endif // CONFIG_EKF2_OPTICAL_FLOW - #endif // CONFIG_EKF2_TERRAIN #if defined(CONFIG_EKF2_RANGE_FINDER) estimator_aid_source1d_s _aid_src_rng_hgt{}; - HeightBiasEstimator _rng_hgt_b_est{HeightSensor::RANGE, _height_sensor_ref}; #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_OPTICAL_FLOW) @@ -831,29 +810,22 @@ class Ekf final : public EstimatorInterface // terrain vertical position estimator void initHagl(); void runTerrainEstimator(const imuSample &imu_delayed); - void predictHagl(const imuSample &imu_delayed); - float getTerrainVPos() const { return isTerrainEstimateValid() ? _terrain_vpos : _last_on_ground_posD; } + float getTerrainVPos() const { return isTerrainEstimateValid() ? _state.terrain : _last_on_ground_posD; } void controlHaglFakeFusion(); - void terrainHandleVerticalPositionReset(float delta_z); # if defined(CONFIG_EKF2_RANGE_FINDER) // update the terrain vertical position estimate using a height above ground measurement from the range finder - void controlHaglRngFusion(); - void updateHaglRng(estimator_aid_source1d_s &aid_src) const; - void fuseHaglRng(estimator_aid_source1d_s &aid_src); - void resetHaglRng(); - void stopHaglRngFusion(); + bool fuseHaglRng(estimator_aid_source1d_s &aid_src, bool update_height, bool update_terrain); + void updateRangeHeight(estimator_aid_source1d_s &aid_src); + void resetHaglRng(estimator_aid_source1d_s &aid_src); float getRngVar() const; # endif // CONFIG_EKF2_RANGE_FINDER # if defined(CONFIG_EKF2_OPTICAL_FLOW) // update the terrain vertical position estimate using an optical flow measurement - void controlHaglFlowFusion(); void resetHaglFlow(); - void stopHaglFlowFusion(); - void fuseFlowForTerrain(estimator_aid_source2d_s &flow); # endif // CONFIG_EKF2_OPTICAL_FLOW #endif // CONFIG_EKF2_TERRAIN @@ -863,6 +835,7 @@ class Ekf final : public EstimatorInterface void controlRangeHeightFusion(); bool isConditionalRangeAidSuitable(); void stopRngHgtFusion(); + void stopRngTerrFusion(); #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_OPTICAL_FLOW) @@ -883,7 +856,7 @@ class Ekf final : public EstimatorInterface // fuse optical flow line of sight rate measurements void updateOptFlow(estimator_aid_source2d_s &aid_src); - void fuseOptFlow(); + void fuseOptFlow(bool update_terrain); float predictFlowRange(); Vector2f predictFlowVelBody(); #endif // CONFIG_EKF2_OPTICAL_FLOW diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index ab416d81da4c..94b1046dbaec 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -211,7 +211,7 @@ void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const #if defined(CONFIG_EKF2_OPTICAL_FLOW) if (_control_status.flags.opt_flow) { float gndclearance = math::max(_params.rng_gnd_clearance, 0.1f); - vel_err_conservative = math::max((_terrain_vpos - _state.pos(2)), gndclearance) * Vector2f(_aid_src_optical_flow.innovation).norm(); + vel_err_conservative = math::max(getHagl(), gndclearance) * Vector2f(_aid_src_optical_flow.innovation).norm(); } #endif // CONFIG_EKF2_OPTICAL_FLOW @@ -271,7 +271,7 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl const float flow_hagl_min = fmaxf(rangefinder_hagl_min, _flow_min_distance); const float flow_hagl_max = fminf(rangefinder_hagl_max, _flow_max_distance); - const float flow_constrained_height = math::constrain(_terrain_vpos - _state.pos(2), flow_hagl_min, flow_hagl_max); + const float flow_constrained_height = math::constrain(getHagl(), flow_hagl_min, flow_hagl_max); // Allow ground relative velocity to use 50% of available flow sensor range to allow for angular motion const float flow_vxy_max = 0.5f * _flow_max_rate * flow_constrained_height; @@ -472,18 +472,9 @@ float Ekf::getHeightAboveGroundInnovationTestRatio() const # if defined(CONFIG_EKF2_RANGE_FINDER) if (_hagl_sensor_status.flags.range_finder) { // return the terrain height innovation test ratio - test_ratio = math::max(test_ratio, fabsf(_aid_src_terrain_range_finder.test_ratio_filtered)); + test_ratio = math::max(test_ratio, fabsf(_aid_src_rng_hgt.test_ratio_filtered)); } -#endif // CONFIG_EKF2_RANGE_FINDER - -# if defined(CONFIG_EKF2_OPTICAL_FLOW) - if (_hagl_sensor_status.flags.flow) { - // return the terrain height innovation test ratio - for (auto &test_ratio_filtered : _aid_src_terrain_optical_flow.test_ratio_filtered) { - test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); - } - } -# endif // CONFIG_EKF2_OPTICAL_FLOW +# endif // CONFIG_EKF2_RANGE_FINDER #endif // CONFIG_EKF2_TERRAIN if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { @@ -569,6 +560,10 @@ void Ekf::fuse(const VectorState &K, float innovation) _state.wind_vel = matrix::constrain(_state.wind_vel - K.slice(State::wind_vel.idx, 0) * innovation, -1.e2f, 1.e2f); } #endif // CONFIG_EKF2_WIND + +#if defined(CONFIG_EKF2_TERRAIN) + _state.terrain = math::constrain(_state.terrain - K(State::terrain.idx) * innovation, -1e4f, 1e4f); +#endif // CONFIG_EKF2_TERRAIN } void Ekf::updateDeadReckoningStatus() @@ -670,7 +665,7 @@ void Ekf::updateGroundEffect() #if defined(CONFIG_EKF2_TERRAIN) if (isTerrainEstimateValid()) { // automatically set ground effect if terrain is valid - float height = _terrain_vpos - _state.pos(2); + float height = getHagl(); _control_status.flags.gnd_effect = (height < _params.gnd_effect_max_hgt); } else diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index 9d07c9bc580d..d81c2848386d 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -301,7 +301,8 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const #if defined(CONFIG_EKF2_RANGE_FINDER) if (_control_status.flags.rng_hgt) { - checks[3] = {ReferenceType::GROUND, _aid_src_rng_hgt.innovation, _aid_src_rng_hgt.innovation_variance}; + // Range is a distance to ground measurement, not a direct height observation and has an opposite sign + checks[3] = {ReferenceType::GROUND, -_aid_src_rng_hgt.innovation, _aid_src_rng_hgt.innovation_variance}; } #endif // CONFIG_EKF2_RANGE_FINDER diff --git a/src/modules/ekf2/EKF/position_fusion.cpp b/src/modules/ekf2/EKF/position_fusion.cpp index d8362b5fceda..3ae92a6b6dd5 100644 --- a/src/modules/ekf2/EKF/position_fusion.cpp +++ b/src/modules/ekf2/EKF/position_fusion.cpp @@ -161,12 +161,9 @@ void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_v #if defined(CONFIG_EKF2_GNSS) _gps_hgt_b_est.setBias(_gps_hgt_b_est.getBias() + delta_z); #endif // CONFIG_EKF2_GNSS -#if defined(CONFIG_EKF2_RANGE_FINDER) - _rng_hgt_b_est.setBias(_rng_hgt_b_est.getBias() + delta_z); -#endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_TERRAIN) - terrainHandleVerticalPositionReset(delta_z); + _state.terrain += delta_z; #endif // Reset the timout timer diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py index 452d9f565b19..4d8b5278dbcf 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py @@ -68,7 +68,8 @@ accel_bias = sf.V3(), mag_I = sf.V3(), mag_B = sf.V3(), - wind_vel = sf.V2() + wind_vel = sf.V2(), + terrain = sf.V1() ) if args.disable_mag: @@ -132,7 +133,8 @@ def predict_covariance( accel_bias = sf.V3.symbolic("delta_a_b"), mag_I = sf.V3.symbolic("mag_I"), mag_B = sf.V3.symbolic("mag_B"), - wind_vel = sf.V2.symbolic("wind_vel") + wind_vel = sf.V2.symbolic("wind_vel"), + terrain = sf.V1.symbolic("terrain") ) if args.disable_mag: @@ -456,7 +458,10 @@ def compute_mag_declination_pred_innov_var_and_h( return (meas_pred, innov_var, H.T) -def predict_opt_flow(state, distance, epsilon): +def predict_hagl(state): + return state["terrain"][0] - state["pos"][2] + +def predict_opt_flow(state, epsilon): R_to_body = state["quat_nominal"].inverse() # Calculate earth relative velocity in a non-rotating sensor frame @@ -464,23 +469,23 @@ def predict_opt_flow(state, distance, epsilon): # Divide by range to get predicted angular LOS rates relative to X and Y # axes. Note these are rates in a non-rotating sensor frame + hagl = predict_hagl(state) + hagl = add_epsilon_sign(hagl, hagl, epsilon) + R_to_earth = state["quat_nominal"].to_rotation_matrix() flow_pred = sf.V2() - flow_pred[0] = rel_vel_sensor[1] / distance - flow_pred[1] = -rel_vel_sensor[0] / distance - flow_pred = add_epsilon_sign(flow_pred, distance, epsilon) + flow_pred[0] = rel_vel_sensor[1] / hagl * R_to_earth[2, 2] + flow_pred[1] = -rel_vel_sensor[0] / hagl * R_to_earth[2, 2] return flow_pred - def compute_flow_xy_innov_var_and_hx( state: VState, P: MTangent, - distance: sf.Scalar, R: sf.Scalar, epsilon: sf.Scalar ) -> (sf.V2, VTangent): state = vstate_to_state(state) - meas_pred = predict_opt_flow(state, distance, epsilon); + meas_pred = predict_opt_flow(state, epsilon) innov_var = sf.V2() Hx = jacobian_chain_rule(meas_pred[0], state) @@ -493,18 +498,40 @@ def compute_flow_xy_innov_var_and_hx( def compute_flow_y_innov_var_and_h( state: VState, P: MTangent, - distance: sf.Scalar, R: sf.Scalar, epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): state = vstate_to_state(state) - meas_pred = predict_opt_flow(state, distance, epsilon); + meas_pred = predict_opt_flow(state, epsilon) Hy = jacobian_chain_rule(meas_pred[1], state) innov_var = (Hy * P * Hy.T + R)[0,0] return (innov_var, Hy.T) +def compute_hagl_innov_var( + P: MTangent, + R: sf.Scalar, +) -> (sf.Scalar): + state = VState.symbolic("state") + state = vstate_to_state(state) + meas_pred = predict_hagl(state) + + H = jacobian_chain_rule(meas_pred, state) + innov_var = (H * P * H.T + R)[0,0] + + return (innov_var) + +def compute_hagl_h( +) -> (VTangent): + state = VState.symbolic("state") + state = vstate_to_state(state) + meas_pred = predict_hagl(state) + + H = jacobian_chain_rule(meas_pred, state) + + return (H.T) + def compute_gnss_yaw_pred_innov_var_and_h( state: VState, P: MTangent, @@ -664,6 +691,8 @@ def compute_gravity_z_innov_var_and_h( generate_px4_function(compute_yaw_innov_var_and_h, output_names=["innov_var", "H"]) generate_px4_function(compute_flow_xy_innov_var_and_hx, output_names=["innov_var", "H"]) generate_px4_function(compute_flow_y_innov_var_and_h, output_names=["innov_var", "H"]) +generate_px4_function(compute_hagl_innov_var, output_names=["innov_var"]) +generate_px4_function(compute_hagl_h, output_names=["H"]) generate_px4_function(compute_gnss_yaw_pred_innov_var_and_h, output_names=["meas_pred", "innov_var", "H"]) generate_px4_function(compute_gravity_xyz_innov_var_and_hx, output_names=["innov_var", "Hx"]) generate_px4_function(compute_gravity_y_innov_var_and_h, output_names=["innov_var", "Hy"]) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h index cc2c18cd6394..52bb16353d36 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h @@ -16,21 +16,21 @@ namespace sym { * Symbolic function: compute_airspeed_h_and_k * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * innov_var: Scalar * epsilon: Scalar * * Outputs: - * H: Matrix23_1 - * K: Matrix23_1 + * H: Matrix24_1 + * K: Matrix24_1 */ template -void ComputeAirspeedHAndK(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar innov_var, - const Scalar epsilon, matrix::Matrix* const H = nullptr, - matrix::Matrix* const K = nullptr) { - // Total ops: 246 +void ComputeAirspeedHAndK(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar innov_var, + const Scalar epsilon, matrix::Matrix* const H = nullptr, + matrix::Matrix* const K = nullptr) { + // Total ops: 256 // Input arrays @@ -47,7 +47,7 @@ void ComputeAirspeedHAndK(const matrix::Matrix& state, // Output terms (2) if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); @@ -59,7 +59,7 @@ void ComputeAirspeedHAndK(const matrix::Matrix& state, } if (K != nullptr) { - matrix::Matrix& _k = (*K); + matrix::Matrix& _k = (*K); _k(0, 0) = _tmp6 * (-P(0, 21) * _tmp3 - P(0, 22) * _tmp4 + P(0, 3) * _tmp3 + P(0, 4) * _tmp4 + P(0, 5) * _tmp5); @@ -107,6 +107,8 @@ void ComputeAirspeedHAndK(const matrix::Matrix& state, P(21, 4) * _tmp4 + P(21, 5) * _tmp5); _k(22, 0) = _tmp6 * (-P(22, 21) * _tmp3 - P(22, 22) * _tmp4 + P(22, 3) * _tmp3 + P(22, 4) * _tmp4 + P(22, 5) * _tmp5); + _k(23, 0) = _tmp6 * (-P(23, 21) * _tmp3 - P(23, 22) * _tmp4 + P(23, 3) * _tmp3 + + P(23, 4) * _tmp4 + P(23, 5) * _tmp5); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h index 34c059b56208..e97088d173cf 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h @@ -16,8 +16,8 @@ namespace sym { * Symbolic function: compute_airspeed_innov_and_innov_var * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * airspeed: Scalar * R: Scalar * epsilon: Scalar @@ -27,8 +27,8 @@ namespace sym { * innov_var: Scalar */ template -void ComputeAirspeedInnovAndInnovVar(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar airspeed, +void ComputeAirspeedInnovAndInnovVar(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar airspeed, const Scalar R, const Scalar epsilon, Scalar* const innov = nullptr, Scalar* const innov_var = nullptr) { diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h index 1b7c762f2c14..6dba76add33f 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_h.h @@ -16,8 +16,8 @@ namespace sym { * Symbolic function: compute_drag_x_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * rho: Scalar * cd: Scalar * cm: Scalar @@ -26,14 +26,14 @@ namespace sym { * * Outputs: * innov_var: Scalar - * Hx: Matrix23_1 + * Hx: Matrix24_1 */ template -void ComputeDragXInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar rho, +void ComputeDragXInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar rho, const Scalar cd, const Scalar cm, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const Hx = nullptr) { + matrix::Matrix* const Hx = nullptr) { // Total ops: 357 // Input arrays @@ -162,7 +162,7 @@ void ComputeDragXInnovVarAndH(const matrix::Matrix& state, } if (Hx != nullptr) { - matrix::Matrix& _hx = (*Hx); + matrix::Matrix& _hx = (*Hx); _hx.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h index 505f4ed4deed..a7bf92840c16 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_h.h @@ -16,8 +16,8 @@ namespace sym { * Symbolic function: compute_drag_y_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * rho: Scalar * cd: Scalar * cm: Scalar @@ -26,14 +26,14 @@ namespace sym { * * Outputs: * innov_var: Scalar - * Hy: Matrix23_1 + * Hy: Matrix24_1 */ template -void ComputeDragYInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar rho, +void ComputeDragYInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar rho, const Scalar cd, const Scalar cm, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const Hy = nullptr) { + matrix::Matrix* const Hy = nullptr) { // Total ops: 360 // Input arrays @@ -162,7 +162,7 @@ void ComputeDragYInnovVarAndH(const matrix::Matrix& state, } if (Hy != nullptr) { - matrix::Matrix& _hy = (*Hy); + matrix::Matrix& _hy = (*Hy); _hy.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h index 856096baf1a4..75809345d968 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h @@ -16,117 +16,153 @@ namespace sym { * Symbolic function: compute_flow_xy_innov_var_and_hx * * Args: - * state: Matrix24_1 - * P: Matrix23_23 - * distance: Scalar + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Matrix21 - * H: Matrix23_1 + * H: Matrix24_1 */ template -void ComputeFlowXyInnovVarAndHx(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar distance, - const Scalar R, const Scalar epsilon, +void ComputeFlowXyInnovVarAndHx(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, + const Scalar epsilon, matrix::Matrix* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 275 + matrix::Matrix* const H = nullptr) { + // Total ops: 431 // Input arrays - // Intermediate terms (42) - const Scalar _tmp0 = 2 * state(4, 0); - const Scalar _tmp1 = 2 * state(1, 0); - const Scalar _tmp2 = _tmp1 * state(6, 0); - const Scalar _tmp3 = -_tmp0 * state(3, 0) + _tmp2; - const Scalar _tmp4 = - Scalar(1.0) / - (distance + epsilon * (2 * math::min(0, (((distance) > 0) - ((distance) < 0))) + 1)); - const Scalar _tmp5 = (Scalar(1) / Scalar(2)) * _tmp4; - const Scalar _tmp6 = _tmp5 * state(2, 0); - const Scalar _tmp7 = 2 * state(3, 0) * state(6, 0); - const Scalar _tmp8 = _tmp5 * (_tmp0 * state(1, 0) + _tmp7); - const Scalar _tmp9 = 2 * state(0, 0); - const Scalar _tmp10 = state(3, 0) * state(5, 0); - const Scalar _tmp11 = 2 * state(2, 0); - const Scalar _tmp12 = _tmp11 * state(6, 0); - const Scalar _tmp13 = -4 * _tmp10 + _tmp12 - _tmp9 * state(4, 0); - const Scalar _tmp14 = _tmp5 * state(1, 0); - const Scalar _tmp15 = _tmp9 * state(6, 0); - const Scalar _tmp16 = _tmp0 * state(2, 0) + _tmp15 - 4 * state(1, 0) * state(5, 0); - const Scalar _tmp17 = _tmp5 * state(3, 0); - const Scalar _tmp18 = -_tmp13 * _tmp14 + _tmp16 * _tmp17 - _tmp3 * _tmp6 + _tmp8 * state(0, 0); - const Scalar _tmp19 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp20 = _tmp4 * (_tmp19 - 2 * std::pow(state(1, 0), Scalar(2))); - const Scalar _tmp21 = _tmp3 * _tmp5; - const Scalar _tmp22 = _tmp5 * state(0, 0); - const Scalar _tmp23 = - _tmp13 * _tmp6 + _tmp16 * _tmp22 - _tmp21 * state(1, 0) - _tmp8 * state(3, 0); - const Scalar _tmp24 = - _tmp13 * _tmp22 - _tmp16 * _tmp6 - _tmp21 * state(3, 0) + _tmp8 * state(1, 0); - const Scalar _tmp25 = _tmp9 * state(3, 0); - const Scalar _tmp26 = _tmp1 * state(2, 0); - const Scalar _tmp27 = _tmp4 * (-_tmp25 + _tmp26); - const Scalar _tmp28 = _tmp4 * (_tmp11 * state(3, 0) + _tmp9 * state(1, 0)); - const Scalar _tmp29 = _tmp4 * (_tmp19 - 2 * std::pow(state(2, 0), Scalar(2))); - const Scalar _tmp30 = 4 * state(4, 0); - const Scalar _tmp31 = _tmp2 - _tmp30 * state(3, 0) + _tmp9 * state(5, 0); - const Scalar _tmp32 = 2 * state(5, 0); - const Scalar _tmp33 = -_tmp15 - _tmp30 * state(2, 0) + _tmp32 * state(1, 0); - const Scalar _tmp34 = _tmp32 * state(2, 0) + _tmp7; - const Scalar _tmp35 = 2 * _tmp10 - _tmp12; - const Scalar _tmp36 = _tmp35 * _tmp5; - const Scalar _tmp37 = _tmp17 * _tmp33 - _tmp22 * _tmp34 - _tmp31 * _tmp6 + _tmp36 * state(1, 0); - const Scalar _tmp38 = -_tmp14 * _tmp33 - _tmp22 * _tmp31 + _tmp34 * _tmp6 + _tmp36 * state(3, 0); - const Scalar _tmp39 = _tmp14 * _tmp31 - _tmp17 * _tmp34 - _tmp22 * _tmp33 + _tmp35 * _tmp6; - const Scalar _tmp40 = _tmp4 * (_tmp25 + _tmp26); - const Scalar _tmp41 = _tmp4 * (_tmp1 * state(3, 0) - _tmp9 * state(2, 0)); + // Intermediate terms (66) + const Scalar _tmp0 = state(2, 0) * state(4, 0); + const Scalar _tmp1 = state(1, 0) * state(5, 0); + const Scalar _tmp2 = 2 * state(6, 0); + const Scalar _tmp3 = _tmp2 * state(0, 0); + const Scalar _tmp4 = -2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp5 = 1 - 2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp6 = _tmp4 + _tmp5; + const Scalar _tmp7 = state(24, 0) - state(9, 0); + const Scalar _tmp8 = + _tmp7 + epsilon * (2 * math::min(0, (((_tmp7) > 0) - ((_tmp7) < 0))) + 1); + const Scalar _tmp9 = Scalar(1.0) / (_tmp8); + const Scalar _tmp10 = _tmp6 * _tmp9; + const Scalar _tmp11 = 2 * state(0, 0) * state(3, 0); + const Scalar _tmp12 = 2 * state(1, 0); + const Scalar _tmp13 = _tmp12 * state(2, 0); + const Scalar _tmp14 = -_tmp11 + _tmp13; + const Scalar _tmp15 = 2 * state(2, 0); + const Scalar _tmp16 = _tmp12 * state(0, 0) + _tmp15 * state(3, 0); + const Scalar _tmp17 = -2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp18 = _tmp17 + _tmp5; + const Scalar _tmp19 = _tmp14 * state(4, 0) + _tmp16 * state(6, 0) + _tmp18 * state(5, 0); + const Scalar _tmp20 = 4 * _tmp9; + const Scalar _tmp21 = _tmp19 * _tmp20; + const Scalar _tmp22 = _tmp10 * (2 * _tmp0 - 4 * _tmp1 + _tmp3) - _tmp21 * state(1, 0); + const Scalar _tmp23 = (Scalar(1) / Scalar(2)) * _tmp22; + const Scalar _tmp24 = 2 * state(4, 0); + const Scalar _tmp25 = 4 * state(3, 0); + const Scalar _tmp26 = _tmp2 * state(2, 0); + const Scalar _tmp27 = -_tmp24 * state(0, 0) - _tmp25 * state(5, 0) + _tmp26; + const Scalar _tmp28 = (Scalar(1) / Scalar(2)) * _tmp10; + const Scalar _tmp29 = _tmp28 * state(0, 0); + const Scalar _tmp30 = (Scalar(1) / Scalar(2)) * state(3, 0); + const Scalar _tmp31 = _tmp2 * state(1, 0); + const Scalar _tmp32 = _tmp10 * (-_tmp24 * state(3, 0) + _tmp31); + const Scalar _tmp33 = _tmp2 * state(3, 0); + const Scalar _tmp34 = _tmp10 * (_tmp24 * state(1, 0) + _tmp33) - _tmp21 * state(2, 0); + const Scalar _tmp35 = (Scalar(1) / Scalar(2)) * _tmp34; + const Scalar _tmp36 = + -_tmp23 * state(2, 0) + _tmp27 * _tmp29 - _tmp30 * _tmp32 + _tmp35 * state(1, 0); + const Scalar _tmp37 = _tmp10 * _tmp14; + const Scalar _tmp38 = _tmp28 * state(2, 0); + const Scalar _tmp39 = (Scalar(1) / Scalar(2)) * _tmp32; + const Scalar _tmp40 = + _tmp23 * state(0, 0) + _tmp27 * _tmp38 - _tmp30 * _tmp34 - _tmp39 * state(1, 0); + const Scalar _tmp41 = _tmp28 * state(1, 0); + const Scalar _tmp42 = + _tmp22 * _tmp30 - _tmp27 * _tmp41 + _tmp35 * state(0, 0) - _tmp39 * state(2, 0); + const Scalar _tmp43 = _tmp10 * _tmp18; + const Scalar _tmp44 = _tmp6 / std::pow(_tmp8, Scalar(2)); + const Scalar _tmp45 = _tmp19 * _tmp44; + const Scalar _tmp46 = _tmp10 * _tmp16; + const Scalar _tmp47 = _tmp12 * state(3, 0) - _tmp15 * state(0, 0); + const Scalar _tmp48 = _tmp10 * _tmp47; + const Scalar _tmp49 = _tmp11 + _tmp13; + const Scalar _tmp50 = _tmp10 * _tmp49; + const Scalar _tmp51 = _tmp17 + _tmp4 + 1; + const Scalar _tmp52 = _tmp10 * _tmp51; + const Scalar _tmp53 = _tmp47 * state(6, 0) + _tmp49 * state(5, 0) + _tmp51 * state(4, 0); + const Scalar _tmp54 = _tmp20 * _tmp53; + const Scalar _tmp55 = 2 * state(5, 0); + const Scalar _tmp56 = -_tmp10 * (_tmp33 + _tmp55 * state(2, 0)) + _tmp54 * state(1, 0); + const Scalar _tmp57 = -_tmp10 * (-4 * _tmp0 + 2 * _tmp1 - _tmp3) + _tmp54 * state(2, 0); + const Scalar _tmp58 = (Scalar(1) / Scalar(2)) * _tmp57; + const Scalar _tmp59 = -_tmp25 * state(4, 0) + _tmp31 + _tmp55 * state(0, 0); + const Scalar _tmp60 = -_tmp26 + _tmp55 * state(3, 0); + const Scalar _tmp61 = _tmp30 * _tmp56 + _tmp38 * _tmp60 + _tmp41 * _tmp59 + _tmp58 * state(0, 0); + const Scalar _tmp62 = (Scalar(1) / Scalar(2)) * _tmp56; + const Scalar _tmp63 = -_tmp30 * _tmp57 - _tmp38 * _tmp59 + _tmp41 * _tmp60 + _tmp62 * state(0, 0); + const Scalar _tmp64 = + _tmp10 * _tmp30 * _tmp60 - _tmp29 * _tmp59 + _tmp58 * state(1, 0) - _tmp62 * state(2, 0); + const Scalar _tmp65 = _tmp44 * _tmp53; // Output terms (2) if (innov_var != nullptr) { matrix::Matrix& _innov_var = (*innov_var); - _innov_var(0, 0) = R + - _tmp18 * (P(0, 1) * _tmp23 + P(1, 1) * _tmp18 + P(2, 1) * _tmp24 + - P(3, 1) * _tmp27 + P(4, 1) * _tmp20 + P(5, 1) * _tmp28) + - _tmp20 * (P(0, 4) * _tmp23 + P(1, 4) * _tmp18 + P(2, 4) * _tmp24 + - P(3, 4) * _tmp27 + P(4, 4) * _tmp20 + P(5, 4) * _tmp28) + - _tmp23 * (P(0, 0) * _tmp23 + P(1, 0) * _tmp18 + P(2, 0) * _tmp24 + - P(3, 0) * _tmp27 + P(4, 0) * _tmp20 + P(5, 0) * _tmp28) + - _tmp24 * (P(0, 2) * _tmp23 + P(1, 2) * _tmp18 + P(2, 2) * _tmp24 + - P(3, 2) * _tmp27 + P(4, 2) * _tmp20 + P(5, 2) * _tmp28) + - _tmp27 * (P(0, 3) * _tmp23 + P(1, 3) * _tmp18 + P(2, 3) * _tmp24 + - P(3, 3) * _tmp27 + P(4, 3) * _tmp20 + P(5, 3) * _tmp28) + - _tmp28 * (P(0, 5) * _tmp23 + P(1, 5) * _tmp18 + P(2, 5) * _tmp24 + - P(3, 5) * _tmp27 + P(4, 5) * _tmp20 + P(5, 5) * _tmp28); - _innov_var(1, 0) = R - - _tmp29 * (P(0, 3) * _tmp37 + P(1, 3) * _tmp39 + P(2, 3) * _tmp38 - - P(3, 3) * _tmp29 - P(4, 3) * _tmp40 - P(5, 3) * _tmp41) + - _tmp37 * (P(0, 0) * _tmp37 + P(1, 0) * _tmp39 + P(2, 0) * _tmp38 - - P(3, 0) * _tmp29 - P(4, 0) * _tmp40 - P(5, 0) * _tmp41) + - _tmp38 * (P(0, 2) * _tmp37 + P(1, 2) * _tmp39 + P(2, 2) * _tmp38 - - P(3, 2) * _tmp29 - P(4, 2) * _tmp40 - P(5, 2) * _tmp41) + - _tmp39 * (P(0, 1) * _tmp37 + P(1, 1) * _tmp39 + P(2, 1) * _tmp38 - - P(3, 1) * _tmp29 - P(4, 1) * _tmp40 - P(5, 1) * _tmp41) - - _tmp40 * (P(0, 4) * _tmp37 + P(1, 4) * _tmp39 + P(2, 4) * _tmp38 - - P(3, 4) * _tmp29 - P(4, 4) * _tmp40 - P(5, 4) * _tmp41) - - _tmp41 * (P(0, 5) * _tmp37 + P(1, 5) * _tmp39 + P(2, 5) * _tmp38 - - P(3, 5) * _tmp29 - P(4, 5) * _tmp40 - P(5, 5) * _tmp41); + _innov_var(0, 0) = + R + + _tmp36 * (P(0, 2) * _tmp40 + P(1, 2) * _tmp42 + P(2, 2) * _tmp36 - P(23, 2) * _tmp45 + + P(3, 2) * _tmp37 + P(4, 2) * _tmp43 + P(5, 2) * _tmp46 + P(8, 2) * _tmp45) + + _tmp37 * (P(0, 3) * _tmp40 + P(1, 3) * _tmp42 + P(2, 3) * _tmp36 - P(23, 3) * _tmp45 + + P(3, 3) * _tmp37 + P(4, 3) * _tmp43 + P(5, 3) * _tmp46 + P(8, 3) * _tmp45) + + _tmp40 * (P(0, 0) * _tmp40 + P(1, 0) * _tmp42 + P(2, 0) * _tmp36 - P(23, 0) * _tmp45 + + P(3, 0) * _tmp37 + P(4, 0) * _tmp43 + P(5, 0) * _tmp46 + P(8, 0) * _tmp45) + + _tmp42 * (P(0, 1) * _tmp40 + P(1, 1) * _tmp42 + P(2, 1) * _tmp36 - P(23, 1) * _tmp45 + + P(3, 1) * _tmp37 + P(4, 1) * _tmp43 + P(5, 1) * _tmp46 + P(8, 1) * _tmp45) + + _tmp43 * (P(0, 4) * _tmp40 + P(1, 4) * _tmp42 + P(2, 4) * _tmp36 - P(23, 4) * _tmp45 + + P(3, 4) * _tmp37 + P(4, 4) * _tmp43 + P(5, 4) * _tmp46 + P(8, 4) * _tmp45) - + _tmp45 * (P(0, 23) * _tmp40 + P(1, 23) * _tmp42 + P(2, 23) * _tmp36 - P(23, 23) * _tmp45 + + P(3, 23) * _tmp37 + P(4, 23) * _tmp43 + P(5, 23) * _tmp46 + P(8, 23) * _tmp45) + + _tmp45 * (P(0, 8) * _tmp40 + P(1, 8) * _tmp42 + P(2, 8) * _tmp36 - P(23, 8) * _tmp45 + + P(3, 8) * _tmp37 + P(4, 8) * _tmp43 + P(5, 8) * _tmp46 + P(8, 8) * _tmp45) + + _tmp46 * (P(0, 5) * _tmp40 + P(1, 5) * _tmp42 + P(2, 5) * _tmp36 - P(23, 5) * _tmp45 + + P(3, 5) * _tmp37 + P(4, 5) * _tmp43 + P(5, 5) * _tmp46 + P(8, 5) * _tmp45); + _innov_var(1, 0) = + R - + _tmp48 * (P(0, 5) * _tmp63 + P(1, 5) * _tmp61 + P(2, 5) * _tmp64 + P(23, 5) * _tmp65 - + P(3, 5) * _tmp52 - P(4, 5) * _tmp50 - P(5, 5) * _tmp48 - P(8, 5) * _tmp65) - + _tmp50 * (P(0, 4) * _tmp63 + P(1, 4) * _tmp61 + P(2, 4) * _tmp64 + P(23, 4) * _tmp65 - + P(3, 4) * _tmp52 - P(4, 4) * _tmp50 - P(5, 4) * _tmp48 - P(8, 4) * _tmp65) - + _tmp52 * (P(0, 3) * _tmp63 + P(1, 3) * _tmp61 + P(2, 3) * _tmp64 + P(23, 3) * _tmp65 - + P(3, 3) * _tmp52 - P(4, 3) * _tmp50 - P(5, 3) * _tmp48 - P(8, 3) * _tmp65) + + _tmp61 * (P(0, 1) * _tmp63 + P(1, 1) * _tmp61 + P(2, 1) * _tmp64 + P(23, 1) * _tmp65 - + P(3, 1) * _tmp52 - P(4, 1) * _tmp50 - P(5, 1) * _tmp48 - P(8, 1) * _tmp65) + + _tmp63 * (P(0, 0) * _tmp63 + P(1, 0) * _tmp61 + P(2, 0) * _tmp64 + P(23, 0) * _tmp65 - + P(3, 0) * _tmp52 - P(4, 0) * _tmp50 - P(5, 0) * _tmp48 - P(8, 0) * _tmp65) + + _tmp64 * (P(0, 2) * _tmp63 + P(1, 2) * _tmp61 + P(2, 2) * _tmp64 + P(23, 2) * _tmp65 - + P(3, 2) * _tmp52 - P(4, 2) * _tmp50 - P(5, 2) * _tmp48 - P(8, 2) * _tmp65) + + _tmp65 * (P(0, 23) * _tmp63 + P(1, 23) * _tmp61 + P(2, 23) * _tmp64 + P(23, 23) * _tmp65 - + P(3, 23) * _tmp52 - P(4, 23) * _tmp50 - P(5, 23) * _tmp48 - P(8, 23) * _tmp65) - + _tmp65 * (P(0, 8) * _tmp63 + P(1, 8) * _tmp61 + P(2, 8) * _tmp64 + P(23, 8) * _tmp65 - + P(3, 8) * _tmp52 - P(4, 8) * _tmp50 - P(5, 8) * _tmp48 - P(8, 8) * _tmp65); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp23; - _h(1, 0) = _tmp18; - _h(2, 0) = _tmp24; - _h(3, 0) = _tmp27; - _h(4, 0) = _tmp20; - _h(5, 0) = _tmp28; + _h(0, 0) = _tmp40; + _h(1, 0) = _tmp42; + _h(2, 0) = _tmp36; + _h(3, 0) = _tmp37; + _h(4, 0) = _tmp43; + _h(5, 0) = _tmp46; + _h(8, 0) = _tmp45; + _h(23, 0) = -_tmp45; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h index 2de18c1f1877..178f6d75e64f 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h @@ -16,85 +16,100 @@ namespace sym { * Symbolic function: compute_flow_y_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 - * distance: Scalar + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix23_1 + * H: Matrix24_1 */ template -void ComputeFlowYInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar distance, - const Scalar R, const Scalar epsilon, - Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 151 +void ComputeFlowYInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, + const Scalar epsilon, Scalar* const innov_var = nullptr, + matrix::Matrix* const H = nullptr) { + // Total ops: 232 // Input arrays - // Intermediate terms (21) - const Scalar _tmp0 = - Scalar(1.0) / - (distance + epsilon * (2 * math::min(0, (((distance) > 0) - ((distance) < 0))) + 1)); - const Scalar _tmp1 = - _tmp0 * (-2 * std::pow(state(2, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1); - const Scalar _tmp2 = 4 * state(4, 0); - const Scalar _tmp3 = 2 * state(0, 0); - const Scalar _tmp4 = 2 * state(6, 0); - const Scalar _tmp5 = -_tmp2 * state(3, 0) + _tmp3 * state(5, 0) + _tmp4 * state(1, 0); - const Scalar _tmp6 = (Scalar(1) / Scalar(2)) * _tmp0; - const Scalar _tmp7 = _tmp5 * _tmp6; - const Scalar _tmp8 = 2 * state(1, 0); - const Scalar _tmp9 = -_tmp2 * state(2, 0) - _tmp4 * state(0, 0) + _tmp8 * state(5, 0); - const Scalar _tmp10 = _tmp6 * _tmp9; - const Scalar _tmp11 = 2 * state(5, 0); - const Scalar _tmp12 = _tmp6 * (_tmp11 * state(2, 0) + _tmp4 * state(3, 0)); - const Scalar _tmp13 = _tmp11 * state(3, 0) - _tmp4 * state(2, 0); - const Scalar _tmp14 = _tmp6 * state(1, 0); - const Scalar _tmp15 = - _tmp10 * state(3, 0) - _tmp12 * state(0, 0) + _tmp13 * _tmp14 - _tmp7 * state(2, 0); - const Scalar _tmp16 = _tmp13 * _tmp6; - const Scalar _tmp17 = - _tmp12 * state(2, 0) - _tmp14 * _tmp9 + _tmp16 * state(3, 0) - _tmp7 * state(0, 0); + // Intermediate terms (28) + const Scalar _tmp0 = 2 * state(0, 0); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = -_tmp0 * state(2, 0) + _tmp1 * state(3, 0); + const Scalar _tmp3 = 1 - 2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp4 = _tmp3 - 2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp5 = state(24, 0) - state(9, 0); + const Scalar _tmp6 = + _tmp5 + epsilon * (2 * math::min(0, (((_tmp5) > 0) - ((_tmp5) < 0))) + 1); + const Scalar _tmp7 = Scalar(1.0) / (_tmp6); + const Scalar _tmp8 = _tmp4 * _tmp7; + const Scalar _tmp9 = _tmp2 * _tmp8; + const Scalar _tmp10 = _tmp0 * state(3, 0) + _tmp1 * state(2, 0); + const Scalar _tmp11 = _tmp10 * _tmp8; + const Scalar _tmp12 = _tmp3 - 2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp13 = _tmp12 * _tmp8; + const Scalar _tmp14 = _tmp10 * state(5, 0) + _tmp12 * state(4, 0) + _tmp2 * state(6, 0); + const Scalar _tmp15 = 4 * _tmp14 * _tmp7; + const Scalar _tmp16 = 2 * state(5, 0); + const Scalar _tmp17 = 2 * state(6, 0); const Scalar _tmp18 = - -_tmp10 * state(0, 0) - _tmp12 * state(3, 0) + _tmp14 * _tmp5 + _tmp16 * state(2, 0); - const Scalar _tmp19 = _tmp0 * (_tmp3 * state(3, 0) + _tmp8 * state(2, 0)); - const Scalar _tmp20 = _tmp0 * (-_tmp3 * state(2, 0) + _tmp8 * state(3, 0)); + (Scalar(1) / Scalar(2)) * _tmp15 * state(1, 0) - + Scalar(1) / Scalar(2) * _tmp8 * (_tmp16 * state(2, 0) + _tmp17 * state(3, 0)); + const Scalar _tmp19 = 4 * state(4, 0); + const Scalar _tmp20 = (Scalar(1) / Scalar(2)) * _tmp15 * state(2, 0) - + Scalar(1) / Scalar(2) * _tmp8 * + (_tmp16 * state(1, 0) - _tmp17 * state(0, 0) - _tmp19 * state(2, 0)); + const Scalar _tmp21 = (Scalar(1) / Scalar(2)) * _tmp8; + const Scalar _tmp22 = + _tmp21 * (_tmp16 * state(0, 0) + _tmp17 * state(1, 0) - _tmp19 * state(3, 0)); + const Scalar _tmp23 = _tmp21 * (_tmp16 * state(3, 0) - _tmp17 * state(2, 0)); + const Scalar _tmp24 = + _tmp18 * state(3, 0) + _tmp20 * state(0, 0) + _tmp22 * state(1, 0) + _tmp23 * state(2, 0); + const Scalar _tmp25 = + _tmp18 * state(0, 0) - _tmp20 * state(3, 0) - _tmp22 * state(2, 0) + _tmp23 * state(1, 0); + const Scalar _tmp26 = + -_tmp18 * state(2, 0) + _tmp20 * state(1, 0) - _tmp22 * state(0, 0) + _tmp23 * state(3, 0); + const Scalar _tmp27 = _tmp14 * _tmp4 / std::pow(_tmp6, Scalar(2)); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = R - - _tmp1 * (P(0, 3) * _tmp15 + P(1, 3) * _tmp18 + P(2, 3) * _tmp17 - P(3, 3) * _tmp1 - - P(4, 3) * _tmp19 - P(5, 3) * _tmp20) + - _tmp15 * (P(0, 0) * _tmp15 + P(1, 0) * _tmp18 + P(2, 0) * _tmp17 - - P(3, 0) * _tmp1 - P(4, 0) * _tmp19 - P(5, 0) * _tmp20) + - _tmp17 * (P(0, 2) * _tmp15 + P(1, 2) * _tmp18 + P(2, 2) * _tmp17 - - P(3, 2) * _tmp1 - P(4, 2) * _tmp19 - P(5, 2) * _tmp20) + - _tmp18 * (P(0, 1) * _tmp15 + P(1, 1) * _tmp18 + P(2, 1) * _tmp17 - - P(3, 1) * _tmp1 - P(4, 1) * _tmp19 - P(5, 1) * _tmp20) - - _tmp19 * (P(0, 4) * _tmp15 + P(1, 4) * _tmp18 + P(2, 4) * _tmp17 - - P(3, 4) * _tmp1 - P(4, 4) * _tmp19 - P(5, 4) * _tmp20) - - _tmp20 * (P(0, 5) * _tmp15 + P(1, 5) * _tmp18 + P(2, 5) * _tmp17 - - P(3, 5) * _tmp1 - P(4, 5) * _tmp19 - P(5, 5) * _tmp20); + _innov_var = + R - + _tmp11 * (P(0, 4) * _tmp25 + P(1, 4) * _tmp24 + P(2, 4) * _tmp26 + P(23, 4) * _tmp27 - + P(3, 4) * _tmp13 - P(4, 4) * _tmp11 - P(5, 4) * _tmp9 - P(8, 4) * _tmp27) - + _tmp13 * (P(0, 3) * _tmp25 + P(1, 3) * _tmp24 + P(2, 3) * _tmp26 + P(23, 3) * _tmp27 - + P(3, 3) * _tmp13 - P(4, 3) * _tmp11 - P(5, 3) * _tmp9 - P(8, 3) * _tmp27) + + _tmp24 * (P(0, 1) * _tmp25 + P(1, 1) * _tmp24 + P(2, 1) * _tmp26 + P(23, 1) * _tmp27 - + P(3, 1) * _tmp13 - P(4, 1) * _tmp11 - P(5, 1) * _tmp9 - P(8, 1) * _tmp27) + + _tmp25 * (P(0, 0) * _tmp25 + P(1, 0) * _tmp24 + P(2, 0) * _tmp26 + P(23, 0) * _tmp27 - + P(3, 0) * _tmp13 - P(4, 0) * _tmp11 - P(5, 0) * _tmp9 - P(8, 0) * _tmp27) + + _tmp26 * (P(0, 2) * _tmp25 + P(1, 2) * _tmp24 + P(2, 2) * _tmp26 + P(23, 2) * _tmp27 - + P(3, 2) * _tmp13 - P(4, 2) * _tmp11 - P(5, 2) * _tmp9 - P(8, 2) * _tmp27) + + _tmp27 * (P(0, 23) * _tmp25 + P(1, 23) * _tmp24 + P(2, 23) * _tmp26 + P(23, 23) * _tmp27 - + P(3, 23) * _tmp13 - P(4, 23) * _tmp11 - P(5, 23) * _tmp9 - P(8, 23) * _tmp27) - + _tmp27 * (P(0, 8) * _tmp25 + P(1, 8) * _tmp24 + P(2, 8) * _tmp26 + P(23, 8) * _tmp27 - + P(3, 8) * _tmp13 - P(4, 8) * _tmp11 - P(5, 8) * _tmp9 - P(8, 8) * _tmp27) - + _tmp9 * (P(0, 5) * _tmp25 + P(1, 5) * _tmp24 + P(2, 5) * _tmp26 + P(23, 5) * _tmp27 - + P(3, 5) * _tmp13 - P(4, 5) * _tmp11 - P(5, 5) * _tmp9 - P(8, 5) * _tmp27); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp15; - _h(1, 0) = _tmp18; - _h(2, 0) = _tmp17; - _h(3, 0) = -_tmp1; - _h(4, 0) = -_tmp19; - _h(5, 0) = -_tmp20; + _h(0, 0) = _tmp25; + _h(1, 0) = _tmp24; + _h(2, 0) = _tmp26; + _h(3, 0) = -_tmp13; + _h(4, 0) = -_tmp11; + _h(5, 0) = -_tmp9; + _h(8, 0) = -_tmp27; + _h(23, 0) = _tmp27; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h index d11b74d3e395..028d7aba5587 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h @@ -16,8 +16,8 @@ namespace sym { * Symbolic function: compute_gnss_yaw_pred_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * antenna_yaw_offset: Scalar * R: Scalar * epsilon: Scalar @@ -25,15 +25,15 @@ namespace sym { * Outputs: * meas_pred: Scalar * innov_var: Scalar - * H: Matrix23_1 + * H: Matrix24_1 */ template -void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, +void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar antenna_yaw_offset, const Scalar R, const Scalar epsilon, Scalar* const meas_pred = nullptr, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { + matrix::Matrix* const H = nullptr) { // Total ops: 114 // Input arrays @@ -93,7 +93,7 @@ void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix& state, } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h index 6d47ae4ab435..a8fc12fe93bd 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_xyz_innov_var_and_hx.h @@ -16,19 +16,19 @@ namespace sym { * Symbolic function: compute_gravity_xyz_innov_var_and_hx * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * * Outputs: * innov_var: Matrix31 - * Hx: Matrix23_1 + * Hx: Matrix24_1 */ template -void ComputeGravityXyzInnovVarAndHx(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeGravityXyzInnovVarAndHx(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, matrix::Matrix* const innov_var = nullptr, - matrix::Matrix* const Hx = nullptr) { + matrix::Matrix* const Hx = nullptr) { // Total ops: 53 // Input arrays @@ -61,7 +61,7 @@ void ComputeGravityXyzInnovVarAndHx(const matrix::Matrix& state, } if (Hx != nullptr) { - matrix::Matrix& _hx = (*Hx); + matrix::Matrix& _hx = (*Hx); _hx.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h index 9aeb442d6970..b562373162f2 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_y_innov_var_and_h.h @@ -16,19 +16,19 @@ namespace sym { * Symbolic function: compute_gravity_y_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * * Outputs: * innov_var: Scalar - * Hy: Matrix23_1 + * Hy: Matrix24_1 */ template -void ComputeGravityYInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeGravityYInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, Scalar* const innov_var = nullptr, - matrix::Matrix* const Hy = nullptr) { + matrix::Matrix* const Hy = nullptr) { // Total ops: 22 // Input arrays @@ -47,7 +47,7 @@ void ComputeGravityYInnovVarAndH(const matrix::Matrix& state, } if (Hy != nullptr) { - matrix::Matrix& _hy = (*Hy); + matrix::Matrix& _hy = (*Hy); _hy.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h index e62e3e7212c3..e5495af10c77 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_z_innov_var_and_h.h @@ -16,19 +16,19 @@ namespace sym { * Symbolic function: compute_gravity_z_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * * Outputs: * innov_var: Scalar - * Hz: Matrix23_1 + * Hz: Matrix24_1 */ template -void ComputeGravityZInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeGravityZInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, Scalar* const innov_var = nullptr, - matrix::Matrix* const Hz = nullptr) { + matrix::Matrix* const Hz = nullptr) { // Total ops: 18 // Input arrays @@ -48,7 +48,7 @@ void ComputeGravityZInnovVarAndH(const matrix::Matrix& state, } if (Hz != nullptr) { - matrix::Matrix& _hz = (*Hz); + matrix::Matrix& _hz = (*Hz); _hz.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_h.h new file mode 100644 index 000000000000..2f66cebf47b7 --- /dev/null +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_h.h @@ -0,0 +1,43 @@ +// ----------------------------------------------------------------------------- +// This file was autogenerated by symforce from template: +// function/FUNCTION.h.jinja +// Do NOT modify by hand. +// ----------------------------------------------------------------------------- + +#pragma once + +#include + +namespace sym { + +/** + * This function was autogenerated from a symbolic function. Do not modify by hand. + * + * Symbolic function: compute_hagl_h + * + * Args: + * + * Outputs: + * H: Matrix24_1 + */ +template +void ComputeHaglH(matrix::Matrix* const H = nullptr) { + // Total ops: 0 + + // Input arrays + + // Intermediate terms (0) + + // Output terms (1) + if (H != nullptr) { + matrix::Matrix& _h = (*H); + + _h.setZero(); + + _h(8, 0) = -1; + _h(23, 0) = 1; + } +} // NOLINT(readability/fn_size) + +// NOLINTNEXTLINE(readability/fn_size) +} // namespace sym diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_innov_var.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_innov_var.h new file mode 100644 index 000000000000..fd50c97cf5d4 --- /dev/null +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_hagl_innov_var.h @@ -0,0 +1,43 @@ +// ----------------------------------------------------------------------------- +// This file was autogenerated by symforce from template: +// function/FUNCTION.h.jinja +// Do NOT modify by hand. +// ----------------------------------------------------------------------------- + +#pragma once + +#include + +namespace sym { + +/** + * This function was autogenerated from a symbolic function. Do not modify by hand. + * + * Symbolic function: compute_hagl_innov_var + * + * Args: + * P: Matrix24_24 + * R: Scalar + * + * Outputs: + * innov_var: Scalar + */ +template +void ComputeHaglInnovVar(const matrix::Matrix& P, const Scalar R, + Scalar* const innov_var = nullptr) { + // Total ops: 4 + + // Input arrays + + // Intermediate terms (0) + + // Output terms (1) + if (innov_var != nullptr) { + Scalar& _innov_var = (*innov_var); + + _innov_var = P(23, 23) - P(23, 8) - P(8, 23) + P(8, 8) + R; + } +} // NOLINT(readability/fn_size) + +// NOLINTNEXTLINE(readability/fn_size) +} // namespace sym diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h index 009892f6d9d1..803bf45e875e 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h @@ -16,22 +16,22 @@ namespace sym { * Symbolic function: compute_mag_declination_pred_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * epsilon: Scalar * * Outputs: * pred: Scalar * innov_var: Scalar - * H: Matrix23_1 + * H: Matrix24_1 */ template -void ComputeMagDeclinationPredInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeMagDeclinationPredInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const pred = nullptr, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { + matrix::Matrix* const H = nullptr) { // Total ops: 22 // Input arrays @@ -59,7 +59,7 @@ void ComputeMagDeclinationPredInnovVarAndH(const matrix::Matrix& } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h index bdad52b5a5b9..4ff8368c4964 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h @@ -16,8 +16,8 @@ namespace sym { * Symbolic function: compute_mag_innov_innov_var_and_hx * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * meas: Matrix31 * R: Scalar * epsilon: Scalar @@ -25,16 +25,16 @@ namespace sym { * Outputs: * innov: Matrix31 * innov_var: Matrix31 - * Hx: Matrix23_1 + * Hx: Matrix24_1 */ template -void ComputeMagInnovInnovVarAndHx(const matrix::Matrix& state, - const matrix::Matrix& P, +void ComputeMagInnovInnovVarAndHx(const matrix::Matrix& state, + const matrix::Matrix& P, const matrix::Matrix& meas, const Scalar R, const Scalar epsilon, matrix::Matrix* const innov = nullptr, matrix::Matrix* const innov_var = nullptr, - matrix::Matrix* const Hx = nullptr) { + matrix::Matrix* const Hx = nullptr) { // Total ops: 461 // Unused inputs @@ -185,7 +185,7 @@ void ComputeMagInnovInnovVarAndHx(const matrix::Matrix& state, } if (Hx != nullptr) { - matrix::Matrix& _hx = (*Hx); + matrix::Matrix& _hx = (*Hx); _hx.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h index a490ca61eabc..697cd92a8243 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h @@ -16,20 +16,20 @@ namespace sym { * Symbolic function: compute_mag_y_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix23_1 + * H: Matrix24_1 */ template -void ComputeMagYInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeMagYInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { + matrix::Matrix* const H = nullptr) { // Total ops: 159 // Unused inputs @@ -85,7 +85,7 @@ void ComputeMagYInnovVarAndH(const matrix::Matrix& state, } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h index 0abdc1d9ca7f..1432222d4756 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h @@ -16,20 +16,20 @@ namespace sym { * Symbolic function: compute_mag_z_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix23_1 + * H: Matrix24_1 */ template -void ComputeMagZInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeMagZInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { + matrix::Matrix* const H = nullptr) { // Total ops: 161 // Unused inputs @@ -85,7 +85,7 @@ void ComputeMagZInnovVarAndH(const matrix::Matrix& state, } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h index 1cd242c727e5..002be9bbe8e9 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h @@ -16,169 +16,172 @@ namespace sym { * Symbolic function: compute_sideslip_h_and_k * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * innov_var: Scalar * epsilon: Scalar * * Outputs: - * H: Matrix23_1 - * K: Matrix23_1 + * H: Matrix24_1 + * K: Matrix24_1 */ template -void ComputeSideslipHAndK(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar innov_var, - const Scalar epsilon, matrix::Matrix* const H = nullptr, - matrix::Matrix* const K = nullptr) { - // Total ops: 497 +void ComputeSideslipHAndK(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar innov_var, + const Scalar epsilon, matrix::Matrix* const H = nullptr, + matrix::Matrix* const K = nullptr) { + // Total ops: 513 // Input arrays - // Intermediate terms (45) + // Intermediate terms (43) const Scalar _tmp0 = -state(23, 0) + state(5, 0); const Scalar _tmp1 = 2 * state(1, 0); const Scalar _tmp2 = -state(22, 0) + state(4, 0); - const Scalar _tmp3 = 2 * state(6, 0); - const Scalar _tmp4 = _tmp3 * state(0, 0); - const Scalar _tmp5 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp6 = _tmp5 - 2 * std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp7 = 2 * state(0, 0); - const Scalar _tmp8 = _tmp7 * state(3, 0); - const Scalar _tmp9 = 2 * state(2, 0); - const Scalar _tmp10 = _tmp9 * state(1, 0); - const Scalar _tmp11 = _tmp10 + _tmp8; - const Scalar _tmp12 = _tmp1 * state(3, 0) - _tmp9 * state(0, 0); - const Scalar _tmp13 = _tmp0 * _tmp11 + _tmp12 * state(6, 0) + _tmp2 * _tmp6; - const Scalar _tmp14 = - _tmp13 + epsilon * (2 * math::min(0, (((_tmp13) > 0) - ((_tmp13) < 0))) + 1); - const Scalar _tmp15 = _tmp5 - 2 * std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp16 = _tmp10 - _tmp8; - const Scalar _tmp17 = _tmp7 * state(1, 0) + _tmp9 * state(3, 0); - const Scalar _tmp18 = - (_tmp0 * _tmp15 + _tmp16 * _tmp2 + _tmp17 * state(6, 0)) / std::pow(_tmp14, Scalar(2)); - const Scalar _tmp19 = _tmp3 * state(3, 0); - const Scalar _tmp20 = Scalar(1.0) / (_tmp14); - const Scalar _tmp21 = -_tmp18 * (_tmp0 * _tmp1 - 4 * _tmp2 * state(2, 0) - _tmp4) + - _tmp20 * (_tmp1 * _tmp2 + _tmp19); - const Scalar _tmp22 = (Scalar(1) / Scalar(2)) * state(3, 0); - const Scalar _tmp23 = - -Scalar(1) / Scalar(2) * _tmp18 * (_tmp0 * _tmp9 + _tmp19) + - (Scalar(1) / Scalar(2)) * _tmp20 * (-4 * _tmp0 * state(1, 0) + _tmp2 * _tmp9 + _tmp4); - const Scalar _tmp24 = 2 * state(3, 0); - const Scalar _tmp25 = _tmp3 * state(2, 0); - const Scalar _tmp26 = _tmp3 * state(1, 0); - const Scalar _tmp27 = -_tmp18 * (_tmp0 * _tmp24 - _tmp25) + _tmp20 * (-_tmp2 * _tmp24 + _tmp26); - const Scalar _tmp28 = (Scalar(1) / Scalar(2)) * _tmp27; - const Scalar _tmp29 = 4 * state(3, 0); + const Scalar _tmp3 = 4 * _tmp2; + const Scalar _tmp4 = 2 * state(6, 0); + const Scalar _tmp5 = _tmp4 * state(0, 0); + const Scalar _tmp6 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp7 = _tmp6 - 2 * std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp8 = 2 * state(0, 0); + const Scalar _tmp9 = _tmp8 * state(3, 0); + const Scalar _tmp10 = 2 * state(2, 0); + const Scalar _tmp11 = _tmp10 * state(1, 0); + const Scalar _tmp12 = _tmp11 + _tmp9; + const Scalar _tmp13 = _tmp1 * state(3, 0) - _tmp10 * state(0, 0); + const Scalar _tmp14 = _tmp0 * _tmp12 + _tmp13 * state(6, 0) + _tmp2 * _tmp7; + const Scalar _tmp15 = + _tmp14 + epsilon * (2 * math::min(0, (((_tmp14) > 0) - ((_tmp14) < 0))) + 1); + const Scalar _tmp16 = _tmp6 - 2 * std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp17 = _tmp11 - _tmp9; + const Scalar _tmp18 = _tmp10 * state(3, 0) + _tmp8 * state(1, 0); + const Scalar _tmp19 = + (_tmp0 * _tmp16 + _tmp17 * _tmp2 + _tmp18 * state(6, 0)) / std::pow(_tmp15, Scalar(2)); + const Scalar _tmp20 = _tmp4 * state(3, 0); + const Scalar _tmp21 = Scalar(1.0) / (_tmp15); + const Scalar _tmp22 = + -Scalar(1) / Scalar(2) * _tmp19 * (_tmp0 * _tmp1 - _tmp3 * state(2, 0) - _tmp5) + + (Scalar(1) / Scalar(2)) * _tmp21 * (_tmp1 * _tmp2 + _tmp20); + const Scalar _tmp23 = 4 * _tmp0; + const Scalar _tmp24 = + -Scalar(1) / Scalar(2) * _tmp19 * (_tmp0 * _tmp10 + _tmp20) + + (Scalar(1) / Scalar(2)) * _tmp21 * (_tmp10 * _tmp2 - _tmp23 * state(1, 0) + _tmp5); + const Scalar _tmp25 = 2 * state(3, 0); + const Scalar _tmp26 = _tmp4 * state(2, 0); + const Scalar _tmp27 = _tmp4 * state(1, 0); + const Scalar _tmp28 = -Scalar(1) / Scalar(2) * _tmp19 * (_tmp0 * _tmp25 - _tmp26) + + (Scalar(1) / Scalar(2)) * _tmp21 * (-_tmp2 * _tmp25 + _tmp27); + const Scalar _tmp29 = + -Scalar(1) / Scalar(2) * _tmp19 * (_tmp0 * _tmp8 + _tmp27 - _tmp3 * state(3, 0)) + + (Scalar(1) / Scalar(2)) * _tmp21 * (-_tmp2 * _tmp8 - _tmp23 * state(3, 0) + _tmp26); const Scalar _tmp30 = - -Scalar(1) / Scalar(2) * _tmp18 * (_tmp0 * _tmp7 - _tmp2 * _tmp29 + _tmp26) + - (Scalar(1) / Scalar(2)) * _tmp20 * (-_tmp0 * _tmp29 - _tmp2 * _tmp7 + _tmp25); + -_tmp22 * state(3, 0) + _tmp24 * state(0, 0) - _tmp28 * state(1, 0) + _tmp29 * state(2, 0); const Scalar _tmp31 = - -_tmp21 * _tmp22 + _tmp23 * state(0, 0) - _tmp28 * state(1, 0) + _tmp30 * state(2, 0); - const Scalar _tmp32 = (Scalar(1) / Scalar(2)) * _tmp21; - const Scalar _tmp33 = - _tmp23 * state(3, 0) - _tmp28 * state(2, 0) - _tmp30 * state(1, 0) + _tmp32 * state(0, 0); - const Scalar _tmp34 = - -_tmp22 * _tmp27 - _tmp23 * state(2, 0) + _tmp30 * state(0, 0) + _tmp32 * state(1, 0); - const Scalar _tmp35 = _tmp18 * _tmp6; - const Scalar _tmp36 = _tmp16 * _tmp20; - const Scalar _tmp37 = -_tmp35 + _tmp36; - const Scalar _tmp38 = _tmp11 * _tmp18; - const Scalar _tmp39 = _tmp15 * _tmp20; - const Scalar _tmp40 = -_tmp38 + _tmp39; - const Scalar _tmp41 = -_tmp12 * _tmp18 + _tmp17 * _tmp20; - const Scalar _tmp42 = _tmp35 - _tmp36; - const Scalar _tmp43 = _tmp38 - _tmp39; - const Scalar _tmp44 = Scalar(1.0) / (math::max(epsilon, innov_var)); + _tmp22 * state(0, 0) + _tmp24 * state(3, 0) - _tmp28 * state(2, 0) - _tmp29 * state(1, 0); + const Scalar _tmp32 = + _tmp22 * state(1, 0) - _tmp24 * state(2, 0) - _tmp28 * state(3, 0) + _tmp29 * state(0, 0); + const Scalar _tmp33 = _tmp19 * _tmp7; + const Scalar _tmp34 = _tmp17 * _tmp21; + const Scalar _tmp35 = -_tmp33 + _tmp34; + const Scalar _tmp36 = _tmp12 * _tmp19; + const Scalar _tmp37 = _tmp16 * _tmp21; + const Scalar _tmp38 = -_tmp36 + _tmp37; + const Scalar _tmp39 = -_tmp13 * _tmp19 + _tmp18 * _tmp21; + const Scalar _tmp40 = _tmp33 - _tmp34; + const Scalar _tmp41 = _tmp36 - _tmp37; + const Scalar _tmp42 = Scalar(1.0) / (math::max(epsilon, innov_var)); // Output terms (2) if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp31; - _h(1, 0) = _tmp33; - _h(2, 0) = _tmp34; - _h(3, 0) = _tmp37; - _h(4, 0) = _tmp40; - _h(5, 0) = _tmp41; - _h(21, 0) = _tmp42; - _h(22, 0) = _tmp43; + _h(0, 0) = _tmp30; + _h(1, 0) = _tmp31; + _h(2, 0) = _tmp32; + _h(3, 0) = _tmp35; + _h(4, 0) = _tmp38; + _h(5, 0) = _tmp39; + _h(21, 0) = _tmp40; + _h(22, 0) = _tmp41; } if (K != nullptr) { - matrix::Matrix& _k = (*K); + matrix::Matrix& _k = (*K); _k(0, 0) = - _tmp44 * (P(0, 0) * _tmp31 + P(0, 1) * _tmp33 + P(0, 2) * _tmp34 + P(0, 21) * _tmp42 + - P(0, 22) * _tmp43 + P(0, 3) * _tmp37 + P(0, 4) * _tmp40 + P(0, 5) * _tmp41); + _tmp42 * (P(0, 0) * _tmp30 + P(0, 1) * _tmp31 + P(0, 2) * _tmp32 + P(0, 21) * _tmp40 + + P(0, 22) * _tmp41 + P(0, 3) * _tmp35 + P(0, 4) * _tmp38 + P(0, 5) * _tmp39); _k(1, 0) = - _tmp44 * (P(1, 0) * _tmp31 + P(1, 1) * _tmp33 + P(1, 2) * _tmp34 + P(1, 21) * _tmp42 + - P(1, 22) * _tmp43 + P(1, 3) * _tmp37 + P(1, 4) * _tmp40 + P(1, 5) * _tmp41); + _tmp42 * (P(1, 0) * _tmp30 + P(1, 1) * _tmp31 + P(1, 2) * _tmp32 + P(1, 21) * _tmp40 + + P(1, 22) * _tmp41 + P(1, 3) * _tmp35 + P(1, 4) * _tmp38 + P(1, 5) * _tmp39); _k(2, 0) = - _tmp44 * (P(2, 0) * _tmp31 + P(2, 1) * _tmp33 + P(2, 2) * _tmp34 + P(2, 21) * _tmp42 + - P(2, 22) * _tmp43 + P(2, 3) * _tmp37 + P(2, 4) * _tmp40 + P(2, 5) * _tmp41); + _tmp42 * (P(2, 0) * _tmp30 + P(2, 1) * _tmp31 + P(2, 2) * _tmp32 + P(2, 21) * _tmp40 + + P(2, 22) * _tmp41 + P(2, 3) * _tmp35 + P(2, 4) * _tmp38 + P(2, 5) * _tmp39); _k(3, 0) = - _tmp44 * (P(3, 0) * _tmp31 + P(3, 1) * _tmp33 + P(3, 2) * _tmp34 + P(3, 21) * _tmp42 + - P(3, 22) * _tmp43 + P(3, 3) * _tmp37 + P(3, 4) * _tmp40 + P(3, 5) * _tmp41); + _tmp42 * (P(3, 0) * _tmp30 + P(3, 1) * _tmp31 + P(3, 2) * _tmp32 + P(3, 21) * _tmp40 + + P(3, 22) * _tmp41 + P(3, 3) * _tmp35 + P(3, 4) * _tmp38 + P(3, 5) * _tmp39); _k(4, 0) = - _tmp44 * (P(4, 0) * _tmp31 + P(4, 1) * _tmp33 + P(4, 2) * _tmp34 + P(4, 21) * _tmp42 + - P(4, 22) * _tmp43 + P(4, 3) * _tmp37 + P(4, 4) * _tmp40 + P(4, 5) * _tmp41); + _tmp42 * (P(4, 0) * _tmp30 + P(4, 1) * _tmp31 + P(4, 2) * _tmp32 + P(4, 21) * _tmp40 + + P(4, 22) * _tmp41 + P(4, 3) * _tmp35 + P(4, 4) * _tmp38 + P(4, 5) * _tmp39); _k(5, 0) = - _tmp44 * (P(5, 0) * _tmp31 + P(5, 1) * _tmp33 + P(5, 2) * _tmp34 + P(5, 21) * _tmp42 + - P(5, 22) * _tmp43 + P(5, 3) * _tmp37 + P(5, 4) * _tmp40 + P(5, 5) * _tmp41); + _tmp42 * (P(5, 0) * _tmp30 + P(5, 1) * _tmp31 + P(5, 2) * _tmp32 + P(5, 21) * _tmp40 + + P(5, 22) * _tmp41 + P(5, 3) * _tmp35 + P(5, 4) * _tmp38 + P(5, 5) * _tmp39); _k(6, 0) = - _tmp44 * (P(6, 0) * _tmp31 + P(6, 1) * _tmp33 + P(6, 2) * _tmp34 + P(6, 21) * _tmp42 + - P(6, 22) * _tmp43 + P(6, 3) * _tmp37 + P(6, 4) * _tmp40 + P(6, 5) * _tmp41); + _tmp42 * (P(6, 0) * _tmp30 + P(6, 1) * _tmp31 + P(6, 2) * _tmp32 + P(6, 21) * _tmp40 + + P(6, 22) * _tmp41 + P(6, 3) * _tmp35 + P(6, 4) * _tmp38 + P(6, 5) * _tmp39); _k(7, 0) = - _tmp44 * (P(7, 0) * _tmp31 + P(7, 1) * _tmp33 + P(7, 2) * _tmp34 + P(7, 21) * _tmp42 + - P(7, 22) * _tmp43 + P(7, 3) * _tmp37 + P(7, 4) * _tmp40 + P(7, 5) * _tmp41); + _tmp42 * (P(7, 0) * _tmp30 + P(7, 1) * _tmp31 + P(7, 2) * _tmp32 + P(7, 21) * _tmp40 + + P(7, 22) * _tmp41 + P(7, 3) * _tmp35 + P(7, 4) * _tmp38 + P(7, 5) * _tmp39); _k(8, 0) = - _tmp44 * (P(8, 0) * _tmp31 + P(8, 1) * _tmp33 + P(8, 2) * _tmp34 + P(8, 21) * _tmp42 + - P(8, 22) * _tmp43 + P(8, 3) * _tmp37 + P(8, 4) * _tmp40 + P(8, 5) * _tmp41); + _tmp42 * (P(8, 0) * _tmp30 + P(8, 1) * _tmp31 + P(8, 2) * _tmp32 + P(8, 21) * _tmp40 + + P(8, 22) * _tmp41 + P(8, 3) * _tmp35 + P(8, 4) * _tmp38 + P(8, 5) * _tmp39); _k(9, 0) = - _tmp44 * (P(9, 0) * _tmp31 + P(9, 1) * _tmp33 + P(9, 2) * _tmp34 + P(9, 21) * _tmp42 + - P(9, 22) * _tmp43 + P(9, 3) * _tmp37 + P(9, 4) * _tmp40 + P(9, 5) * _tmp41); + _tmp42 * (P(9, 0) * _tmp30 + P(9, 1) * _tmp31 + P(9, 2) * _tmp32 + P(9, 21) * _tmp40 + + P(9, 22) * _tmp41 + P(9, 3) * _tmp35 + P(9, 4) * _tmp38 + P(9, 5) * _tmp39); _k(10, 0) = - _tmp44 * (P(10, 0) * _tmp31 + P(10, 1) * _tmp33 + P(10, 2) * _tmp34 + P(10, 21) * _tmp42 + - P(10, 22) * _tmp43 + P(10, 3) * _tmp37 + P(10, 4) * _tmp40 + P(10, 5) * _tmp41); + _tmp42 * (P(10, 0) * _tmp30 + P(10, 1) * _tmp31 + P(10, 2) * _tmp32 + P(10, 21) * _tmp40 + + P(10, 22) * _tmp41 + P(10, 3) * _tmp35 + P(10, 4) * _tmp38 + P(10, 5) * _tmp39); _k(11, 0) = - _tmp44 * (P(11, 0) * _tmp31 + P(11, 1) * _tmp33 + P(11, 2) * _tmp34 + P(11, 21) * _tmp42 + - P(11, 22) * _tmp43 + P(11, 3) * _tmp37 + P(11, 4) * _tmp40 + P(11, 5) * _tmp41); + _tmp42 * (P(11, 0) * _tmp30 + P(11, 1) * _tmp31 + P(11, 2) * _tmp32 + P(11, 21) * _tmp40 + + P(11, 22) * _tmp41 + P(11, 3) * _tmp35 + P(11, 4) * _tmp38 + P(11, 5) * _tmp39); _k(12, 0) = - _tmp44 * (P(12, 0) * _tmp31 + P(12, 1) * _tmp33 + P(12, 2) * _tmp34 + P(12, 21) * _tmp42 + - P(12, 22) * _tmp43 + P(12, 3) * _tmp37 + P(12, 4) * _tmp40 + P(12, 5) * _tmp41); + _tmp42 * (P(12, 0) * _tmp30 + P(12, 1) * _tmp31 + P(12, 2) * _tmp32 + P(12, 21) * _tmp40 + + P(12, 22) * _tmp41 + P(12, 3) * _tmp35 + P(12, 4) * _tmp38 + P(12, 5) * _tmp39); _k(13, 0) = - _tmp44 * (P(13, 0) * _tmp31 + P(13, 1) * _tmp33 + P(13, 2) * _tmp34 + P(13, 21) * _tmp42 + - P(13, 22) * _tmp43 + P(13, 3) * _tmp37 + P(13, 4) * _tmp40 + P(13, 5) * _tmp41); + _tmp42 * (P(13, 0) * _tmp30 + P(13, 1) * _tmp31 + P(13, 2) * _tmp32 + P(13, 21) * _tmp40 + + P(13, 22) * _tmp41 + P(13, 3) * _tmp35 + P(13, 4) * _tmp38 + P(13, 5) * _tmp39); _k(14, 0) = - _tmp44 * (P(14, 0) * _tmp31 + P(14, 1) * _tmp33 + P(14, 2) * _tmp34 + P(14, 21) * _tmp42 + - P(14, 22) * _tmp43 + P(14, 3) * _tmp37 + P(14, 4) * _tmp40 + P(14, 5) * _tmp41); + _tmp42 * (P(14, 0) * _tmp30 + P(14, 1) * _tmp31 + P(14, 2) * _tmp32 + P(14, 21) * _tmp40 + + P(14, 22) * _tmp41 + P(14, 3) * _tmp35 + P(14, 4) * _tmp38 + P(14, 5) * _tmp39); _k(15, 0) = - _tmp44 * (P(15, 0) * _tmp31 + P(15, 1) * _tmp33 + P(15, 2) * _tmp34 + P(15, 21) * _tmp42 + - P(15, 22) * _tmp43 + P(15, 3) * _tmp37 + P(15, 4) * _tmp40 + P(15, 5) * _tmp41); + _tmp42 * (P(15, 0) * _tmp30 + P(15, 1) * _tmp31 + P(15, 2) * _tmp32 + P(15, 21) * _tmp40 + + P(15, 22) * _tmp41 + P(15, 3) * _tmp35 + P(15, 4) * _tmp38 + P(15, 5) * _tmp39); _k(16, 0) = - _tmp44 * (P(16, 0) * _tmp31 + P(16, 1) * _tmp33 + P(16, 2) * _tmp34 + P(16, 21) * _tmp42 + - P(16, 22) * _tmp43 + P(16, 3) * _tmp37 + P(16, 4) * _tmp40 + P(16, 5) * _tmp41); + _tmp42 * (P(16, 0) * _tmp30 + P(16, 1) * _tmp31 + P(16, 2) * _tmp32 + P(16, 21) * _tmp40 + + P(16, 22) * _tmp41 + P(16, 3) * _tmp35 + P(16, 4) * _tmp38 + P(16, 5) * _tmp39); _k(17, 0) = - _tmp44 * (P(17, 0) * _tmp31 + P(17, 1) * _tmp33 + P(17, 2) * _tmp34 + P(17, 21) * _tmp42 + - P(17, 22) * _tmp43 + P(17, 3) * _tmp37 + P(17, 4) * _tmp40 + P(17, 5) * _tmp41); + _tmp42 * (P(17, 0) * _tmp30 + P(17, 1) * _tmp31 + P(17, 2) * _tmp32 + P(17, 21) * _tmp40 + + P(17, 22) * _tmp41 + P(17, 3) * _tmp35 + P(17, 4) * _tmp38 + P(17, 5) * _tmp39); _k(18, 0) = - _tmp44 * (P(18, 0) * _tmp31 + P(18, 1) * _tmp33 + P(18, 2) * _tmp34 + P(18, 21) * _tmp42 + - P(18, 22) * _tmp43 + P(18, 3) * _tmp37 + P(18, 4) * _tmp40 + P(18, 5) * _tmp41); + _tmp42 * (P(18, 0) * _tmp30 + P(18, 1) * _tmp31 + P(18, 2) * _tmp32 + P(18, 21) * _tmp40 + + P(18, 22) * _tmp41 + P(18, 3) * _tmp35 + P(18, 4) * _tmp38 + P(18, 5) * _tmp39); _k(19, 0) = - _tmp44 * (P(19, 0) * _tmp31 + P(19, 1) * _tmp33 + P(19, 2) * _tmp34 + P(19, 21) * _tmp42 + - P(19, 22) * _tmp43 + P(19, 3) * _tmp37 + P(19, 4) * _tmp40 + P(19, 5) * _tmp41); + _tmp42 * (P(19, 0) * _tmp30 + P(19, 1) * _tmp31 + P(19, 2) * _tmp32 + P(19, 21) * _tmp40 + + P(19, 22) * _tmp41 + P(19, 3) * _tmp35 + P(19, 4) * _tmp38 + P(19, 5) * _tmp39); _k(20, 0) = - _tmp44 * (P(20, 0) * _tmp31 + P(20, 1) * _tmp33 + P(20, 2) * _tmp34 + P(20, 21) * _tmp42 + - P(20, 22) * _tmp43 + P(20, 3) * _tmp37 + P(20, 4) * _tmp40 + P(20, 5) * _tmp41); + _tmp42 * (P(20, 0) * _tmp30 + P(20, 1) * _tmp31 + P(20, 2) * _tmp32 + P(20, 21) * _tmp40 + + P(20, 22) * _tmp41 + P(20, 3) * _tmp35 + P(20, 4) * _tmp38 + P(20, 5) * _tmp39); _k(21, 0) = - _tmp44 * (P(21, 0) * _tmp31 + P(21, 1) * _tmp33 + P(21, 2) * _tmp34 + P(21, 21) * _tmp42 + - P(21, 22) * _tmp43 + P(21, 3) * _tmp37 + P(21, 4) * _tmp40 + P(21, 5) * _tmp41); + _tmp42 * (P(21, 0) * _tmp30 + P(21, 1) * _tmp31 + P(21, 2) * _tmp32 + P(21, 21) * _tmp40 + + P(21, 22) * _tmp41 + P(21, 3) * _tmp35 + P(21, 4) * _tmp38 + P(21, 5) * _tmp39); _k(22, 0) = - _tmp44 * (P(22, 0) * _tmp31 + P(22, 1) * _tmp33 + P(22, 2) * _tmp34 + P(22, 21) * _tmp42 + - P(22, 22) * _tmp43 + P(22, 3) * _tmp37 + P(22, 4) * _tmp40 + P(22, 5) * _tmp41); + _tmp42 * (P(22, 0) * _tmp30 + P(22, 1) * _tmp31 + P(22, 2) * _tmp32 + P(22, 21) * _tmp40 + + P(22, 22) * _tmp41 + P(22, 3) * _tmp35 + P(22, 4) * _tmp38 + P(22, 5) * _tmp39); + _k(23, 0) = + _tmp42 * (P(23, 0) * _tmp30 + P(23, 1) * _tmp31 + P(23, 2) * _tmp32 + P(23, 21) * _tmp40 + + P(23, 22) * _tmp41 + P(23, 3) * _tmp35 + P(23, 4) * _tmp38 + P(23, 5) * _tmp39); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h index b93febcede7f..6918bddfc366 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h @@ -16,8 +16,8 @@ namespace sym { * Symbolic function: compute_sideslip_innov_and_innov_var * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * epsilon: Scalar * @@ -26,8 +26,8 @@ namespace sym { * innov_var: Scalar */ template -void ComputeSideslipInnovAndInnovVar(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeSideslipInnovAndInnovVar(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov = nullptr, Scalar* const innov_var = nullptr) { // Total ops: 265 diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h index e082438f09c1..41f21774336d 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h @@ -16,19 +16,19 @@ namespace sym { * Symbolic function: compute_yaw_innov_var_and_h * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * R: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix23_1 + * H: Matrix24_1 */ template -void ComputeYawInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, +void ComputeYawInnovVarAndH(const matrix::Matrix& state, + const matrix::Matrix& P, const Scalar R, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { + matrix::Matrix* const H = nullptr) { // Total ops: 1 // Unused inputs @@ -46,7 +46,7 @@ void ComputeYawInnovVarAndH(const matrix::Matrix& state, } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h index 1ff79d8c7e61..edf246a6bf60 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h @@ -16,8 +16,8 @@ namespace sym { * Symbolic function: predict_covariance * * Args: - * state: Matrix24_1 - * P: Matrix23_23 + * state: Matrix25_1 + * P: Matrix24_24 * accel: Matrix31 * accel_var: Matrix31 * gyro: Matrix31 @@ -25,23 +25,23 @@ namespace sym { * dt: Scalar * * Outputs: - * res: Matrix23_23 + * res: Matrix24_24 */ template -matrix::Matrix PredictCovariance(const matrix::Matrix& state, - const matrix::Matrix& P, +matrix::Matrix PredictCovariance(const matrix::Matrix& state, + const matrix::Matrix& P, const matrix::Matrix& accel, const matrix::Matrix& accel_var, const matrix::Matrix& gyro, const Scalar gyro_var, const Scalar dt) { - // Total ops: 1754 + // Total ops: 1810 // Unused inputs (void)gyro; // Input arrays - // Intermediate terms (147) + // Intermediate terms (144) const Scalar _tmp0 = 2 * state(1, 0); const Scalar _tmp1 = _tmp0 * state(3, 0); const Scalar _tmp2 = -_tmp1 * dt; @@ -177,64 +177,62 @@ matrix::Matrix PredictCovariance(const matrix::Matrix _res; + matrix::Matrix _res; _res.setZero(); @@ -264,40 +262,40 @@ matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix mag_I{}; matrix::Vector3 mag_B{}; matrix::Vector2 wind_vel{}; + float terrain{}; - matrix::Vector Data() const { - matrix::Vector state; + matrix::Vector Data() const { + matrix::Vector state; state.slice<4, 1>(0, 0) = quat_nominal; state.slice<3, 1>(4, 0) = vel; state.slice<3, 1>(7, 0) = pos; @@ -29,15 +30,16 @@ struct StateSample { state.slice<3, 1>(16, 0) = mag_I; state.slice<3, 1>(19, 0) = mag_B; state.slice<2, 1>(22, 0) = wind_vel; + state.slice<1, 1>(24, 0) = terrain; return state; }; - const matrix::Vector& vector() const { - return *reinterpret_cast*>(const_cast(reinterpret_cast(&quat_nominal))); + const matrix::Vector& vector() const { + return *reinterpret_cast*>(const_cast(reinterpret_cast(&quat_nominal))); }; }; -static_assert(sizeof(matrix::Vector) == sizeof(StateSample), "state vector doesn't match StateSample size"); +static_assert(sizeof(matrix::Vector) == sizeof(StateSample), "state vector doesn't match StateSample size"); struct IdxDof { unsigned idx; unsigned dof; }; namespace State { @@ -49,7 +51,8 @@ namespace State { static constexpr IdxDof mag_I{15, 3}; static constexpr IdxDof mag_B{18, 3}; static constexpr IdxDof wind_vel{21, 2}; - static constexpr uint8_t size{23}; + static constexpr IdxDof terrain{23, 1}; + static constexpr uint8_t size{24}; }; } #endif // !EKF_STATE_H diff --git a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp index dad3c322f105..ea6a4259d106 100644 --- a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp +++ b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp @@ -38,26 +38,17 @@ */ #include "ekf.h" -#include "terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h" -#include "terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h" +#include "ekf_derivation/generated/state.h" #include void Ekf::initHagl() { // assume a ground clearance - _terrain_vpos = _state.pos(2) + _params.rng_gnd_clearance; + _state.terrain = _state.pos(2) + _params.rng_gnd_clearance; // use the ground clearance value as our uncertainty - _terrain_var = sq(_params.rng_gnd_clearance); - -#if defined(CONFIG_EKF2_RANGE_FINDER) - _aid_src_terrain_range_finder.time_last_fuse = _time_delayed_us; -#endif // CONFIG_EKF2_RANGE_FINDER - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - _aid_src_terrain_optical_flow.time_last_fuse = _time_delayed_us; -#endif // CONFIG_EKF2_OPTICAL_FLOW + P.uncorrelateCovarianceSetVariance(State::terrain.idx, sq(_params.rng_gnd_clearance)); } void Ekf::runTerrainEstimator(const imuSample &imu_delayed) @@ -74,333 +65,9 @@ void Ekf::runTerrainEstimator(const imuSample &imu_delayed) initHagl(); } - predictHagl(imu_delayed); - -#if defined(CONFIG_EKF2_RANGE_FINDER) - controlHaglRngFusion(); -#endif // CONFIG_EKF2_RANGE_FINDER - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - controlHaglFlowFusion(); -#endif // CONFIG_EKF2_OPTICAL_FLOW - controlHaglFakeFusion(); - - // constrain _terrain_vpos to be a minimum of _params.rng_gnd_clearance larger than _state.pos(2) - if (_terrain_vpos - _state.pos(2) < _params.rng_gnd_clearance) { - _terrain_vpos = _params.rng_gnd_clearance + _state.pos(2); - } -} - -void Ekf::predictHagl(const imuSample &imu_delayed) -{ - // predict the state variance growth where the state is the vertical position of the terrain underneath the vehicle - - // process noise due to errors in vehicle height estimate - _terrain_var += sq(imu_delayed.delta_vel_dt * _params.terrain_p_noise); - - // process noise due to terrain gradient - _terrain_var += sq(imu_delayed.delta_vel_dt * _params.terrain_gradient) - * (sq(_state.vel(0)) + sq(_state.vel(1))); - - // limit the variance to prevent it becoming badly conditioned - _terrain_var = math::constrain(_terrain_var, 0.0f, 1e4f); -} - -#if defined(CONFIG_EKF2_RANGE_FINDER) -void Ekf::controlHaglRngFusion() -{ - if (!(_params.terrain_fusion_mode & TerrainFusionMask::TerrainFuseRangeFinder) - || _control_status.flags.rng_fault) { - - stopHaglRngFusion(); - return; - } - - if (_range_sensor.isDataReady()) { - updateHaglRng(_aid_src_terrain_range_finder); - } - - if (_range_sensor.isDataHealthy()) { - - const bool continuing_conditions_passing = _rng_consistency_check.isKinematicallyConsistent(); - //&& !_control_status.flags.rng_hgt // TODO: should not be fused when using range height - - const bool starting_conditions_passing = continuing_conditions_passing - && _range_sensor.isRegularlySendingData() - && (_rng_consistency_check.getTestRatio() < 1.f); - - _time_last_healthy_rng_data = _time_delayed_us; - - if (_hagl_sensor_status.flags.range_finder) { - if (continuing_conditions_passing) { - fuseHaglRng(_aid_src_terrain_range_finder); - - // We have been rejecting range data for too long - const uint64_t timeout = static_cast(_params.terrain_timeout * 1e6f); - const bool is_fusion_failing = isTimedOut(_aid_src_terrain_range_finder.time_last_fuse, timeout); - - if (is_fusion_failing) { - if (_range_sensor.getDistBottom() > 2.f * _params.rng_gnd_clearance) { - // Data seems good, attempt a reset - resetHaglRng(); - - } else if (starting_conditions_passing) { - // The sensor can probably not detect the ground properly - // declare the sensor faulty and stop the fusion - _control_status.flags.rng_fault = true; - _range_sensor.setFaulty(true); - stopHaglRngFusion(); - - } else { - // This could be a temporary issue, stop the fusion without declaring the sensor faulty - stopHaglRngFusion(); - } - } - - } else { - stopHaglRngFusion(); - } - - } else { - if (starting_conditions_passing) { - _hagl_sensor_status.flags.range_finder = true; - - // Reset the state to the measurement only if the test ratio is large, - // otherwise let it converge through the fusion - if (_hagl_sensor_status.flags.flow && (_aid_src_terrain_range_finder.test_ratio < 0.2f)) { - fuseHaglRng(_aid_src_terrain_range_finder); - - } else { - resetHaglRng(); - } - } - } - - } else if (_hagl_sensor_status.flags.range_finder && isTimedOut(_time_last_healthy_rng_data, _params.reset_timeout_max)) { - // No data anymore. Stop until it comes back. - stopHaglRngFusion(); - } -} - -float Ekf::getRngVar() const -{ - return fmaxf(P(State::pos.idx + 2, State::pos.idx + 2) * _params.vehicle_variance_scaler, 0.0f) - + sq(_params.range_noise) - + sq(_params.range_noise_scaler * _range_sensor.getRange()); -} - -void Ekf::resetHaglRng() -{ - _terrain_vpos = _state.pos(2) + _range_sensor.getDistBottom(); - _terrain_var = getRngVar(); - _terrain_vpos_reset_counter++; - - _aid_src_terrain_range_finder.time_last_fuse = _time_delayed_us; -} - -void Ekf::stopHaglRngFusion() -{ - if (_hagl_sensor_status.flags.range_finder) { - ECL_INFO("stopping HAGL range fusion"); - - // reset flags - _innov_check_fail_status.flags.reject_hagl = false; - - _hagl_sensor_status.flags.range_finder = false; - } -} - -void Ekf::updateHaglRng(estimator_aid_source1d_s &aid_src) const -{ - // get a height above ground measurement from the range finder assuming a flat earth - const float meas_hagl = _range_sensor.getDistBottom(); - - // predict the hagl from the vehicle position and terrain height - const float pred_hagl = _terrain_vpos - _state.pos(2); - - // calculate the observation variance adding the variance of the vehicles own height uncertainty - const float obs_variance = getRngVar(); - - // calculate the innovation variance - limiting it to prevent a badly conditioned fusion - const float hagl_innov_var = fmaxf(_terrain_var + obs_variance, obs_variance); - - updateAidSourceStatus(aid_src, - _time_delayed_us, // sample timestamp - meas_hagl, // observation - obs_variance, // observation variance - pred_hagl - meas_hagl, // innovation - hagl_innov_var, // innovation variance - math::max(_params.range_innov_gate, 1.f)); // innovation gate } -void Ekf::fuseHaglRng(estimator_aid_source1d_s &aid_src) -{ - if (!aid_src.innovation_rejected) { - // calculate the Kalman gain - const float gain = _terrain_var / aid_src.innovation_variance; - - // correct the state - _terrain_vpos -= gain * aid_src.innovation; - - // correct the variance - _terrain_var = fmaxf(_terrain_var * (1.0f - gain), 0.0f); - - // record last successful fusion event - _innov_check_fail_status.flags.reject_hagl = false; - - aid_src.time_last_fuse = _time_delayed_us; - aid_src.fused = true; - - } else { - _innov_check_fail_status.flags.reject_hagl = true; - aid_src.fused = false; - } -} -#endif // CONFIG_EKF2_RANGE_FINDER - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) -void Ekf::controlHaglFlowFusion() -{ - if (!(_params.terrain_fusion_mode & TerrainFusionMask::TerrainFuseOpticalFlow)) { - stopHaglFlowFusion(); - return; - } - - if (_flow_data_ready) { - updateOptFlow(_aid_src_terrain_optical_flow); - - const bool continuing_conditions_passing = _control_status.flags.in_air - && !_control_status.flags.opt_flow - && _control_status.flags.gps - && !_hagl_sensor_status.flags.range_finder; - - const bool starting_conditions_passing = continuing_conditions_passing; - - if (_hagl_sensor_status.flags.flow) { - if (continuing_conditions_passing) { - - // TODO: wait until the midpoint of the flow sample has fallen behind the fusion time horizon - fuseFlowForTerrain(_aid_src_terrain_optical_flow); - - // TODO: do something when failing continuously the innovation check - /* const bool is_fusion_failing = isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.reset_timeout_max); */ - - /* if (is_fusion_failing) { */ - /* resetHaglFlow(); */ - /* } */ - - } else { - stopHaglFlowFusion(); - } - - } else { - if (starting_conditions_passing) { - _hagl_sensor_status.flags.flow = true; - // TODO: do a reset instead of trying to fuse the data? - fuseFlowForTerrain(_aid_src_terrain_optical_flow); - } - } - - _flow_data_ready = false; - - } else if (_hagl_sensor_status.flags.flow && (_time_delayed_us > _flow_sample_delayed.time_us + (uint64_t)5e6)) { - // No data anymore. Stop until it comes back. - stopHaglFlowFusion(); - } -} - -void Ekf::stopHaglFlowFusion() -{ - if (_hagl_sensor_status.flags.flow) { - ECL_INFO("stopping HAGL flow fusion"); - - _hagl_sensor_status.flags.flow = false; - } -} - -void Ekf::resetHaglFlow() -{ - // TODO: use the flow data - _terrain_vpos = fmaxf(0.0f, _state.pos(2)); - _terrain_var = 100.0f; - _terrain_vpos_reset_counter++; - - _aid_src_terrain_optical_flow.time_last_fuse = _time_delayed_us; -} - -void Ekf::fuseFlowForTerrain(estimator_aid_source2d_s &flow) -{ - flow.fused = true; - - const float R_LOS = flow.observation_variance[0]; - - // calculate the height above the ground of the optical flow camera. Since earth frame is NED - // a positive offset in earth frame leads to a smaller height above the ground. - float range = predictFlowRange(); - - const float state = _terrain_vpos; // linearize both axes using the same state value - Vector2f innov_var; - float H; - sym::TerrEstComputeFlowXyInnovVarAndHx(state, _terrain_var, _state.quat_nominal, _state.vel, _state.pos(2), R_LOS, FLT_EPSILON, &innov_var, &H); - innov_var.copyTo(flow.innovation_variance); - - if ((flow.innovation_variance[0] < R_LOS) - || (flow.innovation_variance[1] < R_LOS)) { - // we need to reinitialise the covariance matrix and abort this fusion step - ECL_ERR("Opt flow error - covariance reset"); - _terrain_var = 100.0f; - return; - } - - _innov_check_fail_status.flags.reject_optflow_X = (flow.test_ratio[0] > 1.f); - _innov_check_fail_status.flags.reject_optflow_Y = (flow.test_ratio[1] > 1.f); - - // if either axis fails we abort the fusion - if (flow.innovation_rejected) { - return; - } - - // fuse observation axes sequentially - for (uint8_t index = 0; index <= 1; index++) { - if (index == 0) { - // everything was already computed above - - } else if (index == 1) { - // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::TerrEstComputeFlowYInnovVarAndH(state, _terrain_var, _state.quat_nominal, _state.vel, _state.pos(2), R_LOS, FLT_EPSILON, &flow.innovation_variance[1], &H); - - // recalculate the innovation using the updated state - const Vector2f vel_body = predictFlowVelBody(); - range = predictFlowRange(); - flow.innovation[1] = (-vel_body(0) / range) - flow.observation[1]; - - if (flow.innovation_variance[1] < R_LOS) { - // we need to reinitialise the covariance matrix and abort this fusion step - ECL_ERR("Opt flow error - covariance reset"); - _terrain_var = 100.0f; - return; - } - } - - float Kfusion = _terrain_var * H / flow.innovation_variance[index]; - - _terrain_vpos += Kfusion * flow.innovation[0]; - // constrain terrain to minimum allowed value and predict height above ground - _terrain_vpos = fmaxf(_terrain_vpos, _params.rng_gnd_clearance + _state.pos(2)); - - // guard against negative variance - _terrain_var = fmaxf(_terrain_var - Kfusion * H * _terrain_var, sq(0.01f)); - } - - _fault_status.flags.bad_optflow_X = false; - _fault_status.flags.bad_optflow_Y = false; - - flow.time_last_fuse = _time_delayed_us; - flow.fused = true; -} -#endif // CONFIG_EKF2_OPTICAL_FLOW - void Ekf::controlHaglFakeFusion() { if (!_control_status.flags.in_air @@ -410,11 +77,11 @@ void Ekf::controlHaglFakeFusion() bool recent_terrain_aiding = false; #if defined(CONFIG_EKF2_RANGE_FINDER) - recent_terrain_aiding |= isRecent(_aid_src_terrain_range_finder.time_last_fuse, (uint64_t)1e6); + recent_terrain_aiding |= isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)1e6); #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_OPTICAL_FLOW) - recent_terrain_aiding |= isRecent(_aid_src_terrain_optical_flow.time_last_fuse, (uint64_t)1e6); + recent_terrain_aiding |= isRecent(_aid_src_optical_flow.time_last_fuse, (uint64_t)1e6); #endif // CONFIG_EKF2_OPTICAL_FLOW if (_control_status.flags.vehicle_at_rest || !recent_terrain_aiding) { @@ -425,24 +92,20 @@ void Ekf::controlHaglFakeFusion() bool Ekf::isTerrainEstimateValid() const { - bool valid = false; + // Assume being valid when the uncertainty is small compared to the height above ground + bool valid = getTerrainVariance() < sq(0.1f * getHagl()); #if defined(CONFIG_EKF2_RANGE_FINDER) - // we have been fusing range finder measurements in the last 5 seconds - if (isRecent(_aid_src_terrain_range_finder.time_last_fuse, (uint64_t)5e6)) { - if (_hagl_sensor_status.flags.range_finder || !_control_status.flags.in_air) { - valid = true; - } + if (_hagl_sensor_status.flags.range_finder && isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)5e6)) { + valid = true; } #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_OPTICAL_FLOW) - // we have been fusing optical flow measurements for terrain estimation within the last 5 seconds - // this can only be the case if the main filter does not fuse optical flow - if (_hagl_sensor_status.flags.flow && isRecent(_aid_src_terrain_optical_flow.time_last_fuse, (uint64_t)5e6)) { + if (_hagl_sensor_status.flags.flow && isRecent(_aid_src_optical_flow.time_last_fuse, (uint64_t)5e6)) { valid = true; } @@ -450,7 +113,3 @@ bool Ekf::isTerrainEstimateValid() const return valid; } - -void Ekf::terrainHandleVerticalPositionReset(const float delta_z) { - _terrain_vpos += delta_z; -} diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 166293453a1d..430ed52db5b0 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -326,7 +326,6 @@ bool EKF2::multi_init(int imu, int mag) // RNG advertise if (_param_ekf2_rng_ctrl.get()) { _estimator_aid_src_rng_hgt_pub.advertise(); - _estimator_rng_hgt_bias_pub.advertise(); } #endif // CONFIG_EKF2_RANGE_FINDER @@ -728,10 +727,6 @@ void EKF2::Run() PublishBaroBias(now); #endif // CONFIG_EKF2_BAROMETER -#if defined(CONFIG_EKF2_RANGE_FINDER) - PublishRngHgtBias(now); -#endif // CONFIG_EKF2_RANGE_FINDER - #if defined(CONFIG_EKF2_EXTERNAL_VISION) PublishEvPosBias(now); #endif // CONFIG_EKF2_EXTERNAL_VISION @@ -928,21 +923,6 @@ void EKF2::PublishAidSourceStatus(const hrt_abstime ×tamp) // optical flow PublishAidSourceStatus(_ekf.aid_src_optical_flow(), _status_optical_flow_pub_last, _estimator_aid_src_optical_flow_pub); #endif // CONFIG_EKF2_OPTICAL_FLOW - -#if defined(CONFIG_EKF2_TERRAIN) -# if defined(CONFIG_EKF2_RANGE_FINDER) - // range finder - PublishAidSourceStatus(_ekf.aid_src_terrain_range_finder(), _status_terrain_range_finder_pub_last, - _estimator_aid_src_terrain_range_finder_pub); -#endif // CONFIG_EKF2_RANGE_FINDER - -# if defined(CONFIG_EKF2_OPTICAL_FLOW) - // optical flow - PublishAidSourceStatus(_ekf.aid_src_terrain_optical_flow(), _status_terrain_optical_flow_pub_last, - _estimator_aid_src_terrain_optical_flow_pub); -# endif // CONFIG_EKF2_OPTICAL_FLOW - -#endif // CONFIG_EKF2_TERRAIN } void EKF2::PublishAttitude(const hrt_abstime ×tamp) @@ -996,21 +976,6 @@ void EKF2::PublishGnssHgtBias(const hrt_abstime ×tamp) } #endif // CONFIG_EKF2_GNSS -#if defined(CONFIG_EKF2_RANGE_FINDER) -void EKF2::PublishRngHgtBias(const hrt_abstime ×tamp) -{ - if (_ekf.get_rng_sample_delayed().time_us != 0) { - const BiasEstimator::status &status = _ekf.getRngHgtBiasEstimatorStatus(); - - if (fabsf(status.bias - _last_rng_hgt_bias_published) > 0.001f) { - _estimator_rng_hgt_bias_pub.publish(fillEstimatorBiasMsg(status, _ekf.get_rng_sample_delayed().time_us, timestamp)); - - _last_rng_hgt_bias_published = status.bias; - } - } -} -#endif // CONFIG_EKF2_RANGE_FINDER - #if defined(CONFIG_EKF2_EXTERNAL_VISION) void EKF2::PublishEvPosBias(const hrt_abstime ×tamp) { @@ -1272,10 +1237,6 @@ void EKF2::PublishInnovations(const hrt_abstime ×tamp) // Optical flow innovations.flow[0] = _ekf.aid_src_optical_flow().innovation[0]; innovations.flow[1] = _ekf.aid_src_optical_flow().innovation[1]; -# if defined(CONFIG_EKF2_TERRAIN) - innovations.terr_flow[0] = _ekf.aid_src_terrain_optical_flow().innovation[0]; - innovations.terr_flow[1] = _ekf.aid_src_terrain_optical_flow().innovation[1]; -# endif // CONFIG_EKF2_TERRAIN #endif // CONFIG_EKF2_OPTICAL_FLOW // heading @@ -1313,7 +1274,7 @@ void EKF2::PublishInnovations(const hrt_abstime ×tamp) #if defined(CONFIG_EKF2_TERRAIN) && defined(CONFIG_EKF2_RANGE_FINDER) // hagl - innovations.hagl = _ekf.aid_src_terrain_range_finder().innovation; + innovations.hagl = _ekf.aid_src_rng_hgt().innovation; #endif // CONFIG_EKF2_TERRAIN && CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_RANGE_FINDER) @@ -1339,7 +1300,7 @@ void EKF2::PublishInnovations(const hrt_abstime ×tamp) #if defined(CONFIG_EKF2_TERRAIN) && defined(CONFIG_EKF2_OPTICAL_FLOW) // set dist bottom to scale flow innovation - const float dist_bottom = _ekf.getTerrainVertPos() - _ekf.getPosition()(2); + const float dist_bottom = _ekf.getHagl(); _preflt_checker.setDistBottom(dist_bottom); #endif // CONFIG_EKF2_TERRAIN && CONFIG_EKF2_OPTICAL_FLOW @@ -1406,10 +1367,6 @@ void EKF2::PublishInnovationTestRatios(const hrt_abstime ×tamp) // Optical flow test_ratios.flow[0] = _ekf.aid_src_optical_flow().test_ratio[0]; test_ratios.flow[1] = _ekf.aid_src_optical_flow().test_ratio[1]; -# if defined(CONFIG_EKF2_TERRAIN) - test_ratios.terr_flow[0] = _ekf.aid_src_terrain_optical_flow().test_ratio[0]; - test_ratios.terr_flow[1] = _ekf.aid_src_terrain_optical_flow().test_ratio[1]; -# endif // CONFIG_EKF2_TERRAIN #endif // CONFIG_EKF2_OPTICAL_FLOW // heading @@ -1447,7 +1404,7 @@ void EKF2::PublishInnovationTestRatios(const hrt_abstime ×tamp) #if defined(CONFIG_EKF2_TERRAIN) && defined(CONFIG_EKF2_RANGE_FINDER) // hagl - test_ratios.hagl = _ekf.aid_src_terrain_range_finder().test_ratio; + test_ratios.hagl = _ekf.aid_src_rng_hgt().test_ratio; #endif // CONFIG_EKF2_TERRAIN && CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_RANGE_FINDER) @@ -1503,10 +1460,6 @@ void EKF2::PublishInnovationVariances(const hrt_abstime ×tamp) // Optical flow variances.flow[0] = _ekf.aid_src_optical_flow().innovation_variance[0]; variances.flow[1] = _ekf.aid_src_optical_flow().innovation_variance[1]; -# if defined(CONFIG_EKF2_TERRAIN) - variances.terr_flow[0] = _ekf.aid_src_terrain_optical_flow().innovation_variance[0]; - variances.terr_flow[1] = _ekf.aid_src_terrain_optical_flow().innovation_variance[1]; -# endif // CONFIG_EKF2_TERRAIN #endif // CONFIG_EKF2_OPTICAL_FLOW // heading @@ -1544,7 +1497,7 @@ void EKF2::PublishInnovationVariances(const hrt_abstime ×tamp) #if defined(CONFIG_EKF2_TERRAIN) && defined(CONFIG_EKF2_RANGE_FINDER) // hagl - variances.hagl = _ekf.aid_src_terrain_range_finder().innovation_variance; + variances.hagl = _ekf.aid_src_rng_hgt().innovation_variance; #endif // CONFIG_EKF2_TERRAIN && CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_RANGE_FINDER) @@ -1620,7 +1573,7 @@ void EKF2::PublishLocalPosition(const hrt_abstime ×tamp) #if defined(CONFIG_EKF2_TERRAIN) // Distance to bottom surface (ground) in meters, must be positive - lpos.dist_bottom = math::max(_ekf.getTerrainVertPos() - lpos.z, 0.f); + lpos.dist_bottom = math::max(_ekf.getHagl(), 0.f); lpos.dist_bottom_valid = _ekf.isTerrainEstimateValid(); lpos.dist_bottom_sensor_bitfield = _ekf.getTerrainEstimateSensorBitfield(); #endif // CONFIG_EKF2_TERRAIN diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 28c76dd13046..10a51c9dcd79 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -337,19 +337,6 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem hrt_abstime _status_aux_vel_pub_last{0}; #endif // CONFIG_EKF2_AUXVEL -#if defined(CONFIG_EKF2_TERRAIN) - -# if defined(CONFIG_EKF2_RANGE_FINDER) - uORB::PublicationMulti _estimator_aid_src_terrain_range_finder_pub {ORB_ID(estimator_aid_src_terrain_range_finder)}; - hrt_abstime _status_terrain_range_finder_pub_last{0}; -# endif // CONFIG_EKF2_RANGE_FINDER - -# if defined(CONFIG_EKF2_OPTICAL_FLOW) - uORB::PublicationMulti _estimator_aid_src_terrain_optical_flow_pub {ORB_ID(estimator_aid_src_terrain_optical_flow)}; - hrt_abstime _status_terrain_optical_flow_pub_last{0}; -# endif // CONFIG_EKF2_OPTICAL_FLOW -#endif // CONFIG_EKF2_TERRAIN - #if defined(CONFIG_EKF2_OPTICAL_FLOW) uORB::Subscription _vehicle_optical_flow_sub {ORB_ID(vehicle_optical_flow)}; uORB::PublicationMulti _estimator_optical_flow_vel_pub{ORB_ID(estimator_optical_flow_vel)}; @@ -407,9 +394,7 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem #if defined(CONFIG_EKF2_RANGE_FINDER) hrt_abstime _status_rng_hgt_pub_last {0}; - float _last_rng_hgt_bias_published{}; - uORB::PublicationMulti _estimator_rng_hgt_bias_pub {ORB_ID(estimator_rng_hgt_bias)}; uORB::PublicationMulti _estimator_aid_src_rng_hgt_pub{ORB_ID(estimator_aid_src_rng_hgt)}; uORB::SubscriptionMultiArray _distance_sensor_subs{ORB_ID::distance_sensor}; diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index 84a665ab0e01..bb3627dedb33 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -41,6 +41,7 @@ px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_basics.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_externalVision.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_flow.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) +px4_add_unit_gtest(SRC test_EKF_flow_generated.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gyroscope.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_fusionLogic.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gps.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) 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 88fa6eb85faa..07045ce2c9da 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -1,391 +1,391 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2190000,1,-0.011,-0.014,5.9e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2590000,1,-0.011,-0.013,5.9e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2790000,1,-0.011,-0.013,4.9e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2890000,1,-0.011,-0.013,-1.1e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3090000,1,-0.011,-0.013,4.9e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3190000,1,-0.011,-0.013,-8e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3290000,1,-0.011,-0.013,3.2e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3390000,1,-0.011,-0.012,3.2e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3490000,1,-0.011,-0.013,-4.5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3590000,1,-0.011,-0.012,1.9e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4290000,1,-0.01,-0.012,8.1e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4690000,1,-0.01,-0.012,0.00019,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4790000,1,-0.01,-0.012,0.00018,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5690000,1,-0.0096,-0.011,0.00033,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6090000,1,-0.0094,-0.011,0.00031,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6290000,1,-0.0094,-0.011,0.00021,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6390000,1,-0.0093,-0.011,0.00023,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,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 -6590000,1,-0.0094,-0.011,0.00016,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,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 -6690000,1,-0.0093,-0.011,9e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,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 -6790000,0.78,-0.024,0.0048,-0.62,-0.22,-0.051,-0.11,-0.13,-0.03,-3.7e+02,-0.00029,-0.01,-0.0002,0,0,0.0012,-0.092,-0.021,0.51,-0.00079,-0.075,-0.061,0,0,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 -6890000,0.78,-0.025,0.0057,-0.62,-0.27,-0.065,-0.12,-0.16,-0.04,-3.7e+02,-0.0001,-0.011,-0.00022,0,0,0.0012,-0.1,-0.023,0.51,-0.0012,-0.083,-0.067,0,0,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00025,0.0013,0.00089,0.0014,0.0013,1,1 -6990000,0.78,-0.025,0.006,-0.62,-0.3,-0.077,-0.12,-0.2,-0.05,-3.7e+02,-6.9e-06,-0.011,-0.00022,-0.00057,-7.3e-05,0.00095,-0.1,-0.024,0.5,-0.0016,-0.084,-0.067,0,0,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1 -7090000,0.78,-0.025,0.0062,-0.62,-0.33,-0.088,-0.12,-0.23,-0.063,-3.7e+02,0.00011,-0.011,-0.00023,-0.0013,-0.0003,0.00061,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00016,0.0013,0.00083,0.0014,0.0013,1,1 -7190000,0.78,-0.025,0.0064,-0.62,-0.36,-0.097,-0.15,-0.26,-0.075,-3.7e+02,0.00017,-0.011,-0.00023,-0.0017,-0.00046,0.00083,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00082,0.0013,0.0013,1,1 -7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.099,-0.14,-0.3,-0.082,-3.7e+02,0.00012,-0.011,-0.00023,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1 -7390000,0.78,-0.025,0.0069,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,0.00014,-0.011,-0.00022,-0.0016,-0.00046,9.1e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1 -7490000,0.78,-0.025,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00027,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.0019,-0.085,-0.069,0,0,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1 -7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00026,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1 -7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1 -7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0062,-0.16,-0.44,-0.14,-3.7e+02,0.00041,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1 -7890000,0.78,-0.024,0.0073,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00045,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1 -7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.00046,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1 -8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.0005,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1 -8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00049,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1 -8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00059,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1 -8390000,0.78,-0.024,0.0071,-0.63,-0.18,-0.036,-0.17,-0.49,-0.15,-3.7e+02,0.0006,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1 -8490000,0.78,-0.024,0.0071,-0.63,-0.2,-0.039,-0.17,-0.49,-0.15,-3.7e+02,0.00061,-0.0099,-0.00021,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1 -8590000,0.78,-0.023,0.0073,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00041,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1 -8690000,0.78,-0.023,0.0069,-0.63,-0.24,-0.044,-0.16,-0.53,-0.15,-3.7e+02,0.00042,-0.0096,-0.00019,-0.0019,-0.00051,-0.033,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,29,29,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,8.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 -8790000,0.78,-0.023,0.007,-0.63,-0.25,-0.047,-0.15,-0.53,-0.15,-3.7e+02,0.00045,-0.0095,-0.00019,-0.0019,-0.00051,-0.039,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.096,25,25,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,8.5e-05,0.0013,0.00076,0.0013,0.0013,1,1 -8890000,0.78,-0.023,0.0069,-0.63,-0.27,-0.051,-0.15,-0.55,-0.16,-3.7e+02,0.00044,-0.0094,-0.00018,-0.0019,-0.00051,-0.043,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.095,27,27,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0012,8.4e-05,0.0013,0.00076,0.0013,0.0013,1,1 -8990000,0.78,-0.023,0.0069,-0.63,-0.28,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00049,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1 -9090000,0.78,-0.022,0.0069,-0.63,-0.29,-0.053,-0.14,-0.58,-0.17,-3.7e+02,0.00041,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1 -9190000,0.78,-0.022,0.0062,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00042,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1 -9290000,0.78,-0.022,0.0059,-0.63,-0.31,-0.072,-0.14,-0.62,-0.18,-3.7e+02,0.00044,-0.0086,-0.00016,-0.0018,-6.2e-05,-0.059,-0.11,-0.025,0.5,-0.0028,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1 -9390000,0.78,-0.022,0.0058,-0.63,-0.33,-0.081,-0.13,-0.65,-0.19,-3.7e+02,0.00046,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1 -9490000,0.78,-0.022,0.0053,-0.63,-0.34,-0.094,-0.13,-0.67,-0.21,-3.7e+02,0.00049,-0.0082,-0.00015,-0.0018,0.00039,-0.067,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1 -9590000,0.78,-0.022,0.005,-0.63,-0.34,-0.093,-0.13,-0.7,-0.21,-3.7e+02,0.00034,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1 -9690000,0.78,-0.022,0.0052,-0.63,-0.36,-0.09,-0.12,-0.73,-0.22,-3.7e+02,0.00025,-0.008,-0.00014,-0.0021,0.00091,-0.075,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1 -9790000,0.78,-0.022,0.0048,-0.63,-0.37,-0.1,-0.11,-0.75,-0.23,-3.7e+02,0.00026,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1 -9890000,0.78,-0.021,0.0046,-0.63,-0.38,-0.1,-0.11,-0.78,-0.24,-3.7e+02,0.00017,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1 -9990000,0.78,-0.021,0.0046,-0.63,-0.39,-0.1,-0.1,-0.82,-0.25,-3.7e+02,0.00012,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1 -10090000,0.78,-0.021,0.0043,-0.63,-0.4,-0.1,-0.096,-0.84,-0.26,-3.7e+02,1.3e-05,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1 -10190000,0.78,-0.021,0.0046,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-2e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1 -10290000,0.78,-0.021,0.0048,-0.63,-0.44,-0.1,-0.083,-0.93,-0.27,-3.7e+02,-4.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10390000,0.78,-0.021,0.0046,-0.63,-0.0086,-0.022,0.0097,7.5e-05,-0.0019,-3.7e+02,-3.9e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10490000,0.78,-0.021,0.0047,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-6.2e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10590000,0.78,-0.02,0.0044,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00025,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1 -10690000,0.78,-0.02,0.0043,-0.63,-0.044,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00026,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 -10790000,0.78,-0.02,0.0039,-0.63,-0.041,-0.01,0.024,0.001,-0.0011,-3.7e+02,-0.00032,-0.0072,-0.00011,-0.00017,0.0013,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 -10890000,0.78,-0.02,0.0038,-0.63,-0.057,-0.013,0.02,-0.0037,-0.0023,-3.7e+02,-0.00033,-0.0071,-0.0001,-0.00011,0.0014,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 -10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.01,0.015,0.00013,-0.0011,-3.7e+02,-0.00036,-0.0069,-9.7e-05,0.0036,-0.00089,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.069,0,0,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1 -11090000,0.78,-0.02,0.0027,-0.63,-0.06,-0.014,0.02,-0.0048,-0.0026,-3.7e+02,-0.00041,-0.0068,-9.2e-05,0.0036,-0.00047,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.07,0,0,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1 -11190000,0.78,-0.019,0.0022,-0.63,-0.054,-0.01,0.0082,0.00068,-0.00048,-3.7e+02,-0.00051,-0.0067,-8.9e-05,0.0082,-0.0037,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1 -11290000,0.78,-0.019,0.0023,-0.63,-0.07,-0.012,0.008,-0.0058,-0.0016,-3.7e+02,-0.00047,-0.0067,-9.1e-05,0.0083,-0.0039,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1 -11390000,0.78,-0.019,0.0019,-0.63,-0.064,-0.011,0.0024,0.00033,-0.00038,-3.7e+02,-0.00057,-0.0067,-9e-05,0.012,-0.0076,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1 -11490000,0.78,-0.019,0.0021,-0.63,-0.078,-0.012,0.0032,-0.0072,-0.0013,-3.7e+02,-0.00055,-0.0068,-9.2e-05,0.012,-0.0081,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11590000,0.78,-0.019,0.0016,-0.63,-0.069,-0.012,-0.0027,-0.0022,-0.00077,-3.7e+02,-0.0006,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11690000,0.78,-0.019,0.0017,-0.63,-0.08,-0.015,-0.0071,-0.0098,-0.0023,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.013,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11790000,0.78,-0.019,0.0011,-0.63,-0.072,-0.011,-0.0089,-0.0062,-0.00016,-3.7e+02,-0.0006,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11890000,0.78,-0.019,0.0012,-0.63,-0.084,-0.011,-0.0098,-0.014,-0.0012,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1 -11990000,0.78,-0.019,0.0006,-0.63,-0.072,-0.0062,-0.015,-0.009,0.00097,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1 -12090000,0.78,-0.018,0.00044,-0.63,-0.078,-0.0083,-0.021,-0.016,0.00015,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0033,-0.09,-0.07,0,0,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1 -12190000,0.78,-0.018,-0.00024,-0.62,-0.064,-0.011,-0.016,-0.0086,-0.00028,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12290000,0.78,-0.019,-0.00026,-0.62,-0.07,-0.013,-0.015,-0.015,-0.0019,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12390000,0.78,-0.018,-0.00067,-0.62,-0.058,-0.011,-0.013,-0.0083,-0.00087,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12490000,0.78,-0.018,-0.00053,-0.62,-0.065,-0.013,-0.016,-0.015,-0.002,-3.7e+02,-0.00082,-0.0064,-8.5e-05,0.038,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1 -12590000,0.78,-0.018,-0.00073,-0.62,-0.06,-0.011,-0.022,-0.013,-0.00087,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12690000,0.78,-0.018,-0.00066,-0.62,-0.065,-0.01,-0.025,-0.019,-0.0011,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.025,0.5,-0.0034,-0.091,-0.07,0,0,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12790000,0.78,-0.018,-0.00094,-0.62,-0.061,-0.0093,-0.029,-0.017,-0.001,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12890000,0.78,-0.018,-0.00093,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0025,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 -12990000,0.78,-0.018,-0.0014,-0.62,-0.055,-0.0099,-0.028,-0.018,-0.0024,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1 -13090000,0.78,-0.018,-0.0013,-0.62,-0.061,-0.0097,-0.028,-0.024,-0.0032,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0012,0.0012,1,1 -13190000,0.78,-0.018,-0.0016,-0.62,-0.049,-0.0091,-0.025,-0.017,-0.0025,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.036,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,0.00027,0.00029,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13290000,0.78,-0.018,-0.0017,-0.62,-0.054,-0.012,-0.022,-0.023,-0.0046,-3.7e+02,-0.00094,-0.0062,-8.3e-05,0.049,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00027,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13390000,0.78,-0.018,-0.002,-0.62,-0.044,-0.011,-0.018,-0.016,-0.0038,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00025,0.00027,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13490000,0.78,-0.018,-0.002,-0.62,-0.047,-0.013,-0.016,-0.021,-0.0055,-3.7e+02,-0.00097,-0.0061,-8e-05,0.052,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00025,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.4e-06,2.3e-06,0.017,0.018,0.0087,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13590000,0.78,-0.018,-0.0022,-0.62,-0.038,-0.011,-0.019,-0.014,-0.004,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00025,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13690000,0.78,-0.018,-0.0022,-0.62,-0.041,-0.015,-0.023,-0.018,-0.0057,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13790000,0.78,-0.018,-0.0024,-0.62,-0.03,-0.013,-0.024,-0.0067,-0.0045,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13890000,0.78,-0.018,-0.0024,-0.62,-0.033,-0.014,-0.029,-0.01,-0.0064,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1 -13990000,0.78,-0.018,-0.0026,-0.62,-0.026,-0.013,-0.028,-0.0037,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0069,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00028,-0.0049,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14290000,0.78,-0.017,-0.0028,-0.62,-0.022,-0.014,-0.03,-0.0023,-0.0062,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0017,-0.0048,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.06,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14490000,0.78,-0.017,-0.003,-0.62,-0.019,-0.017,-0.035,-0.00051,-0.0068,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0064,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.063,-0.037,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14690000,0.78,-0.017,-0.003,-0.62,-0.023,-0.017,-0.032,-0.0035,-0.0084,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0078,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.019,-0.031,-0.0061,-0.0097,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -14990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0047,-0.0076,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -15090000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0092,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -15190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0074,-3.7e+02,-0.00097,-0.006,-7.5e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1 -15290000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.025,-0.0081,-0.0091,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15390000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.023,-0.0076,-0.0093,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15490000,0.78,-0.017,-0.0029,-0.62,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0098,-0.01,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15790000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.015,-0.025,-0.0086,-0.0097,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.039,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15890000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -15990000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.018,-0.0079,-0.01,-3.7e+02,-0.001,-0.006,-7.1e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.014,-0.0074,-0.0094,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0096,0.011,0.0025,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16290000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0098,-0.012,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0095,0.01,0.0024,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.015,-0.014,-0.0074,-0.0089,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0093,0.01,0.0022,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16490000,0.78,-0.017,-0.003,-0.62,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0021,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16590000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.012,-0.018,-0.0097,-0.0064,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.8e-06,2.4e-06,0.0091,0.01,0.002,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16690000,0.78,-0.017,-0.003,-0.62,-0.024,-0.013,-0.014,-0.012,-0.0074,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.009,0.0099,0.0019,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.0094,-0.013,-0.012,-0.0041,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0089,0.0098,0.0018,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16890000,0.78,-0.017,-0.003,-0.62,-0.024,-0.01,-0.01,-0.014,-0.0049,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0088,0.0097,0.0017,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -16990000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.01,-0.0099,-0.013,-0.0048,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.037,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0087,0.0095,0.0016,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -17090000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.012,-0.0098,-0.015,-0.0059,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.037,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0086,0.0094,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -17190000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.014,-0.011,-0.014,-0.0061,-3.7e+02,-0.0012,-0.006,-6e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.3e-06,1.6e-06,2.4e-06,0.0085,0.0093,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1 -17290000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.0061,-0.016,-0.0072,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0084,0.0092,0.0014,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.017,-0.0042,-0.013,-0.0075,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.091,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0083,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17490000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0093,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17590000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.018,0.003,-0.014,-0.009,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.023,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1 -17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18090000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18290000,0.78,-0.017,-0.0028,-0.62,-0.025,-0.02,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18490000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18590000,0.78,-0.016,-0.0029,-0.62,-0.022,-0.022,0.0062,-0.011,-0.013,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0074,0.0082,0.00076,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18690000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0074,0.0081,0.00074,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18790000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0073,0.008,0.0007,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18890000,0.78,-0.016,-0.003,-0.62,-0.022,-0.024,0.0046,-0.013,-0.015,-3.7e+02,-0.0013,-0.006,-4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0072,0.008,0.00068,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -18990000,0.78,-0.016,-0.003,-0.62,-0.019,-0.023,0.0033,-0.0093,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.00065,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19090000,0.78,-0.016,-0.003,-0.62,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.0071,0.0079,0.00063,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19190000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0063,-0.0072,-0.014,-3.7e+02,-0.0013,-0.006,-3.2e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.0006,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19290000,0.78,-0.016,-0.003,-0.62,-0.016,-0.024,0.0091,-0.0089,-0.016,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.06,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.007,0.0077,0.00058,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19390000,0.78,-0.016,-0.003,-0.62,-0.015,-0.022,0.013,-0.008,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.007,0.0077,0.00056,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19490000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0093,-0.0095,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0069,0.0076,0.00055,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1 -19590000,0.78,-0.016,-0.0031,-0.62,-0.013,-0.022,0.0085,-0.008,-0.015,-3.7e+02,-0.0013,-0.0059,-2e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,7.9e-07,9.7e-07,2.3e-06,0.0069,0.0075,0.00052,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -19690000,0.78,-0.016,-0.0031,-0.62,-0.014,-0.021,0.01,-0.0088,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.8e-07,9.6e-07,2.3e-06,0.0068,0.0075,0.00051,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -19790000,0.78,-0.016,-0.0031,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.8e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -19890000,0.78,-0.016,-0.0031,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.4e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-4.8e-06,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,-9.5e-08,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20190000,0.78,-0.016,-0.0033,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,5.9e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20290000,0.78,-0.016,-0.0033,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,7.6e-06,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20390000,0.78,-0.016,-0.0033,-0.62,-0.0085,-0.017,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20490000,0.78,-0.016,-0.0033,-0.62,-0.0087,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,9.8e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20590000,0.78,-0.016,-0.0033,-0.62,-0.0082,-0.014,0.014,-0.0085,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0064,0.007,0.00038,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20690000,0.78,-0.016,-0.0033,-0.62,-0.0089,-0.015,0.015,-0.0094,-0.018,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0064,0.007,0.00037,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20790000,0.78,-0.016,-0.0034,-0.62,-0.0066,-0.014,0.015,-0.0078,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0063,0.0069,0.00036,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20890000,0.78,-0.016,-0.0034,-0.62,-0.0068,-0.014,0.014,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,2.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0063,0.0069,0.00035,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -20990000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.012,0.015,-0.008,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0063,0.0069,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21090000,0.78,-0.016,-0.0034,-0.62,-0.0063,-0.012,0.015,-0.009,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0062,0.0068,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21190000,0.78,-0.016,-0.0034,-0.62,-0.0064,-0.011,0.014,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9.3e-05,0.0001,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00033,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21290000,0.78,-0.016,-0.0036,-0.62,-0.006,-0.012,0.016,-0.0094,-0.023,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00032,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21390000,0.78,-0.016,-0.0035,-0.62,-0.0054,-0.0074,0.016,-0.0083,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.0061,0.0067,0.00031,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21490000,0.78,-0.016,-0.0035,-0.62,-0.006,-0.0084,0.016,-0.0093,-0.019,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.0061,0.0067,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21590000,0.78,-0.016,-0.0035,-0.62,-0.0046,-0.0067,0.016,-0.0078,-0.015,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.7e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.0061,0.0066,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21690000,0.78,-0.016,-0.0035,-0.62,-0.0062,-0.0078,0.017,-0.009,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.006,0.0066,0.00029,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21790000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.0055,0.016,-0.0079,-0.01,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.5e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21890000,0.78,-0.016,-0.0034,-0.62,-0.0059,-0.0064,0.016,-0.0086,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,9e-05,9.6e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1 -21990000,0.78,-0.016,-0.0033,-0.62,-0.0057,-0.0036,0.017,-0.0081,-0.007,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22090000,0.78,-0.016,-0.0033,-0.62,-0.0054,-0.0052,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22190000,0.78,-0.016,-0.0033,-0.62,-0.0041,-0.0057,0.015,-0.007,-0.0067,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0054,0.016,-0.0077,-0.0071,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22390000,0.78,-0.016,-0.0034,-0.62,-0.0012,-0.0053,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22490000,0.78,-0.016,-0.0034,-0.62,-4.6e-06,-0.006,0.018,-0.0054,-0.0068,-3.7e+02,-0.0014,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22590000,0.78,-0.016,-0.0034,-0.62,0.0018,-0.0049,0.017,-0.0036,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22690000,0.78,-0.016,-0.0034,-0.62,0.0034,-0.0063,0.019,-0.0029,-0.0073,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22790000,0.78,-0.016,-0.0033,-0.62,0.0044,-0.0055,0.02,-0.0024,-0.0059,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22890000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0064,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 -22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0066,0.022,-0.0026,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0063,0.023,-0.0024,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23190000,0.78,-0.016,-0.0033,-0.62,0.0026,-0.0052,0.024,-0.0051,-0.0072,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0057,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23290000,0.78,-0.016,-0.0032,-0.62,0.0023,-0.005,0.025,-0.0054,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,9.1e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23390000,0.78,-0.016,-0.0033,-0.62,-0.001,-0.0047,0.022,-0.0096,-0.0083,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23490000,0.78,-0.013,-0.0054,-0.62,0.0046,-0.0043,-0.011,-0.01,-0.0099,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00021,-0.043,-0.0095,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23690000,0.78,0.0011,-0.0086,-0.62,0.043,0.014,-0.093,-0.007,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23790000,0.78,-0.0026,-0.0061,-0.62,0.064,0.031,-0.15,-0.007,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23890000,0.78,-0.0089,-0.0042,-0.62,0.077,0.043,-0.2,0.00048,-2e-05,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -23990000,0.78,-0.014,-0.0034,-0.62,0.072,0.043,-0.25,-0.005,-0.0015,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.0019,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.067,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24190000,0.78,-0.01,-0.0054,-0.62,0.07,0.041,-0.35,-0.0059,-0.0003,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1 -24290000,0.78,-0.0092,-0.0058,-0.62,0.078,0.046,-0.4,0.00062,0.0041,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1 -24390000,0.79,-0.0096,-0.0059,-0.62,0.075,0.044,-0.46,-0.012,-0.0023,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.6e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1 -24490000,0.79,-0.0054,-0.0063,-0.62,0.086,0.051,-0.51,-0.0038,0.0024,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1 -24590000,0.79,-0.0019,-0.0064,-0.62,0.09,0.055,-0.56,-0.017,-0.0064,-3.7e+02,-0.0012,-0.0059,6.4e-05,0.067,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.6e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.6e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24690000,0.79,-0.00099,-0.0064,-0.62,0.11,0.071,-0.64,-0.0079,-0.0014,-3.7e+02,-0.0012,-0.0059,7.1e-05,0.068,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.09,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24790000,0.79,-0.0025,-0.0063,-0.62,0.11,0.08,-0.73,-0.027,-0.0061,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0026,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.018,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24890000,0.79,-0.00064,-0.0078,-0.62,0.13,0.095,-0.75,-0.016,0.0027,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.089,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0058,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1 -24990000,0.79,0.0011,-0.0095,-0.62,0.13,0.1,-0.81,-0.038,-0.0036,-3.7e+02,-0.0011,-0.0059,4.5e-05,0.071,-0.03,-0.13,-0.11,-0.026,0.5,-0.0024,-0.089,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25090000,0.79,0.00055,-0.0098,-0.62,0.16,0.12,-0.86,-0.024,0.0078,-3.7e+02,-0.0011,-0.0059,4.3e-05,0.071,-0.03,-0.13,-0.11,-0.027,0.5,-0.0025,-0.088,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1 -25190000,0.79,-0.0014,-0.0096,-0.61,0.15,0.11,-0.91,-0.068,-0.014,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0022,-0.088,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00057,0.0011,0.0012,1,1 -25290000,0.79,0.0056,-0.011,-0.62,0.18,0.13,-0.96,-0.052,-0.003,-3.7e+02,-0.0011,-0.0058,2.6e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.0011,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1 -25390000,0.79,0.012,-0.011,-0.61,0.18,0.13,-1,-0.1,-0.027,-3.7e+02,-0.001,-0.0058,7.5e-06,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0021,-0.087,-0.07,0,0,8.1e-05,8.5e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.001,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1 -25490000,0.79,0.013,-0.011,-0.61,0.21,0.16,-1.1,-0.081,-0.014,-3.7e+02,-0.001,-0.0058,1.6e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0024,-0.086,-0.069,0,0,8.2e-05,8.5e-05,0.046,0.022,0.022,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.2e-05,0.0012,0.00057,0.0011,0.0011,1,1 -25590000,0.79,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.058,0.0024,-3.7e+02,-0.001,-0.0058,2.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.6e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.1e-05,0.0011,0.00056,0.0011,0.0011,1,1 -25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,2.9e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1 -25790000,0.79,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0013,0.041,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.079,-0.03,-0.13,-0.12,-0.028,0.5,-0.0035,-0.083,-0.067,0,0,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1 -25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.04,0.065,-3.7e+02,-0.00099,-0.0058,5.6e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1 -25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.5e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0045,-0.08,-0.065,0,0,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1 -26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.079,-0.031,-0.13,-0.12,-0.029,0.5,-0.0046,-0.079,-0.065,0,0,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1 -26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.031,-0.13,-0.13,-0.03,0.5,-0.0054,-0.075,-0.063,0,0,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1 -26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.7e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00052,0.00091,0.00099,1,1 -26390000,0.78,0.041,-0.021,-0.62,0.75,0.51,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,8.5e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,9e-05,0.041,0.042,0.046,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00084,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1 -26490000,0.78,0.057,-0.027,-0.63,0.84,0.57,-1.3,0.4,0.3,-3.7e+02,-0.00097,-0.0058,9e-05,0.08,-0.032,-0.13,-0.13,-0.031,0.49,-0.0066,-0.069,-0.058,0,0,8.9e-05,9.1e-05,0.039,0.045,0.05,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00081,4.9e-05,0.00093,0.00049,0.00084,0.00093,1,1 -26590000,0.78,0.074,-0.032,-0.62,0.95,0.65,-1.3,0.49,0.36,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.081,-0.032,-0.13,-0.14,-0.032,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9.1e-05,0.038,0.049,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00076,4.6e-05,0.00088,0.00047,0.0008,0.00088,1,1 -26690000,0.77,0.077,-0.033,-0.63,1.1,0.72,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,0.0001,0.08,-0.032,-0.13,-0.14,-0.033,0.49,-0.0073,-0.061,-0.052,0,0,9.1e-05,9.2e-05,0.035,0.053,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00071,4.3e-05,0.00082,0.00045,0.00074,0.00082,1,1 -26790000,0.77,0.071,-0.032,-0.63,1.2,0.8,-1.3,0.71,0.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.032,-0.13,-0.14,-0.034,0.48,-0.0071,-0.057,-0.049,0,0,9.2e-05,9.3e-05,0.032,0.056,0.067,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0057,0.00014,0.00067,4.1e-05,0.00078,0.00042,0.00069,0.00077,1,1 -26890000,0.77,0.094,-0.039,-0.63,1.3,0.88,-1.3,0.84,0.58,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.035,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.3e-05,0.03,0.059,0.072,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00063,3.9e-05,0.00073,0.00039,0.00065,0.00073,1,1 -26990000,0.76,0.12,-0.044,-0.63,1.5,0.99,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.032,-0.13,-0.15,-0.036,0.48,-0.0079,-0.047,-0.043,0,0,9.3e-05,9.4e-05,0.027,0.063,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00013,0.00057,3.5e-05,0.00066,0.00035,0.00059,0.00066,1,1 -27090000,0.76,0.12,-0.045,-0.63,1.7,1.1,-1.3,1.1,0.77,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.037,0.47,-0.0078,-0.043,-0.039,0,0,9.3e-05,9.4e-05,0.024,0.067,0.085,0.0061,0.36,0.37,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00052,3.2e-05,0.00059,0.00032,0.00053,0.00059,1,1 -27190000,0.76,0.11,-0.042,-0.63,1.9,1.2,-1.2,1.3,0.89,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.038,0.47,-0.0074,-0.04,-0.035,0,0,9.4e-05,9.5e-05,0.021,0.071,0.091,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00048,3e-05,0.00055,0.00029,0.00049,0.00054,1,1 -27290000,0.77,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.5e-05,0.019,0.072,0.094,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00045,2.9e-05,0.00052,0.00026,0.00046,0.00051,1,1 -27390000,0.77,0.078,-0.033,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0074,-0.035,-0.032,0,0,9.5e-05,9.6e-05,0.017,0.073,0.094,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00043,2.8e-05,0.0005,0.00023,0.00044,0.00049,1,1 -27490000,0.77,0.062,-0.029,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0071,-0.034,-0.032,0,0,9.6e-05,9.6e-05,0.015,0.074,0.093,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00042,2.7e-05,0.00049,0.00021,0.00043,0.00048,1,1 -27590000,0.77,0.05,-0.025,-0.63,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.028,-0.13,-0.17,-0.039,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.7e-05,0.014,0.074,0.092,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00041,2.6e-05,0.00048,0.0002,0.00042,0.00048,1,1 -27690000,0.77,0.048,-0.025,-0.63,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.028,-0.13,-0.17,-0.04,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.7e-05,0.013,0.074,0.09,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.0004,2.6e-05,0.00048,0.00019,0.00042,0.00047,1,1 -27790000,0.77,0.05,-0.025,-0.63,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,9.7e-05,0.082,-0.027,-0.13,-0.17,-0.04,0.47,-0.0056,-0.032,-0.031,0,0,9.8e-05,9.8e-05,0.012,0.074,0.089,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00039,2.6e-05,0.00047,0.00017,0.00041,0.00047,1,1 -27890000,0.77,0.048,-0.024,-0.63,2.3,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,9.6e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.46,-0.0056,-0.031,-0.031,0,0,9.9e-05,9.8e-05,0.011,0.075,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00039,2.5e-05,0.00047,0.00016,0.0004,0.00047,1,1 -27990000,0.77,0.044,-0.023,-0.63,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.5e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.47,-0.0056,-0.031,-0.031,0,0,0.0001,9.9e-05,0.01,0.075,0.088,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.5e-05,0.00047,0.00016,0.0004,0.00046,1,1 -28090000,0.78,0.058,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0096,0.076,0.088,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00038,2.4e-05,0.00046,0.00015,0.00039,0.00046,1,1 -28190000,0.77,0.071,-0.031,-0.63,2.4,1.7,-0.93,3.5,2.4,-3.7e+02,-0.00095,-0.0058,8.9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,0.0001,0.0001,0.0091,0.077,0.088,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00037,2.4e-05,0.00046,0.00014,0.00038,0.00045,1,1 -28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.5e-05,0.083,-0.024,-0.13,-0.17,-0.04,0.46,-0.0048,-0.029,-0.029,0,0,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1 -28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,8e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.077,0.084,0.0061,0.75,0.79,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1 -28490000,0.78,0.0015,-0.0059,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.5e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1 -28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.083,-0.022,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1 -28690000,0.78,-0.0032,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,7e-05,0.082,-0.022,-0.12,-0.17,-0.041,0.46,-0.0044,-0.028,-0.029,0,0,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1 -28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.5e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1 -28890000,0.78,-0.0033,-0.0037,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6.1e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1 -28990000,0.78,-0.0028,-0.0039,-0.62,2.1,1.5,0.98,5.4,3.8,-3.7e+02,-0.001,-0.0058,5.5e-05,0.081,-0.02,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29090000,0.78,-0.0024,-0.004,-0.62,2,1.5,0.97,5.6,4,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.085,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29190000,0.78,-0.0021,-0.0041,-0.62,2,1.5,0.97,5.8,4.1,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.083,0.087,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1 -29290000,0.78,-0.0013,-0.0043,-0.62,1.9,1.5,0.99,6,4.2,-3.7e+02,-0.001,-0.0058,4.6e-05,0.08,-0.019,-0.12,-0.17,-0.041,0.46,-0.0036,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.00011,0.00037,0.00043,1,1 -29390000,0.78,9e-05,-0.0046,-0.62,1.9,1.4,1,6.2,4.4,-3.7e+02,-0.001,-0.0058,3.9e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1 -29490000,0.78,0.0013,-0.005,-0.62,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.7e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1 -29590000,0.78,0.0023,-0.0052,-0.62,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0057,3.4e-05,0.079,-0.017,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1 -29690000,0.78,0.003,-0.0055,-0.62,1.7,1.4,0.99,6.7,4.8,-3.7e+02,-0.001,-0.0057,2.9e-05,0.079,-0.016,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.9e-05,0.00037,0.00043,1,1 -29790000,0.78,0.0034,-0.0056,-0.62,1.7,1.4,0.98,6.9,5,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.015,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.027,0,0,0.00011,0.0001,0.0054,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.8e-05,0.00037,0.00042,1,1 -29890000,0.78,0.0036,-0.0057,-0.62,1.7,1.3,0.97,7.1,5.1,-3.7e+02,-0.001,-0.0057,2e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.7e-05,0.00037,0.00042,1,1 -29990000,0.78,0.0036,-0.0057,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1 -30090000,0.78,0.0035,-0.0057,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1.2e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1 -30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.3e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1 -30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,1e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1 -30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,5.8e-06,0.077,-0.012,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.11,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1 -30490000,0.78,0.0025,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,4.7e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1 -30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,2.6e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1 -30690000,0.78,0.0017,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-7.1e-07,0.076,-0.0098,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1 -30790000,0.78,0.0013,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-3.8e-06,0.076,-0.0096,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1 -30890000,0.78,0.00091,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-6.8e-06,0.075,-0.0088,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1 -30990000,0.78,0.00032,-0.005,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1e-05,0.075,-0.008,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1 -31090000,0.78,-0.00023,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.5e-05,0.074,-0.0073,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 -31190000,0.78,-0.00064,-0.0047,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0064,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 -31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2e-05,0.074,-0.0057,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1 -31390000,0.78,-0.002,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.074,-0.0051,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 -31490000,0.78,-0.0026,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-2.9e-05,0.073,-0.0044,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1 -31590000,0.78,-0.0029,-0.0042,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3e-05,0.073,-0.0037,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1 -31690000,0.78,-0.0037,-0.004,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.072,-0.003,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 -31790000,0.78,-0.0044,-0.0038,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.4e-05,0.072,-0.0021,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 -31890000,0.78,-0.0051,-0.0037,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-3.8e-05,0.071,-0.0012,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1 -31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.071,-0.0003,-0.12,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1 -32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.95,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-4.8e-05,0.07,0.0004,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 -32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-5.7e-05,0.07,0.0013,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 -32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.1e-05,0.069,0.0024,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 -32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.069,0.003,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1 -32490000,0.78,-0.009,-0.0029,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.068,0.0038,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32590000,0.78,-0.0093,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.8e-05,0.068,0.0041,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.067,0.0047,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.025,0,0,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.067,0.0051,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1 -32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.066,0.0056,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 -32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0062,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 -33090000,0.79,-0.0092,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.065,0.0064,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1 -33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.065,0.0065,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1 -33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.065,0.0063,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1 -33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.064,0.006,-0.11,-0.18,-0.041,0.46,-0.0009,-0.027,-0.024,0,0,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8e-05,0.00032,0.00039,1,1 -33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.3e-05,0.064,0.0061,-0.11,-0.18,-0.043,0.46,-0.0004,-0.02,-0.024,0,0,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1 -33590000,0.99,-0.0083,-0.00011,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.8e-05,0.064,0.0061,-0.11,-0.19,-0.044,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1 -33690000,1,-0.012,0.0041,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.064,0.0061,-0.11,-0.19,-0.045,0.46,0.00018,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1 -33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00053,-0.0066,-0.025,0,0,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1 -33890000,0.93,-0.013,0.0086,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.1e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00075,-0.0053,-0.025,0,0,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1 -33990000,0.86,-0.015,0.0072,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0058,-0.11,-0.2,-0.046,0.46,0.00053,-0.0039,-0.025,0,0,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1 -34090000,0.8,-0.016,0.0064,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0052,-0.11,-0.2,-0.046,0.46,0.0002,-0.0033,-0.025,0,0,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1 -34190000,0.75,-0.014,0.0071,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1 -34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0047,-0.11,-0.2,-0.047,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1 -34390000,0.69,-0.0077,0.01,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0044,-0.11,-0.2,-0.047,0.46,9.4e-05,-0.002,-0.025,0,0,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1 -34490000,0.67,-0.0055,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0043,-0.11,-0.2,-0.047,0.46,5.2e-05,-0.002,-0.025,0,0,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1 -34590000,0.66,-0.0041,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0042,-0.11,-0.2,-0.047,0.46,-4.5e-05,-0.0019,-0.025,0,0,0.00014,9.7e-05,0.0012,0.057,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1 -34690000,0.65,-0.0033,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0042,-0.11,-0.2,-0.047,0.46,1.8e-05,-0.0016,-0.025,0,0,0.00014,9.7e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1 -34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0041,-0.11,-0.2,-0.047,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1 -34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0039,-0.11,-0.2,-0.047,0.46,8.8e-05,-0.0016,-0.025,0,0,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1 -34990000,0.64,-0.0061,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1 -35090000,0.64,-0.0062,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00022,-0.0016,-0.025,0,0,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1 -35190000,0.64,-0.0063,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00025,-0.0015,-0.025,0,0,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1 -35290000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1 -35390000,0.64,-0.0064,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1 -35490000,0.64,-0.0065,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00045,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1 -35590000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00042,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1 -35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1 -35790000,0.64,-0.0065,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1 -35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1 -35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1 -36090000,0.64,-0.0066,0.02,0.77,-3.4,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1 -36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1 -36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0016,-0.025,0,0,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1 -36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1 -36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00055,-0.0015,-0.025,0,0,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1 -36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1 -36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1 -36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00064,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1 -36890000,0.64,-0.0069,0.021,0.77,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0041,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 -36990000,0.64,-0.0069,0.021,0.77,-3.7,-4.1,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0042,-0.11,-0.2,-0.047,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1 -37090000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0064,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1 -37190000,0.64,-0.0069,0.021,0.77,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 -37290000,0.64,-0.0069,0.021,0.77,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.7e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1 -37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.017,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00071,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1 -37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.7e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0011,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 -37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.067,0.0045,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1 -37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 -37790000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1 -37890000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0046,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 -37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1 -38090000,0.64,-0.0071,0.021,0.77,-4,-4.9,0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1 -38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1 -38290000,0.64,-0.0071,0.021,0.77,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 -38390000,0.64,-0.007,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1 -38490000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 -38590000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 -38690000,0.64,-0.007,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.71,0.85,0.0065,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1 -38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0046,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1 -38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1 +10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.032 +90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.058 +190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.082 +290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.1,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.11 +390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.1,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.13 +490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.16 +590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.18 +690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.1,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.21 +790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00077,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.23 +890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.019,0.019,0.00051,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.26 +990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.021,0.021,0.00062,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.28 +1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.023,0.023,0.00043,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.31 +1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 +1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 +1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 +1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +2190000,1,-0.011,-0.014,5.9e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.011,-0.013,5.9e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.011,-0.013,4.9e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.011,-0.013,-1.1e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.011,-0.013,4.9e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.011,-0.013,-8e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.011,-0.013,3.2e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.011,-0.012,3.2e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.011,-0.013,-4.5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.011,-0.012,1.9e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.01,-0.012,8.1e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.01,-0.012,0.00019,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.01,-0.012,0.00018,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0096,-0.011,0.00033,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0094,-0.011,0.00031,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0094,-0.011,0.00021,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-3.6e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0093,-0.011,0.00023,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-3.6e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.5e-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.0094,-0.011,0.00016,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-7.6e-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,9e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.6e-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.78,-0.024,0.0048,-0.62,-0.22,-0.051,-0.11,-0.13,-0.03,-3.7e+02,-0.00029,-0.01,-0.0002,0,0,0.0012,-0.092,-0.021,0.51,-0.00079,-0.075,-0.061,0,0,-3.6e+02,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1,1.7 +6890000,0.78,-0.025,0.0057,-0.62,-0.27,-0.065,-0.12,-0.16,-0.04,-3.7e+02,-0.0001,-0.011,-0.00022,0,0,0.0012,-0.1,-0.023,0.51,-0.0012,-0.083,-0.067,0,0,-3.6e+02,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00025,0.0013,0.00089,0.0014,0.0013,1,1,1.8 +6990000,0.78,-0.025,0.006,-0.62,-0.3,-0.077,-0.12,-0.2,-0.05,-3.7e+02,-6.9e-06,-0.011,-0.00022,-0.00057,-7.3e-05,0.00095,-0.1,-0.024,0.5,-0.0016,-0.084,-0.067,0,0,-3.6e+02,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1,1.8 +7090000,0.78,-0.025,0.0062,-0.62,-0.33,-0.088,-0.12,-0.23,-0.063,-3.7e+02,0.00011,-0.011,-0.00023,-0.0013,-0.0003,0.00061,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00016,0.0013,0.00083,0.0014,0.0013,1,1,1.8 +7190000,0.78,-0.025,0.0064,-0.62,-0.36,-0.097,-0.15,-0.26,-0.075,-3.7e+02,0.00017,-0.011,-0.00023,-0.0017,-0.00046,0.00083,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00082,0.0013,0.0013,1,1,1.8 +7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.099,-0.14,-0.3,-0.082,-3.7e+02,0.00012,-0.011,-0.00023,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1,1.9 +7390000,0.78,-0.025,0.0069,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,0.00014,-0.011,-0.00022,-0.0016,-0.00046,9.1e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1,1.9 +7490000,0.78,-0.025,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00027,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.0019,-0.085,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 +7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00026,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 +7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1,2 +7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0062,-0.16,-0.44,-0.14,-3.7e+02,0.00041,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1,2 +7890000,0.78,-0.024,0.0073,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00045,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 +7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.00046,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 +8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.0005,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1,2.1 +8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00049,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 +8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00059,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 +8390000,0.78,-0.024,0.0071,-0.63,-0.18,-0.036,-0.17,-0.49,-0.15,-3.7e+02,0.0006,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 +8490000,0.78,-0.024,0.0071,-0.63,-0.2,-0.039,-0.17,-0.49,-0.15,-3.7e+02,0.00061,-0.0099,-0.00021,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 +8590000,0.78,-0.023,0.0073,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00041,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 +8690000,0.78,-0.023,0.0069,-0.63,-0.24,-0.044,-0.16,-0.53,-0.15,-3.7e+02,0.00042,-0.0096,-0.00019,-0.0019,-0.00051,-0.033,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,29,29,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,8.6e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 +8790000,0.78,-0.023,0.007,-0.63,-0.25,-0.047,-0.15,-0.53,-0.15,-3.7e+02,0.00045,-0.0095,-0.00019,-0.0019,-0.00051,-0.039,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.096,25,25,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,8.5e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.2 +8890000,0.78,-0.023,0.0069,-0.63,-0.27,-0.051,-0.15,-0.55,-0.16,-3.7e+02,0.00044,-0.0094,-0.00018,-0.0019,-0.00051,-0.043,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.095,27,27,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0012,8.4e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.3 +8990000,0.78,-0.023,0.0069,-0.63,-0.28,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00049,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 +9090000,0.78,-0.022,0.0069,-0.63,-0.29,-0.053,-0.14,-0.58,-0.17,-3.7e+02,0.00041,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 +9190000,0.78,-0.022,0.0062,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00042,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.3 +9290000,0.78,-0.022,0.0059,-0.63,-0.31,-0.072,-0.14,-0.62,-0.18,-3.7e+02,0.00044,-0.0086,-0.00016,-0.0018,-6.2e-05,-0.059,-0.11,-0.025,0.5,-0.0028,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 +9390000,0.78,-0.022,0.0058,-0.63,-0.33,-0.081,-0.13,-0.65,-0.19,-3.7e+02,0.00046,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 +9490000,0.78,-0.022,0.0053,-0.63,-0.34,-0.094,-0.13,-0.67,-0.21,-3.7e+02,0.00049,-0.0082,-0.00015,-0.0018,0.00039,-0.067,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 +9590000,0.78,-0.022,0.005,-0.63,-0.34,-0.093,-0.13,-0.7,-0.21,-3.7e+02,0.00034,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 +9690000,0.78,-0.022,0.0052,-0.63,-0.36,-0.09,-0.12,-0.73,-0.22,-3.7e+02,0.00025,-0.008,-0.00014,-0.0021,0.00091,-0.075,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 +9790000,0.78,-0.022,0.0048,-0.63,-0.37,-0.1,-0.11,-0.75,-0.23,-3.7e+02,0.00026,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 +9890000,0.78,-0.021,0.0046,-0.63,-0.38,-0.1,-0.11,-0.78,-0.24,-3.7e+02,0.00017,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 +9990000,0.78,-0.021,0.0046,-0.63,-0.39,-0.1,-0.1,-0.82,-0.25,-3.7e+02,0.00012,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.5 +10090000,0.78,-0.021,0.0043,-0.63,-0.4,-0.1,-0.096,-0.84,-0.26,-3.7e+02,1.3e-05,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 +10190000,0.78,-0.021,0.0046,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-2e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 +10290000,0.78,-0.021,0.0048,-0.63,-0.44,-0.1,-0.083,-0.93,-0.27,-3.7e+02,-4.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 +10390000,0.78,-0.021,0.0046,-0.63,-0.0086,-0.022,0.0097,7.5e-05,-0.0019,-3.7e+02,-3.9e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 +10490000,0.78,-0.021,0.0047,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-6.2e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 +10590000,0.78,-0.02,0.0044,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00025,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 +10690000,0.78,-0.02,0.0043,-0.63,-0.044,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00026,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 +10790000,0.78,-0.02,0.0039,-0.63,-0.041,-0.01,0.024,0.001,-0.0011,-3.7e+02,-0.00032,-0.0072,-0.00011,-0.00017,0.0013,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 +10890000,0.78,-0.02,0.0038,-0.63,-0.057,-0.013,0.02,-0.0037,-0.0023,-3.7e+02,-0.00033,-0.0071,-0.0001,-0.00011,0.0014,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 +10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.01,0.015,0.00013,-0.0011,-3.7e+02,-0.00036,-0.0069,-9.7e-05,0.0036,-0.00089,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.069,0,0,-3.6e+02,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 +11090000,0.78,-0.02,0.0027,-0.63,-0.06,-0.014,0.02,-0.0048,-0.0026,-3.7e+02,-0.00041,-0.0068,-9.2e-05,0.0036,-0.00047,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.07,0,0,-3.6e+02,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 +11190000,0.78,-0.019,0.0022,-0.63,-0.054,-0.01,0.0082,0.00068,-0.00048,-3.7e+02,-0.00051,-0.0067,-8.9e-05,0.0082,-0.0037,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 +11290000,0.78,-0.019,0.0023,-0.63,-0.07,-0.012,0.008,-0.0058,-0.0016,-3.7e+02,-0.00047,-0.0067,-9.1e-05,0.0083,-0.0039,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.9 +11390000,0.78,-0.019,0.0019,-0.63,-0.064,-0.011,0.0024,0.00033,-0.00038,-3.7e+02,-0.00057,-0.0067,-9e-05,0.012,-0.0076,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 +11490000,0.78,-0.019,0.0021,-0.63,-0.078,-0.012,0.0032,-0.0072,-0.0013,-3.7e+02,-0.00055,-0.0068,-9.3e-05,0.012,-0.0081,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 +11590000,0.78,-0.019,0.0016,-0.63,-0.069,-0.012,-0.0027,-0.0022,-0.00077,-3.7e+02,-0.0006,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,-3.6e+02,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 +11690000,0.78,-0.019,0.0017,-0.63,-0.08,-0.015,-0.0071,-0.0098,-0.0023,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.013,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,-3.6e+02,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 +11790000,0.78,-0.019,0.0011,-0.63,-0.072,-0.011,-0.0089,-0.0062,-0.00016,-3.7e+02,-0.0006,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 +11890000,0.78,-0.019,0.0012,-0.63,-0.084,-0.011,-0.0098,-0.014,-0.0012,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 +11990000,0.78,-0.019,0.0006,-0.63,-0.072,-0.0062,-0.015,-0.009,0.00097,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3 +12090000,0.78,-0.018,0.00044,-0.63,-0.078,-0.0083,-0.021,-0.016,0.00015,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0033,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1 +12190000,0.78,-0.018,-0.00024,-0.62,-0.064,-0.011,-0.016,-0.0086,-0.00028,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 +12290000,0.78,-0.019,-0.00026,-0.62,-0.07,-0.013,-0.015,-0.015,-0.0019,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 +12390000,0.78,-0.018,-0.00067,-0.62,-0.058,-0.011,-0.013,-0.0083,-0.00087,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 +12490000,0.78,-0.018,-0.00053,-0.62,-0.065,-0.013,-0.016,-0.015,-0.002,-3.7e+02,-0.00082,-0.0064,-8.5e-05,0.038,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.2 +12590000,0.78,-0.018,-0.00073,-0.62,-0.06,-0.011,-0.022,-0.013,-0.00087,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 +12690000,0.78,-0.018,-0.00066,-0.62,-0.065,-0.01,-0.025,-0.019,-0.0011,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.025,0.5,-0.0034,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 +12790000,0.78,-0.018,-0.00094,-0.62,-0.061,-0.0093,-0.029,-0.017,-0.001,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 +12890000,0.78,-0.018,-0.00093,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0025,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 +12990000,0.78,-0.018,-0.0014,-0.62,-0.055,-0.0099,-0.028,-0.018,-0.0024,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 +13090000,0.78,-0.018,-0.0013,-0.62,-0.061,-0.0097,-0.028,-0.024,-0.0032,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0012,0.0012,1,1,3.3 +13190000,0.78,-0.018,-0.0016,-0.62,-0.049,-0.0091,-0.025,-0.017,-0.0026,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.036,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00029,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.3 +13290000,0.78,-0.018,-0.0017,-0.62,-0.054,-0.012,-0.022,-0.023,-0.0046,-3.7e+02,-0.00094,-0.0062,-8.3e-05,0.049,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13390000,0.78,-0.018,-0.002,-0.62,-0.044,-0.011,-0.018,-0.016,-0.0038,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00027,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13490000,0.78,-0.018,-0.002,-0.62,-0.047,-0.013,-0.016,-0.021,-0.0055,-3.7e+02,-0.00097,-0.0061,-8e-05,0.052,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.4e-06,2.3e-06,0.017,0.018,0.0087,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13590000,0.78,-0.018,-0.0022,-0.62,-0.038,-0.011,-0.019,-0.014,-0.004,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13690000,0.78,-0.018,-0.0022,-0.62,-0.041,-0.015,-0.023,-0.018,-0.0057,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +13790000,0.78,-0.018,-0.0024,-0.62,-0.03,-0.013,-0.024,-0.0067,-0.0045,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +13890000,0.78,-0.018,-0.0024,-0.62,-0.033,-0.014,-0.029,-0.01,-0.0064,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +13990000,0.78,-0.018,-0.0026,-0.62,-0.026,-0.013,-0.028,-0.0037,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.5 +14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0069,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00028,-0.0049,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14290000,0.78,-0.017,-0.0028,-0.62,-0.022,-0.014,-0.03,-0.0023,-0.0062,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0017,-0.0048,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.06,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14490000,0.78,-0.017,-0.003,-0.62,-0.019,-0.017,-0.035,-0.00051,-0.0068,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0064,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.063,-0.037,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14690000,0.78,-0.017,-0.003,-0.62,-0.023,-0.017,-0.032,-0.0035,-0.0084,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0078,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.019,-0.031,-0.0061,-0.0097,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +14990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0047,-0.0076,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +15090000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0092,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +15190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0074,-3.7e+02,-0.00097,-0.006,-7.5e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +15290000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.025,-0.0081,-0.0091,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15390000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.023,-0.0076,-0.0093,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15490000,0.78,-0.017,-0.0029,-0.62,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0098,-0.01,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +15790000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.015,-0.025,-0.0086,-0.0097,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.039,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +15890000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +15990000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.018,-0.0079,-0.01,-3.7e+02,-0.001,-0.006,-7.1e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.004,-0.091,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +16090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.014,-0.0074,-0.0094,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0096,0.011,0.0025,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16290000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0098,-0.012,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0095,0.01,0.0024,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.015,-0.014,-0.0074,-0.0089,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0093,0.01,0.0022,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16490000,0.78,-0.017,-0.003,-0.62,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0021,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16590000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.012,-0.018,-0.0097,-0.0064,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.8e-06,2.4e-06,0.0091,0.01,0.002,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16690000,0.78,-0.017,-0.003,-0.62,-0.024,-0.013,-0.014,-0.012,-0.0074,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.009,0.0099,0.0019,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.0094,-0.013,-0.012,-0.0041,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0089,0.0098,0.0018,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16890000,0.78,-0.017,-0.003,-0.62,-0.024,-0.01,-0.01,-0.014,-0.0049,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0088,0.0097,0.0017,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +16990000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.01,-0.0099,-0.013,-0.0048,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.037,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0087,0.0095,0.0016,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +17090000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.012,-0.0098,-0.015,-0.0059,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.037,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0086,0.0094,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +17190000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.014,-0.011,-0.014,-0.0061,-3.7e+02,-0.0012,-0.006,-6e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.3e-06,1.6e-06,2.4e-06,0.0085,0.0093,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +17290000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.0061,-0.016,-0.0072,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0084,0.0092,0.0014,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 +17390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.017,-0.0042,-0.013,-0.0075,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.091,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0083,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 +17490000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0093,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 +17590000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.018,0.003,-0.014,-0.009,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 +17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.023,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +18090000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18290000,0.78,-0.017,-0.0028,-0.62,-0.025,-0.02,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18490000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18590000,0.78,-0.016,-0.0029,-0.62,-0.022,-0.022,0.0062,-0.011,-0.013,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0074,0.0082,0.00076,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18690000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0074,0.0081,0.00074,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18790000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0073,0.008,0.0007,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18890000,0.78,-0.016,-0.003,-0.62,-0.022,-0.024,0.0046,-0.013,-0.015,-3.7e+02,-0.0013,-0.006,-4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0072,0.008,0.00068,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +18990000,0.78,-0.016,-0.003,-0.62,-0.019,-0.023,0.0033,-0.0093,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.00065,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +19090000,0.78,-0.016,-0.003,-0.62,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.0071,0.0079,0.00063,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +19190000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0063,-0.0072,-0.014,-3.7e+02,-0.0013,-0.006,-3.2e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.0006,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +19290000,0.78,-0.016,-0.003,-0.62,-0.016,-0.024,0.0091,-0.0089,-0.016,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.06,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.007,0.0077,0.00058,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 +19390000,0.78,-0.016,-0.003,-0.62,-0.015,-0.022,0.013,-0.008,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.007,0.0077,0.00056,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 +19490000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0093,-0.0095,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0069,0.0076,0.00055,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 +19590000,0.78,-0.016,-0.0031,-0.62,-0.013,-0.022,0.0085,-0.008,-0.015,-3.7e+02,-0.0013,-0.0059,-2e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,8e-07,9.7e-07,2.3e-06,0.0069,0.0075,0.00052,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,4.9 +19690000,0.78,-0.016,-0.0031,-0.62,-0.014,-0.021,0.01,-0.0088,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.8e-07,9.6e-07,2.3e-06,0.0068,0.0075,0.00051,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 +19790000,0.78,-0.016,-0.0031,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.8e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 +19890000,0.78,-0.016,-0.0031,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.4e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 +19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-4.8e-06,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 +20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,-8.7e-08,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20190000,0.78,-0.016,-0.0033,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,5.9e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20290000,0.78,-0.016,-0.0033,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,7.6e-06,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20390000,0.78,-0.016,-0.0033,-0.62,-0.0085,-0.017,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20490000,0.78,-0.016,-0.0033,-0.62,-0.0087,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,9.9e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20590000,0.78,-0.016,-0.0033,-0.62,-0.0082,-0.014,0.014,-0.0085,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.6e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0064,0.007,0.00038,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20690000,0.78,-0.016,-0.0033,-0.62,-0.0089,-0.015,0.015,-0.0094,-0.018,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.6e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0064,0.007,0.00037,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20790000,0.78,-0.016,-0.0034,-0.62,-0.0066,-0.014,0.015,-0.0078,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0063,0.0069,0.00036,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20890000,0.78,-0.016,-0.0034,-0.62,-0.0068,-0.014,0.014,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,2.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.5e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0063,0.0069,0.00035,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +20990000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.012,0.015,-0.008,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0063,0.0069,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +21090000,0.78,-0.016,-0.0034,-0.62,-0.0063,-0.012,0.015,-0.009,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0062,0.0068,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +21190000,0.78,-0.016,-0.0034,-0.62,-0.0064,-0.011,0.014,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.3e-05,0.0001,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00033,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +21290000,0.78,-0.016,-0.0036,-0.62,-0.006,-0.012,0.016,-0.0094,-0.023,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00032,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21390000,0.78,-0.016,-0.0035,-0.62,-0.0054,-0.0074,0.016,-0.0083,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.0061,0.0067,0.00031,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21490000,0.78,-0.016,-0.0035,-0.62,-0.006,-0.0084,0.016,-0.0093,-0.019,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.0061,0.0067,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21590000,0.78,-0.016,-0.0035,-0.62,-0.0046,-0.0067,0.016,-0.0078,-0.015,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.7e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.0061,0.0066,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21690000,0.78,-0.016,-0.0035,-0.62,-0.0062,-0.0078,0.017,-0.009,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.006,0.0066,0.00029,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 +21790000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.0055,0.016,-0.0079,-0.01,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 +21890000,0.78,-0.016,-0.0034,-0.62,-0.0059,-0.0064,0.016,-0.0086,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.6e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 +21990000,0.78,-0.016,-0.0033,-0.62,-0.0057,-0.0036,0.017,-0.008,-0.007,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22090000,0.78,-0.016,-0.0033,-0.62,-0.0054,-0.0052,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22190000,0.78,-0.016,-0.0033,-0.62,-0.0041,-0.0057,0.015,-0.007,-0.0067,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0054,0.016,-0.0077,-0.0071,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22390000,0.78,-0.016,-0.0034,-0.62,-0.0012,-0.0053,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22490000,0.78,-0.016,-0.0034,-0.62,-3.2e-06,-0.006,0.018,-0.0053,-0.0068,-3.7e+02,-0.0014,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22590000,0.78,-0.016,-0.0034,-0.62,0.0018,-0.0049,0.017,-0.0036,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22690000,0.78,-0.016,-0.0034,-0.62,0.0034,-0.0063,0.019,-0.0029,-0.0073,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0027,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22790000,0.78,-0.016,-0.0033,-0.62,0.0044,-0.0055,0.02,-0.0024,-0.0059,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22890000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0065,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0066,0.022,-0.0026,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0063,0.023,-0.0024,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23190000,0.78,-0.016,-0.0033,-0.62,0.0027,-0.0052,0.024,-0.0051,-0.0072,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0057,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23290000,0.78,-0.016,-0.0032,-0.62,0.0023,-0.005,0.025,-0.0054,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23390000,0.78,-0.016,-0.0033,-0.62,-0.001,-0.0047,0.022,-0.0096,-0.0083,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23490000,0.78,-0.013,-0.0054,-0.62,0.0046,-0.0043,-0.011,-0.01,-0.0099,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00021,-0.043,-0.0094,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23690000,0.78,0.0011,-0.0086,-0.62,0.043,0.014,-0.093,-0.007,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23790000,0.78,-0.0026,-0.0061,-0.62,0.064,0.031,-0.15,-0.007,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23890000,0.78,-0.0089,-0.0042,-0.62,0.077,0.043,-0.2,0.00048,-2.4e-05,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23990000,0.78,-0.014,-0.0034,-0.62,0.072,0.043,-0.25,-0.005,-0.0015,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.0019,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +24190000,0.78,-0.01,-0.0054,-0.62,0.07,0.041,-0.35,-0.0059,-0.00031,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +24290000,0.78,-0.0092,-0.0058,-0.62,0.078,0.046,-0.4,0.00062,0.0041,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 +24390000,0.79,-0.0096,-0.0059,-0.62,0.075,0.044,-0.46,-0.012,-0.0023,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 +24490000,0.79,-0.0054,-0.0063,-0.62,0.086,0.051,-0.51,-0.0038,0.0024,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 +24590000,0.79,-0.0019,-0.0064,-0.62,0.09,0.055,-0.56,-0.017,-0.0064,-3.7e+02,-0.0012,-0.0059,6.4e-05,0.067,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.6e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +24690000,0.79,-0.00099,-0.0064,-0.62,0.11,0.071,-0.64,-0.0079,-0.0014,-3.7e+02,-0.0012,-0.0059,7.1e-05,0.068,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.09,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +24790000,0.79,-0.0025,-0.0063,-0.62,0.11,0.08,-0.73,-0.027,-0.0061,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0026,-0.09,-0.068,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.018,0.018,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +24890000,0.79,-0.00064,-0.0078,-0.62,0.13,0.095,-0.75,-0.016,0.0027,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.089,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0058,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +24990000,0.79,0.0011,-0.0095,-0.62,0.13,0.1,-0.81,-0.038,-0.0036,-3.7e+02,-0.0011,-0.0059,4.5e-05,0.071,-0.03,-0.13,-0.11,-0.026,0.5,-0.0024,-0.089,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +25090000,0.79,0.00055,-0.0098,-0.62,0.16,0.12,-0.86,-0.024,0.0078,-3.7e+02,-0.0011,-0.0059,4.3e-05,0.071,-0.03,-0.13,-0.11,-0.027,0.5,-0.0025,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +25190000,0.79,-0.0014,-0.0096,-0.61,0.15,0.11,-0.91,-0.068,-0.014,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0022,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 +25290000,0.79,0.0056,-0.011,-0.62,0.18,0.13,-0.96,-0.052,-0.003,-3.7e+02,-0.0011,-0.0058,2.6e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0023,-0.087,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.0011,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 +25390000,0.79,0.012,-0.011,-0.61,0.18,0.13,-1,-0.1,-0.027,-3.7e+02,-0.001,-0.0058,7.6e-06,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0021,-0.087,-0.07,0,0,-3.7e+02,8.1e-05,8.5e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.001,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 +25490000,0.79,0.013,-0.011,-0.61,0.21,0.16,-1.1,-0.081,-0.014,-3.7e+02,-0.001,-0.0058,1.6e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0024,-0.086,-0.069,0,0,-3.7e+02,8.2e-05,8.5e-05,0.046,0.022,0.022,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.2e-05,0.0012,0.00057,0.0011,0.0011,1,1,0.01 +25590000,0.79,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.058,0.0024,-3.7e+02,-0.001,-0.0058,2.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0027,-0.085,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.1e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01 +25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,3e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,-3.7e+02,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01 +25790000,0.79,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0013,0.041,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.079,-0.03,-0.13,-0.12,-0.028,0.5,-0.0035,-0.083,-0.067,0,0,-3.7e+02,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 +25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.04,0.065,-3.7e+02,-0.00099,-0.0058,5.6e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0041,-0.081,-0.066,0,0,-3.7e+02,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 +25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.5e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0045,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01 +26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.079,-0.031,-0.13,-0.12,-0.029,0.5,-0.0046,-0.079,-0.065,0,0,-3.7e+02,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1,0.01 +26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.031,-0.13,-0.13,-0.03,0.5,-0.0054,-0.075,-0.063,0,0,-3.7e+02,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1,0.01 +26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.8e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,-3.7e+02,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00052,0.00091,0.00099,1,1,0.01 +26390000,0.78,0.041,-0.021,-0.62,0.75,0.51,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,8.5e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0063,-0.071,-0.06,0,0,-3.7e+02,8.8e-05,9e-05,0.041,0.042,0.046,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00084,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1,0.01 +26490000,0.78,0.057,-0.027,-0.63,0.84,0.57,-1.3,0.4,0.3,-3.7e+02,-0.00097,-0.0058,9e-05,0.08,-0.032,-0.13,-0.13,-0.031,0.49,-0.0066,-0.069,-0.058,0,0,-3.7e+02,8.9e-05,9.1e-05,0.039,0.045,0.05,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00081,4.9e-05,0.00093,0.00049,0.00084,0.00093,1,1,0.01 +26590000,0.78,0.074,-0.032,-0.62,0.95,0.65,-1.3,0.49,0.36,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.081,-0.032,-0.13,-0.14,-0.032,0.49,-0.0062,-0.066,-0.057,0,0,-3.7e+02,9e-05,9.1e-05,0.038,0.049,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00076,4.6e-05,0.00088,0.00047,0.0008,0.00088,1,1,0.01 +26690000,0.77,0.077,-0.033,-0.63,1.1,0.72,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,0.0001,0.08,-0.032,-0.13,-0.14,-0.033,0.49,-0.0073,-0.061,-0.052,0,0,-3.7e+02,9.1e-05,9.2e-05,0.035,0.053,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00071,4.3e-05,0.00082,0.00045,0.00074,0.00082,1,1,0.01 +26790000,0.77,0.071,-0.032,-0.63,1.2,0.8,-1.3,0.71,0.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.032,-0.13,-0.14,-0.034,0.48,-0.0071,-0.057,-0.049,0,0,-3.7e+02,9.2e-05,9.3e-05,0.032,0.056,0.067,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0057,0.00014,0.00067,4.1e-05,0.00078,0.00042,0.00069,0.00077,1,1,0.01 +26890000,0.77,0.094,-0.039,-0.63,1.3,0.88,-1.3,0.84,0.58,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.035,0.48,-0.0077,-0.053,-0.047,0,0,-3.7e+02,9.2e-05,9.3e-05,0.03,0.059,0.072,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00063,3.9e-05,0.00073,0.00039,0.00065,0.00073,1,1,0.01 +26990000,0.76,0.12,-0.044,-0.63,1.5,0.99,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.032,-0.13,-0.15,-0.036,0.48,-0.0079,-0.047,-0.043,0,0,-3.7e+02,9.3e-05,9.4e-05,0.027,0.063,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00013,0.00057,3.5e-05,0.00066,0.00035,0.00059,0.00066,1,1,0.01 +27090000,0.76,0.12,-0.045,-0.63,1.7,1.1,-1.3,1.1,0.77,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.037,0.47,-0.0078,-0.043,-0.039,0,0,-3.7e+02,9.3e-05,9.4e-05,0.024,0.067,0.085,0.0061,0.36,0.37,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00052,3.2e-05,0.00059,0.00032,0.00053,0.00059,1,1,0.01 +27190000,0.76,0.11,-0.042,-0.63,1.9,1.2,-1.2,1.3,0.89,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.038,0.47,-0.0074,-0.04,-0.035,0,0,-3.7e+02,9.4e-05,9.5e-05,0.021,0.071,0.091,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00048,3e-05,0.00055,0.00029,0.00049,0.00054,1,1,0.01 +27290000,0.77,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0075,-0.036,-0.033,0,0,-3.7e+02,9.4e-05,9.5e-05,0.019,0.072,0.094,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00045,2.9e-05,0.00052,0.00026,0.00046,0.00051,1,1,0.01 +27390000,0.77,0.078,-0.033,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0074,-0.035,-0.032,0,0,-3.7e+02,9.5e-05,9.6e-05,0.017,0.073,0.094,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00043,2.8e-05,0.0005,0.00023,0.00044,0.00049,1,1,0.01 +27490000,0.77,0.062,-0.029,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0071,-0.034,-0.032,0,0,-3.7e+02,9.6e-05,9.6e-05,0.015,0.074,0.093,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00042,2.7e-05,0.00049,0.00021,0.00043,0.00048,1,1,0.01 +27590000,0.77,0.05,-0.025,-0.63,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.028,-0.13,-0.17,-0.039,0.47,-0.0066,-0.033,-0.031,0,0,-3.7e+02,9.6e-05,9.7e-05,0.014,0.074,0.092,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00041,2.6e-05,0.00048,0.0002,0.00042,0.00048,1,1,0.01 +27690000,0.77,0.048,-0.025,-0.63,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.028,-0.13,-0.17,-0.04,0.47,-0.0062,-0.032,-0.031,0,0,-3.7e+02,9.7e-05,9.7e-05,0.013,0.074,0.09,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.0004,2.6e-05,0.00048,0.00019,0.00042,0.00047,1,1,0.01 +27790000,0.77,0.05,-0.025,-0.63,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,9.7e-05,0.082,-0.027,-0.13,-0.17,-0.04,0.47,-0.0056,-0.032,-0.031,0,0,-3.7e+02,9.8e-05,9.8e-05,0.012,0.074,0.089,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00039,2.6e-05,0.00047,0.00017,0.00041,0.00047,1,1,0.01 +27890000,0.77,0.048,-0.024,-0.63,2.3,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,9.7e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.46,-0.0056,-0.031,-0.031,0,0,-3.7e+02,9.9e-05,9.8e-05,0.011,0.075,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00039,2.5e-05,0.00047,0.00016,0.0004,0.00047,1,1,0.01 +27990000,0.77,0.044,-0.023,-0.63,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.5e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.47,-0.0056,-0.031,-0.031,0,0,-3.7e+02,0.0001,9.9e-05,0.01,0.075,0.088,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.5e-05,0.00047,0.00016,0.0004,0.00046,1,1,0.01 +28090000,0.78,0.058,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,-3.7e+02,0.0001,9.9e-05,0.0096,0.076,0.088,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00038,2.4e-05,0.00046,0.00015,0.00039,0.00046,1,1,0.01 +28190000,0.77,0.071,-0.031,-0.63,2.4,1.7,-0.93,3.5,2.4,-3.7e+02,-0.00095,-0.0058,8.9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,-3.7e+02,0.0001,0.0001,0.0091,0.077,0.088,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00037,2.4e-05,0.00046,0.00014,0.00038,0.00045,1,1,0.01 +28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.5e-05,0.083,-0.024,-0.13,-0.17,-0.04,0.46,-0.0048,-0.029,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1,0.01 +28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,8e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0082,0.077,0.084,0.0061,0.75,0.79,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 +28490000,0.78,0.0015,-0.0059,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.5e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 +28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.083,-0.022,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 +28690000,0.78,-0.0032,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,7e-05,0.082,-0.022,-0.12,-0.17,-0.041,0.46,-0.0044,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 +28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.5e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1,0.01 +28890000,0.78,-0.0033,-0.0037,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6.1e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0041,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1,0.01 +28990000,0.78,-0.0028,-0.0039,-0.62,2.1,1.5,0.98,5.4,3.8,-3.7e+02,-0.001,-0.0058,5.5e-05,0.081,-0.02,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 +29090000,0.78,-0.0024,-0.004,-0.62,2,1.5,0.97,5.6,4,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0037,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0063,0.081,0.085,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 +29190000,0.78,-0.0021,-0.0041,-0.62,2,1.5,0.97,5.8,4.1,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0061,0.083,0.087,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 +29290000,0.78,-0.0013,-0.0044,-0.62,1.9,1.5,0.99,6,4.2,-3.7e+02,-0.001,-0.0058,4.6e-05,0.08,-0.019,-0.12,-0.17,-0.041,0.46,-0.0036,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.00011,0.00037,0.00043,1,1,0.01 +29390000,0.78,9e-05,-0.0046,-0.62,1.9,1.4,1,6.2,4.4,-3.7e+02,-0.001,-0.0058,3.9e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 +29490000,0.78,0.0013,-0.005,-0.62,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.7e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 +29590000,0.78,0.0023,-0.0052,-0.62,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0057,3.4e-05,0.079,-0.017,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 +29690000,0.78,0.003,-0.0055,-0.62,1.7,1.4,0.99,6.7,4.8,-3.7e+02,-0.001,-0.0057,2.9e-05,0.079,-0.016,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.9e-05,0.00037,0.00043,1,1,0.01 +29790000,0.78,0.0034,-0.0056,-0.62,1.7,1.4,0.98,6.9,5,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.015,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.027,0,0,-3.7e+02,0.00011,0.0001,0.0054,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.8e-05,0.00037,0.00042,1,1,0.01 +29890000,0.78,0.0036,-0.0057,-0.62,1.7,1.3,0.97,7.1,5.1,-3.7e+02,-0.001,-0.0057,2e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.7e-05,0.00037,0.00042,1,1,0.01 +29990000,0.78,0.0036,-0.0057,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1,0.01 +30090000,0.78,0.0035,-0.0057,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1.2e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1,0.01 +30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.3e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1,0.01 +30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,1e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01 +30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,5.9e-06,0.077,-0.012,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.11,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 +30490000,0.78,0.0025,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,4.8e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 +30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,2.7e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01 +30690000,0.78,0.0017,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-6.4e-07,0.076,-0.0098,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 +30790000,0.78,0.0013,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-3.8e-06,0.076,-0.0096,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 +30890000,0.78,0.00091,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-6.7e-06,0.075,-0.0088,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01 +30990000,0.78,0.00032,-0.005,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1e-05,0.075,-0.008,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1,0.01 +31090000,0.78,-0.00023,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.5e-05,0.074,-0.0073,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 +31190000,0.78,-0.00064,-0.0047,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0064,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 +31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2e-05,0.074,-0.0057,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 +31390000,0.78,-0.002,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.074,-0.0051,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 +31490000,0.78,-0.0026,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-2.9e-05,0.073,-0.0044,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 +31590000,0.78,-0.0029,-0.0042,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3e-05,0.073,-0.0037,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1,0.01 +31690000,0.78,-0.0037,-0.004,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.072,-0.003,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31790000,0.78,-0.0044,-0.0038,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.4e-05,0.072,-0.0021,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31890000,0.78,-0.0051,-0.0037,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-3.8e-05,0.071,-0.0012,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.071,-0.00029,-0.12,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1,0.01 +32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.95,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-4.7e-05,0.07,0.00041,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-5.7e-05,0.07,0.0014,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.1e-05,0.069,0.0024,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.1e-05,0.069,0.003,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32490000,0.78,-0.009,-0.0029,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.068,0.0038,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 +32590000,0.78,-0.0093,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0041,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 +32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.067,0.0047,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 +32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.067,0.0051,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 +32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.066,0.0056,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 +32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0062,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 +33090000,0.79,-0.0092,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0064,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 +33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.065,0.0065,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1,0.01 +33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.065,0.0064,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1,0.01 +33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.064,0.006,-0.11,-0.18,-0.041,0.46,-0.0009,-0.027,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8e-05,0.00032,0.00039,1,1,0.01 +33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.3e-05,0.064,0.0061,-0.11,-0.18,-0.043,0.46,-0.0004,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01 +33590000,0.99,-0.0083,-0.00011,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.8e-05,0.064,0.0061,-0.11,-0.19,-0.044,0.46,0.00035,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01 +33690000,1,-0.012,0.0041,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.064,0.0061,-0.11,-0.19,-0.045,0.46,0.00018,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01 +33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00053,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01 +33890000,0.93,-0.013,0.0086,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.1e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00075,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01 +33990000,0.86,-0.015,0.0072,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0058,-0.11,-0.2,-0.046,0.46,0.00053,-0.0039,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1,0.01 +34090000,0.8,-0.016,0.0064,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0052,-0.11,-0.2,-0.046,0.46,0.0002,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01 +34190000,0.75,-0.014,0.0071,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01 +34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0047,-0.11,-0.2,-0.047,0.46,0.00016,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01 +34390000,0.69,-0.0077,0.01,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0044,-0.11,-0.2,-0.047,0.46,9.4e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01 +34490000,0.67,-0.0055,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0043,-0.11,-0.2,-0.047,0.46,5.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01 +34590000,0.66,-0.0041,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0042,-0.11,-0.2,-0.047,0.46,-4.5e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01 +34690000,0.65,-0.0033,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0042,-0.11,-0.2,-0.047,0.46,1.8e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01 +34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0041,-0.11,-0.2,-0.047,0.46,0.00014,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1,0.01 +34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0039,-0.11,-0.2,-0.047,0.46,8.8e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01 +34990000,0.64,-0.0061,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1,0.01 +35090000,0.64,-0.0062,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00022,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1,0.01 +35190000,0.64,-0.0063,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00026,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01 +35290000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0003,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01 +35390000,0.64,-0.0064,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00038,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01 +35490000,0.64,-0.0065,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00045,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01 +35590000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00042,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 +35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 +35790000,0.64,-0.0065,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 +35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 +35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 +36090000,0.64,-0.0066,0.02,0.77,-3.4,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 +36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 +36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 +36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 +36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00055,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 +36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 +36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00061,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 +36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00064,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 +36890000,0.64,-0.0069,0.021,0.77,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0041,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 +36990000,0.64,-0.0069,0.021,0.77,-3.7,-4.1,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0042,-0.11,-0.2,-0.047,0.46,0.00069,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 +37090000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0064,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.44 +37190000,0.64,-0.0069,0.021,0.77,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 +37290000,0.64,-0.0069,0.021,0.77,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.7e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 +37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.017,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00071,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 +37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 +37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.067,0.0045,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 +37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 +37790000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 +37890000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0046,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 +37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 +38090000,0.64,-0.0071,0.021,0.77,-4,-4.9,0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 +38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00079,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 +38290000,0.64,-0.0071,0.021,0.77,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00079,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 +38390000,0.64,-0.007,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 +38490000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 +38590000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 +38690000,0.64,-0.007,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0065,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 +38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0046,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 +38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index c5ad1dd6f49a..af5d55ea1550 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -1,351 +1,351 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,4.9e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.6e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.5e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.7e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.5e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2490000,1,-0.011,-0.014,0.00048,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.5e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-2.1e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2790000,1,-0.01,-0.013,0.00038,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -2990000,1,-0.01,-0.013,0.00032,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-3.1e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-3.1e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3190000,1,-0.01,-0.013,0.00057,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.5e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3490000,1,-0.0097,-0.013,0.00059,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3690000,1,-0.0095,-0.013,0.00053,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.8e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3890000,1,-0.0094,-0.013,0.00064,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4090000,1,-0.0093,-0.012,0.00077,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-5.2e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-5.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4290000,1,-0.0095,-0.012,0.00075,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.7e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.7e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4490000,1,-0.0094,-0.012,0.00077,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-6.2e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-6.2e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4690000,1,-0.0094,-0.012,0.00077,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4790000,1,-0.0093,-0.012,0.00087,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4890000,1,-0.0092,-0.012,0.00091,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-7e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-7e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5090000,1,-0.0091,-0.011,0.00097,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-7.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5690000,1,-0.0089,-0.011,0.0009,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5790000,1,-0.0088,-0.011,0.00086,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5890000,1,-0.0088,-0.011,0.00089,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -5990000,1,-0.0088,-0.012,0.00087,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6090000,1,-0.0088,-0.011,0.00068,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6190000,1,-0.0089,-0.011,0.00069,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6290000,1,-0.0089,-0.011,0.00072,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6390000,1,-0.0089,-0.011,0.00073,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6490000,1,-0.0089,-0.011,0.00063,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.8e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6590000,1,-0.009,-0.011,0.00056,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 -6690000,1,-0.0089,-0.011,0.00052,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,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 -6790000,1,-0.009,-0.011,0.00048,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-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 -6890000,1,-0.0088,-0.011,0.0004,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-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 -6990000,-0.29,0.024,-0.0061,0.96,-0.2,-0.033,-0.037,-0.11,-0.019,-0.055,-0.00071,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1 -7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.049,-0.038,-0.15,-0.027,-0.056,-0.00058,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1 -7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.00054,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1 -7290000,-0.29,0.025,-0.0063,0.96,-0.28,-0.066,-0.034,-0.2,-0.04,-0.055,-0.00053,-0.01,-0.00021,-0.00088,-0.00019,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1 -7390000,-0.29,0.025,-0.0063,0.96,-0.3,-0.072,-0.032,-0.23,-0.048,-0.052,-0.00052,-0.01,-0.00021,-0.0011,-0.00023,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00014,0.0013,0.0013,0.00086,0.0013,1,1 -7490000,-0.29,0.024,-0.0063,0.96,-0.32,-0.08,-0.026,-0.25,-0.056,-0.046,-0.00051,-0.0099,-0.00021,-0.0015,-0.00027,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1 -7590000,-0.29,0.024,-0.0065,0.96,-0.34,-0.087,-0.022,-0.28,-0.065,-0.041,-0.00049,-0.0098,-0.00021,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1 -7690000,-0.29,0.024,-0.0065,0.96,-0.35,-0.096,-0.022,-0.31,-0.076,-0.036,-0.00047,-0.0097,-0.00021,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1 -7790000,-0.29,0.023,-0.0063,0.96,-0.36,-0.11,-0.024,-0.34,-0.09,-0.041,-0.0004,-0.0096,-0.00021,-0.0017,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1 -7890000,-0.29,0.023,-0.0063,0.96,-0.37,-0.11,-0.025,-0.37,-0.1,-0.045,-0.00038,-0.0095,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00086,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.0001,0.0013,0.0013,0.00083,0.0013,1,1 -7990000,-0.29,0.023,-0.0064,0.96,-0.39,-0.12,-0.021,-0.4,-0.11,-0.041,-0.00041,-0.0094,-0.0002,-0.0016,-0.00019,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.8e-05,0.0013,0.0012,0.00083,0.0013,1,1 -8090000,-0.29,0.023,-0.0062,0.96,-0.41,-0.13,-0.022,-0.43,-0.13,-0.044,-0.00034,-0.0094,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.0008,0.00083,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,9.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 -8190000,-0.29,0.022,-0.0063,0.96,-0.41,-0.14,-0.017,-0.46,-0.15,-0.038,-0.00028,-0.0092,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00078,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.4e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8290000,-0.29,0.022,-0.0064,0.96,-0.44,-0.15,-0.016,-0.51,-0.16,-0.038,-0.00033,-0.0093,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00075,0.00078,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.2e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8390000,-0.29,0.022,-0.0065,0.96,-0.45,-0.15,-0.015,-0.55,-0.17,-0.036,-0.00034,-0.0092,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0012,9e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8490000,-0.29,0.022,-0.0065,0.96,-0.46,-0.15,-0.016,-0.58,-0.18,-0.041,-0.00043,-0.0091,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.00071,0.00073,0.053,0.82,0.81,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.9e-05,0.0013,0.0012,0.00082,0.0013,1,1 -8590000,-0.29,0.022,-0.0063,0.96,-0.45,-0.16,-0.012,-0.6,-0.2,-0.036,-0.00037,-0.0089,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00069,0.00071,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.7e-05,0.0013,0.0012,0.00081,0.0013,1,1 -8690000,-0.29,0.021,-0.0064,0.96,-0.46,-0.16,-0.014,-0.64,-0.21,-0.037,-0.00042,-0.0088,-0.00019,-0.0016,-7.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00067,0.00069,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,8.6e-05,0.0013,0.0012,0.00081,0.0013,1,1 -8790000,-0.29,0.021,-0.0065,0.96,-0.48,-0.16,-0.013,-0.67,-0.23,-0.035,-0.00041,-0.0088,-0.00019,-0.0016,-6.7e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00065,0.00067,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,8.5e-05,0.0013,0.0012,0.00081,0.0013,1,1 -8890000,-0.29,0.021,-0.0064,0.96,-0.47,-0.16,-0.0093,-0.68,-0.24,-0.029,-0.00046,-0.0085,-0.00018,-0.0016,4.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.00063,0.00065,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,8.4e-05,0.0013,0.0012,0.0008,0.0013,1,1 -8990000,-0.29,0.02,-0.0063,0.96,-0.45,-0.17,-0.0088,-0.68,-0.25,-0.032,-0.0005,-0.0082,-0.00017,-0.0013,0.00015,-0.13,-0.1,-0.024,0.5,0.08,-0.032,-0.069,0,0,0.00062,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,8.3e-05,0.0013,0.0012,0.0008,0.0013,1,1 -9090000,-0.29,0.02,-0.0064,0.96,-0.46,-0.16,-0.0099,-0.72,-0.23,-0.032,-0.00067,-0.0082,-0.00016,-0.0012,0.00032,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1 -9190000,-0.29,0.02,-0.0064,0.96,-0.46,-0.15,-0.0095,-0.74,-0.23,-0.033,-0.00077,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9290000,-0.29,0.02,-0.0061,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00077,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9390000,-0.29,0.02,-0.0059,0.96,-0.45,-0.17,-0.007,-0.75,-0.28,-0.031,-0.00069,-0.0077,-0.00015,-0.00085,0.00049,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9490000,-0.29,0.019,-0.006,0.96,-0.46,-0.17,-0.0055,-0.78,-0.28,-0.028,-0.00077,-0.0076,-0.00015,-0.00093,0.00058,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1 -9590000,-0.29,0.019,-0.006,0.96,-0.47,-0.19,-0.0054,-0.82,-0.33,-0.029,-0.00064,-0.0075,-0.00015,-0.00087,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9690000,-0.29,0.019,-0.0059,0.96,-0.47,-0.2,-0.0026,-0.83,-0.36,-0.028,-0.0006,-0.0074,-0.00015,-0.00078,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9790000,-0.29,0.019,-0.0059,0.96,-0.48,-0.21,-0.0039,-0.88,-0.4,-0.029,-0.00052,-0.0074,-0.00015,-0.00077,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9890000,-0.29,0.019,-0.0058,0.96,-0.47,-0.21,-0.0027,-0.88,-0.42,-0.03,-0.00055,-0.0072,-0.00014,-0.00053,0.00044,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1 -9990000,-0.29,0.019,-0.0058,0.96,-0.49,-0.22,-0.002,-0.93,-0.46,-0.032,-0.00049,-0.0072,-0.00015,-0.00044,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10090000,-0.29,0.019,-0.0057,0.96,-0.49,-0.24,-0.00079,-0.96,-0.51,-0.03,-0.00039,-0.0071,-0.00015,-0.00045,0.0003,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10190000,-0.29,0.019,-0.0057,0.96,-0.49,-0.26,4.4e-05,-0.97,-0.58,-0.031,-0.00025,-0.007,-0.00015,-0.00028,0.00017,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10290000,-0.29,0.019,-0.0056,0.96,-0.49,-0.26,-0.0011,-0.98,-0.59,-0.03,-0.00032,-0.0069,-0.00014,-0.00016,0.00024,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10390000,-0.29,0.019,-0.0055,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00015,-0.029,-0.00036,-0.0067,-0.00014,-6.4e-06,0.0003,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1 -10490000,-0.29,0.019,-0.0055,0.96,-0.01,-0.0087,0.0071,0.00024,-0.00081,-0.024,-0.00029,-0.0067,-0.00014,-0.00015,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10590000,-0.29,0.019,-0.0054,0.96,-0.021,-0.0074,0.013,-0.0011,-0.00057,-0.022,-0.00039,-0.0066,-0.00013,0.0001,0.0006,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10690000,-0.29,0.019,-0.0053,0.96,-0.034,-0.01,0.016,-0.0038,-0.0015,-0.018,-0.00037,-0.0065,-0.00013,0.00013,0.00058,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10790000,-0.29,0.019,-0.0052,0.96,-0.034,-0.014,0.014,0.00012,-0.0018,-0.016,-0.0004,-0.0064,-0.00013,0.002,5.7e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10890000,-0.29,0.019,-0.0051,0.96,-0.043,-0.019,0.01,-0.0037,-0.0034,-0.019,-0.00052,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1 -10990000,-0.29,0.019,-0.0051,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00056,-0.0064,-0.00012,0.0058,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11090000,-0.29,0.019,-0.0052,0.96,-0.051,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00045,-0.0063,-0.00013,0.006,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11190000,-0.29,0.018,-0.0053,0.96,-0.041,-0.026,0.027,-0.0021,-0.0027,-0.0011,-0.00045,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11290000,-0.29,0.018,-0.0053,0.96,-0.05,-0.027,0.026,-0.0066,-0.0053,-0.00072,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1 -11390000,-0.29,0.018,-0.0052,0.96,-0.043,-0.024,0.017,-0.0037,-0.0034,-0.0091,-0.00052,-0.0063,-0.00013,0.019,0.0029,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00037,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11490000,-0.29,0.018,-0.0051,0.96,-0.05,-0.026,0.021,-0.0082,-0.006,-0.003,-0.00053,-0.0062,-0.00012,0.019,0.003,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00037,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11590000,-0.29,0.018,-0.0052,0.96,-0.045,-0.021,0.019,-0.005,-0.0039,-0.004,-0.00057,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11690000,-0.29,0.017,-0.0052,0.96,-0.051,-0.026,0.019,-0.0097,-0.0062,-0.0053,-0.00061,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.087,0.087,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1 -11790000,-0.29,0.017,-0.0051,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.0007,-0.0063,-0.00012,0.03,0.0046,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 -11890000,-0.29,0.017,-0.0053,0.96,-0.049,-0.028,0.018,-0.01,-0.008,-0.0016,-0.00069,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 -11990000,-0.29,0.017,-0.0053,0.96,-0.039,-0.021,0.015,-0.0064,-0.0053,-0.0052,-0.00072,-0.0063,-0.00012,0.037,0.0066,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 -12090000,-0.29,0.017,-0.0052,0.96,-0.045,-0.022,0.018,-0.011,-0.0076,0.00088,-0.0007,-0.0062,-0.00012,0.037,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1 -12190000,-0.29,0.017,-0.0052,0.96,-0.038,-0.013,0.017,-0.0054,-0.0029,0.0028,-0.00066,-0.0062,-0.00012,0.043,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12290000,-0.29,0.017,-0.0053,0.96,-0.04,-0.012,0.016,-0.0094,-0.0041,0.0038,-0.00063,-0.0062,-0.00012,0.043,0.0085,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12390000,-0.29,0.016,-0.0053,0.96,-0.033,-0.0087,0.014,-0.0051,-0.0027,-0.0022,-0.00063,-0.0062,-0.00012,0.047,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12490000,-0.29,0.016,-0.0053,0.96,-0.036,-0.0097,0.018,-0.0087,-0.0037,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12590000,-0.29,0.016,-0.0052,0.96,-0.03,-0.0084,0.02,-0.0035,-0.0039,0.0017,-0.00061,-0.0061,-0.00012,0.05,0.0078,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12690000,-0.29,0.016,-0.0052,0.96,-0.033,-0.0065,0.019,-0.0066,-0.0047,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1 -12790000,-0.29,0.016,-0.005,0.96,-0.023,-0.012,0.02,-0.0016,-0.0077,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.4e-06,7e-06,2.2e-06,0.0093,0.0096,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1 -12890000,-0.29,0.016,-0.005,0.96,-0.025,-0.013,0.021,-0.004,-0.009,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0073,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1 -12990000,-0.29,0.016,-0.005,0.96,-0.021,-0.0099,0.022,-0.0012,-0.0063,0.0096,-0.00075,-0.0061,-0.00012,0.054,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0083,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1 -13090000,-0.29,0.016,-0.0049,0.96,-0.023,-0.011,0.019,-0.0033,-0.0076,0.0084,-0.00079,-0.006,-0.00011,0.054,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1 -13190000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.018,-0.0017,-0.0086,0.009,-0.00082,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0072,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1 -13290000,-0.29,0.016,-0.0049,0.96,-0.021,-0.011,0.016,-0.0038,-0.0099,0.0084,-0.00081,-0.006,-0.00011,0.056,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13390000,-0.29,0.016,-0.0049,0.96,-0.017,-0.0083,0.015,-0.0014,-0.0068,0.009,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.0001,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13490000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.015,-0.0032,-0.0079,0.0051,-0.00079,-0.006,-0.00011,0.057,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.0001,0.0001,0.051,0.053,0.053,0.009,0.067,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13590000,-0.29,0.016,-0.0049,0.96,-0.014,-0.0075,0.016,0.0017,-0.0056,0.0036,-0.00077,-0.006,-0.00011,0.059,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,9.3e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0059,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1 -13690000,-0.29,0.016,-0.0048,0.96,-0.015,-0.0066,0.016,0.00026,-0.0063,0.0062,-0.00079,-0.0059,-0.00011,0.059,0.0093,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,9.4e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -13790000,-0.29,0.015,-0.0048,0.96,-0.011,-0.0047,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.061,0.0092,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,8.7e-05,8.7e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -13890000,-0.29,0.015,-0.0047,0.96,-0.012,-0.0058,0.017,0.0044,-0.0039,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0093,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,8.8e-05,8.8e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -13990000,-0.29,0.015,-0.0047,0.96,-0.014,-0.0096,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0097,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,8.3e-05,8.3e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0047,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14090000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0037,0.017,0.0022,-0.0049,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14190000,-0.29,0.015,-0.0048,0.96,-0.01,-0.0025,0.017,0.0035,-0.0039,0.0033,-0.00073,-0.006,-0.00011,0.063,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0046,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14290000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0029,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.063,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,8.1e-05,8e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14390000,-0.29,0.015,-0.0048,0.96,-0.012,-0.0025,0.017,0.0036,-0.0047,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0043,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14490000,-0.29,0.015,-0.005,0.96,-0.012,-0.0018,0.02,0.0022,-0.0047,0.014,-0.00071,-0.0059,-0.00012,0.064,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.8e-05,7.7e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14590000,-0.29,0.015,-0.005,0.96,-0.015,-0.0035,0.018,0.00068,-0.0052,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.5e-05,7.4e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0038,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14690000,-0.29,0.015,-0.005,0.96,-0.016,-0.0038,0.018,-0.00092,-0.0057,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14790000,-0.29,0.015,-0.0051,0.96,-0.019,-0.0012,0.018,-0.00061,-0.0012,0.013,-0.00072,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.0007,0.022,-0.0027,-0.0016,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -14990000,-0.29,0.015,-0.005,0.96,-0.02,-0.0013,0.025,-0.0022,-0.0028,0.016,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -15090000,-0.29,0.016,-0.0049,0.96,-0.021,-0.0024,0.029,-0.0043,-0.0029,0.018,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00056,0.029,-0.0034,-0.0023,0.02,-0.00073,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1 -15290000,-0.29,0.016,-0.0051,0.96,-0.024,-0.00067,0.029,-0.0059,-0.0028,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15390000,-0.29,0.016,-0.0052,0.96,-0.023,-0.0026,0.028,-0.0046,-0.0023,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15490000,-0.29,0.016,-0.0052,0.96,-0.025,-0.00012,0.028,-0.007,-0.0025,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0045,0.028,-0.0033,-0.0057,0.017,-0.00078,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15690000,-0.29,0.016,-0.0051,0.96,-0.024,-0.0024,0.028,-0.0049,-0.0061,0.018,-0.00083,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15790000,-0.29,0.015,-0.0051,0.96,-0.021,-0.0012,0.028,-0.0035,-0.0052,0.019,-0.00087,-0.0058,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15890000,-0.29,0.016,-0.0052,0.96,-0.021,-0.0024,0.029,-0.0059,-0.0052,0.019,-0.00084,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0019,0.026,-0.0049,-0.0044,0.018,-0.00083,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00065,0.024,-0.0072,-0.0044,0.018,-0.00082,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00046,0.023,-0.0071,-0.0036,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16290000,-0.29,0.016,-0.0051,0.96,-0.022,0.00049,0.022,-0.0091,-0.0037,0.017,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16390000,-0.29,0.016,-0.005,0.96,-0.023,-6.6e-05,0.023,-0.007,-0.0036,0.017,-0.00082,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16490000,-0.29,0.016,-0.0051,0.96,-0.027,0.0009,0.025,-0.0098,-0.0035,0.021,-0.00081,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16590000,-0.29,0.016,-0.0051,0.96,-0.031,0.0013,0.029,-0.0085,-0.003,0.021,-0.00082,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16690000,-0.29,0.015,-0.0051,0.96,-0.034,0.0049,0.029,-0.011,-0.0028,0.021,-0.00084,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16790000,-0.29,0.015,-0.005,0.96,-0.035,0.0046,0.028,-0.0096,-0.0025,0.021,-0.00086,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0028,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16890000,-0.29,0.015,-0.0049,0.96,-0.035,0.0041,0.029,-0.013,-0.0025,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6.1e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -16990000,-0.29,0.015,-0.005,0.96,-0.032,0.0045,0.029,-0.011,-0.0027,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17090000,-0.29,0.015,-0.0051,0.96,-0.037,0.0065,0.028,-0.015,-0.0022,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17190000,-0.29,0.015,-0.0052,0.96,-0.036,0.0083,0.03,-0.014,-0.0038,0.021,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17290000,-0.29,0.015,-0.0052,0.96,-0.039,0.009,0.03,-0.018,-0.0026,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17390000,-0.29,0.015,-0.0051,0.96,-0.029,0.014,0.029,-0.01,-0.0013,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17490000,-0.29,0.015,-0.0052,0.96,-0.029,0.015,0.029,-0.013,0.00029,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17590000,-0.29,0.015,-0.0052,0.96,-0.029,0.013,0.028,-0.012,-0.00011,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17690000,-0.29,0.015,-0.0052,0.96,-0.03,0.014,0.029,-0.016,0.001,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17790000,-0.29,0.015,-0.0053,0.96,-0.031,0.014,0.029,-0.015,0.0018,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0026,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17890000,-0.29,0.015,-0.0052,0.96,-0.035,0.015,0.029,-0.017,0.003,0.032,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1 -17990000,-0.29,0.015,-0.0052,0.96,-0.034,0.016,0.029,-0.014,0.0053,0.033,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18090000,-0.29,0.015,-0.0052,0.96,-0.036,0.017,0.028,-0.018,0.0068,0.031,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18190000,-0.29,0.015,-0.0052,0.96,-0.032,0.014,0.028,-0.013,0.0046,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18290000,-0.29,0.015,-0.0052,0.96,-0.036,0.014,0.027,-0.017,0.0057,0.028,-0.00098,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18390000,-0.29,0.015,-0.0051,0.96,-0.032,0.014,0.027,-0.012,0.0048,0.027,-0.00099,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18490000,-0.29,0.015,-0.0051,0.96,-0.036,0.013,0.026,-0.015,0.0057,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0025,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18590000,-0.29,0.015,-0.005,0.96,-0.034,0.013,0.026,-0.013,0.0051,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18690000,-0.29,0.015,-0.005,0.96,-0.034,0.012,0.025,-0.015,0.006,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18790000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.024,-0.012,0.0052,0.028,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18890000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.022,-0.015,0.0065,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -18990000,-0.29,0.015,-0.0049,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19090000,-0.29,0.015,-0.0049,0.96,-0.028,0.013,0.024,-0.016,0.0064,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19190000,-0.29,0.015,-0.0049,0.96,-0.026,0.014,0.023,-0.014,0.0063,0.023,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19390000,-0.29,0.015,-0.005,0.96,-0.026,0.012,0.025,-0.015,0.0074,0.021,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19690000,-0.29,0.015,-0.0049,0.96,-0.025,0.013,0.025,-0.018,0.0078,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19790000,-0.29,0.015,-0.005,0.96,-0.022,0.013,0.023,-0.018,0.0085,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19890000,-0.29,0.015,-0.005,0.96,-0.023,0.013,0.023,-0.02,0.0098,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -19990000,-0.29,0.015,-0.005,0.96,-0.02,0.014,0.021,-0.016,0.009,0.012,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20090000,-0.29,0.015,-0.005,0.96,-0.023,0.016,0.021,-0.018,0.01,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20190000,-0.29,0.015,-0.005,0.96,-0.024,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20290000,-0.29,0.015,-0.005,0.96,-0.022,0.016,0.022,-0.021,0.012,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20390000,-0.29,0.015,-0.005,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1 -20490000,-0.29,0.015,-0.005,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.3e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20590000,-0.29,0.015,-0.0049,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.2e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20690000,-0.29,0.015,-0.0048,0.96,-0.017,0.016,0.023,-0.025,0.014,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20790000,-0.29,0.015,-0.0042,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20890000,-0.29,0.01,0.0044,0.96,-0.0063,0.0016,-0.11,-0.021,0.011,0.0066,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1 -20990000,-0.29,0.0063,0.0074,0.96,0.0088,-0.015,-0.25,-0.017,0.0081,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.2e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21090000,-0.29,0.0069,0.0058,0.96,0.023,-0.028,-0.37,-0.015,0.0062,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21190000,-0.29,0.0088,0.0033,0.96,0.029,-0.033,-0.5,-0.013,0.0046,-0.075,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.8e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21290000,-0.29,0.01,0.0012,0.96,0.027,-0.036,-0.63,-0.01,0.002,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21390000,-0.29,0.011,-0.00024,0.96,0.021,-0.029,-0.75,-0.012,0.0052,-0.2,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21490000,-0.29,0.012,-0.00099,0.96,0.014,-0.028,-0.89,-0.0097,0.0021,-0.28,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21590000,-0.29,0.012,-0.0015,0.96,0.0028,-0.022,-1,-0.014,0.0068,-0.37,-0.0011,-0.0058,-0.00012,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.002,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21690000,-0.29,0.012,-0.0018,0.96,-0.0025,-0.019,-1.1,-0.014,0.004,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21790000,-0.29,0.012,-0.0022,0.96,-0.0083,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0072,-1.4,-0.016,0.0097,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.001,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22090000,-0.29,0.013,-0.0039,0.96,-0.023,0.0043,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22190000,-0.29,0.013,-0.0043,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22290000,-0.29,0.014,-0.005,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22390000,-0.29,0.014,-0.0053,0.96,-0.045,0.022,-1.4,-0.038,0.029,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22490000,-0.29,0.015,-0.0054,0.96,-0.052,0.028,-1.4,-0.043,0.032,-1.6,-0.001,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22590000,-0.29,0.015,-0.0052,0.96,-0.057,0.034,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22690000,-0.29,0.015,-0.0052,0.96,-0.062,0.039,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1 -22790000,-0.29,0.016,-0.0051,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1 -22890000,-0.29,0.016,-0.0052,0.96,-0.073,0.048,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1 -22990000,-0.29,0.016,-0.005,0.96,-0.076,0.048,-1.4,-0.065,0.045,-2.3,-0.0011,-0.0058,-7e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23090000,-0.29,0.017,-0.005,0.96,-0.082,0.052,-1.4,-0.072,0.05,-2.5,-0.0011,-0.0058,-6.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23190000,-0.29,0.017,-0.0049,0.96,-0.084,0.047,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.1e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23290000,-0.29,0.017,-0.0054,0.96,-0.09,0.051,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23390000,-0.29,0.017,-0.0053,0.96,-0.09,0.054,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.8e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23490000,-0.29,0.017,-0.0053,0.96,-0.096,0.054,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23590000,-0.29,0.017,-0.0055,0.96,-0.095,0.048,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23690000,-0.29,0.018,-0.006,0.96,-0.094,0.051,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.2e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23790000,-0.29,0.021,-0.0075,0.96,-0.079,0.048,-0.95,-0.08,0.047,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23890000,-0.29,0.025,-0.01,0.96,-0.074,0.051,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -23990000,-0.29,0.028,-0.012,0.96,-0.065,0.05,-0.13,-0.074,0.046,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24090000,-0.29,0.027,-0.012,0.96,-0.072,0.058,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.7e-05,0.0012,0.0011,0.00066,0.0012,1,1 -24190000,-0.29,0.023,-0.0092,0.96,-0.076,0.055,0.088,-0.066,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24290000,-0.29,0.019,-0.0072,0.96,-0.08,0.057,0.066,-0.074,0.044,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24390000,-0.29,0.018,-0.0064,0.96,-0.064,0.05,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24490000,-0.29,0.018,-0.0066,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24590000,-0.29,0.018,-0.0072,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24690000,-0.29,0.018,-0.0077,0.96,-0.045,0.044,0.075,-0.046,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24790000,-0.29,0.017,-0.0078,0.96,-0.039,0.042,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24890000,-0.29,0.017,-0.0077,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25090000,-0.29,0.016,-0.0078,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25190000,-0.29,0.016,-0.008,0.96,-0.011,0.042,0.047,-0.0079,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25290000,-0.3,0.016,-0.0082,0.96,-0.006,0.045,0.042,-0.0086,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25390000,-0.3,0.015,-0.0083,0.96,0.003,0.043,0.04,0.0014,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25490000,-0.3,0.015,-0.0084,0.96,0.0074,0.044,0.04,0.0011,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25590000,-0.3,0.015,-0.0085,0.96,0.012,0.04,0.041,0.0086,0.0097,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25690000,-0.3,0.014,-0.008,0.96,0.013,0.039,0.03,0.0099,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25790000,-0.3,0.014,-0.0078,0.96,0.024,0.034,0.03,0.017,0.0035,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25890000,-0.3,0.014,-0.0079,0.96,0.03,0.034,0.033,0.02,0.0078,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -25990000,-0.3,0.014,-0.0079,0.96,0.032,0.029,0.026,0.017,-0.0034,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26090000,-0.3,0.014,-0.0076,0.96,0.037,0.029,0.025,0.021,-0.0013,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26190000,-0.3,0.014,-0.0074,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26290000,-0.3,0.015,-0.0074,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26390000,-0.3,0.015,-0.0068,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26490000,-0.3,0.015,-0.0066,0.96,0.043,0.0087,0.028,0.023,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26590000,-0.3,0.015,-0.006,0.96,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26690000,-0.3,0.015,-0.0059,0.96,0.044,-0.0049,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26790000,-0.3,0.014,-0.0057,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -26990000,-0.3,0.015,-0.0045,0.96,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27090000,-0.3,0.015,-0.0043,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 -27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27290000,-0.3,0.016,-0.0044,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27390000,-0.3,0.018,-0.0056,0.96,0.067,-0.026,0.46,0.007,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27490000,-0.3,0.02,-0.0067,0.95,0.072,-0.028,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27590000,-0.3,0.019,-0.0067,0.96,0.063,-0.03,0.87,0.0077,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27690000,-0.3,0.016,-0.0058,0.96,0.058,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27790000,-0.3,0.015,-0.0047,0.96,0.054,-0.026,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27890000,-0.3,0.015,-0.0043,0.96,0.061,-0.031,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -27990000,-0.3,0.015,-0.0047,0.96,0.061,-0.034,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28090000,-0.3,0.015,-0.005,0.96,0.065,-0.034,0.8,0.026,-0.027,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28190000,-0.3,0.015,-0.0044,0.96,0.062,-0.033,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28290000,-0.3,0.016,-0.0038,0.96,0.066,-0.036,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28390000,-0.3,0.016,-0.0038,0.96,0.068,-0.038,0.81,0.035,-0.034,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28490000,-0.3,0.017,-0.004,0.96,0.07,-0.041,0.81,0.043,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28590000,-0.29,0.017,-0.004,0.96,0.063,-0.042,0.81,0.043,-0.041,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28690000,-0.29,0.016,-0.0039,0.96,0.062,-0.043,0.81,0.049,-0.045,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28790000,-0.29,0.016,-0.0032,0.96,0.06,-0.042,0.81,0.05,-0.044,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28890000,-0.29,0.015,-0.0031,0.96,0.064,-0.044,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -28990000,-0.29,0.016,-0.0028,0.96,0.062,-0.042,0.81,0.058,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29090000,-0.29,0.016,-0.0027,0.96,0.065,-0.043,0.81,0.065,-0.053,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29190000,-0.29,0.016,-0.0026,0.96,0.066,-0.043,0.8,0.067,-0.052,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29290000,-0.29,0.016,-0.0028,0.96,0.071,-0.048,0.81,0.075,-0.056,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29390000,-0.29,0.015,-0.0033,0.96,0.067,-0.045,0.81,0.074,-0.053,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29490000,-0.29,0.015,-0.0033,0.96,0.07,-0.046,0.81,0.081,-0.059,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29590000,-0.29,0.015,-0.0032,0.96,0.068,-0.045,0.81,0.079,-0.057,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29690000,-0.29,0.015,-0.0032,0.96,0.072,-0.044,0.81,0.087,-0.062,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29790000,-0.29,0.015,-0.003,0.96,0.069,-0.038,0.8,0.084,-0.059,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29890000,-0.29,0.015,-0.0024,0.96,0.071,-0.039,0.8,0.092,-0.063,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 -29990000,-0.29,0.016,-0.0025,0.96,0.066,-0.038,0.8,0.087,-0.062,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30090000,-0.29,0.016,-0.0027,0.96,0.067,-0.037,0.8,0.094,-0.064,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30190000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.089,-0.056,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30290000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.096,-0.059,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30390000,-0.29,0.015,-0.0027,0.96,0.06,-0.026,0.8,0.095,-0.053,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30490000,-0.29,0.015,-0.0027,0.96,0.063,-0.026,0.8,0.1,-0.056,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30590000,-0.29,0.016,-0.0029,0.96,0.062,-0.024,0.8,0.098,-0.053,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30690000,-0.29,0.016,-0.0033,0.96,0.059,-0.023,0.8,0.1,-0.056,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30790000,-0.29,0.016,-0.0031,0.96,0.053,-0.014,0.79,0.096,-0.044,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30890000,-0.29,0.015,-0.0025,0.96,0.052,-0.01,0.79,0.1,-0.045,-0.95,-0.0013,-0.0058,-4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -30990000,-0.29,0.015,-0.0026,0.96,0.047,-0.0087,0.79,0.095,-0.043,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31090000,-0.29,0.015,-0.0028,0.96,0.046,-0.0074,0.79,0.1,-0.043,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31190000,-0.29,0.016,-0.0029,0.96,0.043,-0.0043,0.8,0.094,-0.04,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31290000,-0.29,0.016,-0.0031,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31390000,-0.29,0.015,-0.0029,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31490000,-0.29,0.016,-0.0026,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31590000,-0.29,0.016,-0.0024,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-6.1e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31890000,-0.29,0.017,-0.0023,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.8e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -31990000,-0.29,0.016,-0.0026,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,9.1e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32090000,-0.29,0.016,-0.003,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,4.8e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32190000,-0.29,0.016,-0.0033,0.96,0.028,0.028,0.8,0.094,-0.0047,-0.028,-0.0012,-0.0058,3.6e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32290000,-0.29,0.016,-0.0031,0.96,0.027,0.03,0.79,0.098,-0.002,0.042,-0.0012,-0.0058,7.4e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1 -32390000,-0.29,0.016,-0.0033,0.96,0.024,0.032,0.79,0.094,0.0016,0.12,-0.0012,-0.0058,5.6e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0093,0.12,-0.0012,-0.0058,3.3e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32590000,-0.29,0.015,-0.0064,0.96,-0.014,0.084,-0.081,0.093,0.0023,0.1,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-1.6e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32790000,-0.29,0.015,-0.0062,0.96,-0.0057,0.09,-0.083,0.093,0.0036,0.072,-0.0012,-0.0058,-7.2e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32890000,-0.29,0.015,-0.0062,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-2.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -32990000,-0.29,0.015,-0.0061,0.96,-0.0024,0.091,-0.084,0.092,-0.00065,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33090000,-0.29,0.015,-0.006,0.96,0.0014,0.097,-0.081,0.092,0.0086,0.036,-0.0013,-0.0058,-9.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.006,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0027,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33390000,-0.3,0.015,-0.0059,0.96,0.014,0.093,-0.078,0.094,-0.0055,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33490000,-0.3,0.015,-0.0059,0.96,0.019,0.097,-0.077,0.097,0.0039,0.0017,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33590000,-0.3,0.015,-0.0057,0.95,0.023,0.095,-0.074,0.096,-0.009,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33690000,-0.3,0.015,-0.0057,0.95,0.026,0.098,-0.075,0.097,-3.8e-05,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.069,0.094,-0.013,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33890000,-0.3,0.015,-0.0056,0.95,0.033,0.098,-0.069,0.097,-0.0041,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -33990000,-0.3,0.015,-0.0055,0.95,0.035,0.096,-0.065,0.096,-0.012,-0.032,-0.0013,-0.0058,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34090000,-0.3,0.015,-0.0055,0.95,0.038,0.1,-0.064,0.099,-0.0028,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 -34190000,-0.3,0.015,-0.0054,0.95,0.039,0.098,-0.061,0.094,-0.015,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34290000,-0.3,0.015,-0.0053,0.95,0.04,0.1,-0.06,0.098,-0.0048,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34390000,-0.3,0.015,-0.0052,0.95,0.042,0.097,-0.055,0.093,-0.016,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34490000,-0.3,0.015,-0.0052,0.95,0.045,0.1,-0.053,0.097,-0.0069,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34590000,-0.3,0.014,-0.0051,0.95,0.045,0.098,0.74,0.092,-0.021,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 -34890000,-0.3,0.014,-0.0051,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 +10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.032 +90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.058 +190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.082 +290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.095,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.11 +390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.095,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.13 +490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.16 +590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.18 +690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.095,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.21 +790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00077,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.23 +890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.095,0.019,0.019,0.00051,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.26 +990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,4.9e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.095,0.021,0.021,0.00062,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.28 +1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.095,0.023,0.023,0.00043,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.31 +1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.6e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 +1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 +1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 +1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.5e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.095,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.7e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.095,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.095,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.5e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.095,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.014,0.00048,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.5e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-2.1e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.095,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.01,-0.013,0.00038,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.01,-0.013,0.00032,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-3.1e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.095,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-3.1e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.01,-0.013,0.00057,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.095,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.5e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.095,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.095,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.0097,-0.013,0.00059,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.095,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.095,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.0095,-0.013,0.00053,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.095,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.8e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.095,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.0094,-0.013,0.00064,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.095,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.095,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.0093,-0.012,0.00077,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-5.2e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.095,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-5.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.095,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.0095,-0.012,0.00075,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.7e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.095,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.7e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.095,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.0094,-0.012,0.00077,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-6.2e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.095,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-6.2e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.095,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.0094,-0.012,0.00077,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.095,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.0093,-0.012,0.00087,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.095,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.0092,-0.012,0.00091,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-7e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.095,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-7e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.0091,-0.011,0.00097,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-7.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0089,-0.011,0.0009,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0088,-0.011,0.00086,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0088,-0.011,0.00089,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0088,-0.012,0.00087,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0088,-0.011,0.00068,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0089,-0.011,0.00069,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0089,-0.011,0.00072,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0089,-0.011,0.00073,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0089,-0.011,0.00063,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.8e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.009,-0.011,0.00056,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0089,-0.011,0.00052,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-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.009,-0.011,0.00048,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-9.2e-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,8.1e-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.0088,-0.011,0.0004,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-9.2e-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,8.1e-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.29,0.024,-0.0061,0.96,-0.2,-0.033,-0.037,-0.11,-0.019,-0.055,-0.00071,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.095,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1,1.8 +7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.049,-0.038,-0.15,-0.027,-0.056,-0.00058,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.095,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1,1.8 +7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.00054,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1,1.8 +7290000,-0.29,0.025,-0.0063,0.96,-0.28,-0.066,-0.034,-0.2,-0.04,-0.055,-0.00053,-0.01,-0.00021,-0.00088,-0.00019,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1,1.9 +7390000,-0.29,0.025,-0.0063,0.96,-0.3,-0.072,-0.032,-0.23,-0.048,-0.052,-0.00052,-0.01,-0.00021,-0.0011,-0.00023,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00014,0.0013,0.0013,0.00086,0.0013,1,1,1.9 +7490000,-0.29,0.024,-0.0063,0.96,-0.32,-0.08,-0.026,-0.25,-0.056,-0.046,-0.00051,-0.0099,-0.00021,-0.0015,-0.00027,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 +7590000,-0.29,0.024,-0.0065,0.96,-0.34,-0.087,-0.022,-0.28,-0.065,-0.041,-0.00049,-0.0098,-0.00021,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 +7690000,-0.29,0.024,-0.0065,0.96,-0.35,-0.096,-0.022,-0.31,-0.076,-0.036,-0.00047,-0.0097,-0.00021,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 +7790000,-0.29,0.023,-0.0063,0.96,-0.36,-0.11,-0.024,-0.34,-0.09,-0.041,-0.0004,-0.0096,-0.00021,-0.0017,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 +7890000,-0.29,0.023,-0.0063,0.96,-0.37,-0.11,-0.025,-0.37,-0.1,-0.045,-0.00038,-0.0095,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00086,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.0001,0.0013,0.0013,0.00083,0.0013,1,1,2 +7990000,-0.29,0.023,-0.0064,0.96,-0.39,-0.12,-0.021,-0.4,-0.11,-0.041,-0.00041,-0.0094,-0.0002,-0.0016,-0.00019,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.8e-05,0.0013,0.0012,0.00083,0.0013,1,1,2 +8090000,-0.29,0.023,-0.0062,0.96,-0.41,-0.13,-0.022,-0.43,-0.13,-0.044,-0.00034,-0.0094,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.0008,0.00083,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,9.6e-05,0.0013,0.0012,0.00083,0.0013,1,1,2.1 +8190000,-0.29,0.022,-0.0063,0.96,-0.41,-0.14,-0.017,-0.46,-0.15,-0.038,-0.00028,-0.0092,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00078,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.4e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 +8290000,-0.29,0.022,-0.0064,0.96,-0.44,-0.15,-0.016,-0.51,-0.16,-0.038,-0.00033,-0.0093,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00075,0.00078,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.2e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 +8390000,-0.29,0.022,-0.0065,0.96,-0.45,-0.15,-0.015,-0.55,-0.17,-0.036,-0.00034,-0.0092,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0012,9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 +8490000,-0.29,0.022,-0.0065,0.96,-0.46,-0.15,-0.016,-0.58,-0.18,-0.041,-0.00043,-0.0091,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00071,0.00073,0.053,0.82,0.81,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.2 +8590000,-0.29,0.022,-0.0063,0.96,-0.45,-0.16,-0.012,-0.6,-0.2,-0.036,-0.00037,-0.0089,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00069,0.00071,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.7e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 +8690000,-0.29,0.021,-0.0064,0.96,-0.46,-0.16,-0.014,-0.64,-0.21,-0.037,-0.00042,-0.0088,-0.00019,-0.0016,-7.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00067,0.00069,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,8.6e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 +8790000,-0.29,0.021,-0.0065,0.96,-0.48,-0.16,-0.013,-0.67,-0.23,-0.035,-0.00041,-0.0088,-0.00019,-0.0016,-6.7e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00065,0.00067,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,8.5e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 +8890000,-0.29,0.021,-0.0064,0.96,-0.47,-0.16,-0.0093,-0.68,-0.24,-0.029,-0.00046,-0.0085,-0.00018,-0.0016,4.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00063,0.00065,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,8.4e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 +8990000,-0.29,0.02,-0.0063,0.96,-0.45,-0.17,-0.0088,-0.68,-0.25,-0.032,-0.0005,-0.0082,-0.00017,-0.0013,0.00015,-0.13,-0.1,-0.024,0.5,0.08,-0.032,-0.069,0,0,0.095,0.00062,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,8.3e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 +9090000,-0.29,0.02,-0.0064,0.96,-0.46,-0.16,-0.0099,-0.72,-0.23,-0.032,-0.00067,-0.0082,-0.00016,-0.0012,0.00032,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 +9190000,-0.29,0.02,-0.0064,0.96,-0.46,-0.15,-0.0095,-0.74,-0.23,-0.033,-0.00077,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.095,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.3 +9290000,-0.29,0.02,-0.0061,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00077,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 +9390000,-0.29,0.02,-0.0059,0.96,-0.45,-0.17,-0.007,-0.75,-0.28,-0.031,-0.00069,-0.0077,-0.00015,-0.00085,0.00049,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 +9490000,-0.29,0.019,-0.006,0.96,-0.46,-0.17,-0.0055,-0.78,-0.28,-0.028,-0.00077,-0.0076,-0.00015,-0.00093,0.00058,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 +9590000,-0.29,0.019,-0.006,0.96,-0.47,-0.19,-0.0054,-0.82,-0.33,-0.029,-0.00064,-0.0075,-0.00015,-0.00087,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4 +9690000,-0.29,0.019,-0.0059,0.96,-0.47,-0.2,-0.0026,-0.83,-0.36,-0.028,-0.0006,-0.0074,-0.00015,-0.00078,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9790000,-0.29,0.019,-0.0059,0.96,-0.48,-0.21,-0.0039,-0.88,-0.4,-0.029,-0.00052,-0.0074,-0.00015,-0.00077,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9890000,-0.29,0.019,-0.0058,0.96,-0.47,-0.21,-0.0027,-0.88,-0.42,-0.03,-0.00055,-0.0072,-0.00014,-0.00053,0.00044,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9990000,-0.29,0.019,-0.0058,0.96,-0.49,-0.22,-0.002,-0.93,-0.46,-0.032,-0.00049,-0.0072,-0.00015,-0.00044,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.5 +10090000,-0.29,0.019,-0.0057,0.96,-0.49,-0.24,-0.00079,-0.96,-0.51,-0.03,-0.00039,-0.0071,-0.00015,-0.00045,0.0003,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10190000,-0.29,0.019,-0.0057,0.96,-0.49,-0.26,4.4e-05,-0.97,-0.58,-0.031,-0.00025,-0.007,-0.00015,-0.00028,0.00017,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10290000,-0.29,0.019,-0.0056,0.96,-0.49,-0.26,-0.0011,-0.98,-0.59,-0.03,-0.00032,-0.0069,-0.00014,-0.00016,0.00024,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10390000,-0.29,0.019,-0.0055,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00015,-0.029,-0.00036,-0.0067,-0.00014,-6.4e-06,0.0003,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10490000,-0.29,0.019,-0.0055,0.96,-0.01,-0.0087,0.0071,0.00024,-0.00081,-0.024,-0.00029,-0.0067,-0.00014,-0.00015,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10590000,-0.29,0.019,-0.0054,0.96,-0.021,-0.0074,0.013,-0.0011,-0.00057,-0.022,-0.00039,-0.0066,-0.00013,0.0001,0.0006,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10690000,-0.29,0.019,-0.0053,0.96,-0.034,-0.01,0.016,-0.0038,-0.0015,-0.018,-0.00037,-0.0065,-0.00013,0.00013,0.00058,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10790000,-0.29,0.019,-0.0052,0.96,-0.034,-0.014,0.014,0.00012,-0.0018,-0.016,-0.0004,-0.0064,-0.00013,0.002,5.7e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10890000,-0.29,0.019,-0.0051,0.96,-0.043,-0.019,0.01,-0.0037,-0.0034,-0.019,-0.00052,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.8 +10990000,-0.29,0.019,-0.0051,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00056,-0.0064,-0.00012,0.0058,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 +11090000,-0.29,0.019,-0.0052,0.96,-0.051,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00045,-0.0063,-0.00013,0.006,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 +11190000,-0.29,0.018,-0.0053,0.96,-0.041,-0.026,0.027,-0.0021,-0.0027,-0.0011,-0.00045,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 +11290000,-0.29,0.018,-0.0053,0.96,-0.05,-0.027,0.026,-0.0066,-0.0053,-0.00072,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.9 +11390000,-0.29,0.018,-0.0052,0.96,-0.043,-0.024,0.017,-0.0037,-0.0034,-0.0091,-0.00052,-0.0063,-0.00013,0.019,0.0029,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 +11490000,-0.29,0.018,-0.0051,0.96,-0.05,-0.026,0.021,-0.0082,-0.006,-0.003,-0.00053,-0.0062,-0.00012,0.019,0.003,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 +11590000,-0.29,0.018,-0.0052,0.96,-0.045,-0.021,0.019,-0.005,-0.0039,-0.004,-0.00057,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 +11690000,-0.29,0.017,-0.0052,0.96,-0.051,-0.026,0.019,-0.0097,-0.0062,-0.0053,-0.00061,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.087,0.087,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,3 +11790000,-0.29,0.017,-0.0051,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.0007,-0.0063,-0.00012,0.03,0.0046,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 +11890000,-0.29,0.017,-0.0053,0.96,-0.049,-0.028,0.018,-0.01,-0.008,-0.0016,-0.00069,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 +11990000,-0.29,0.017,-0.0053,0.96,-0.039,-0.021,0.015,-0.0064,-0.0053,-0.0052,-0.00072,-0.0063,-0.00012,0.037,0.0066,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 +12090000,-0.29,0.017,-0.0052,0.96,-0.045,-0.022,0.018,-0.011,-0.0076,0.00088,-0.0007,-0.0062,-0.00012,0.037,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3.1 +12190000,-0.29,0.017,-0.0052,0.96,-0.038,-0.013,0.017,-0.0054,-0.0029,0.0028,-0.00066,-0.0062,-0.00012,0.043,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 +12290000,-0.29,0.017,-0.0053,0.96,-0.04,-0.012,0.016,-0.0094,-0.0041,0.0038,-0.00063,-0.0062,-0.00012,0.043,0.0085,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 +12390000,-0.29,0.016,-0.0053,0.96,-0.033,-0.0087,0.014,-0.0051,-0.0027,-0.0022,-0.00063,-0.0062,-0.00012,0.047,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 +12490000,-0.29,0.016,-0.0053,0.96,-0.036,-0.0097,0.018,-0.0087,-0.0037,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 +12590000,-0.29,0.016,-0.0052,0.96,-0.03,-0.0084,0.02,-0.0035,-0.0039,0.0017,-0.00061,-0.0061,-0.00012,0.05,0.0078,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 +12690000,-0.29,0.016,-0.0052,0.96,-0.033,-0.0065,0.019,-0.0066,-0.0047,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 +12790000,-0.29,0.016,-0.005,0.96,-0.023,-0.012,0.02,-0.0016,-0.0077,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.4e-06,7e-06,2.2e-06,0.0093,0.0096,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.2 +12890000,-0.29,0.016,-0.005,0.96,-0.025,-0.013,0.021,-0.004,-0.009,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0073,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +12990000,-0.29,0.016,-0.005,0.96,-0.021,-0.0099,0.022,-0.0012,-0.0063,0.0096,-0.00075,-0.0061,-0.00012,0.054,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0083,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +13090000,-0.29,0.016,-0.0049,0.96,-0.023,-0.011,0.019,-0.0033,-0.0076,0.0084,-0.00079,-0.006,-0.00011,0.054,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +13190000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.018,-0.0017,-0.0086,0.009,-0.00082,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0072,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +13290000,-0.29,0.016,-0.0049,0.96,-0.021,-0.011,0.016,-0.0038,-0.0099,0.0084,-0.00081,-0.006,-0.00011,0.056,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13390000,-0.29,0.016,-0.0049,0.96,-0.017,-0.0083,0.015,-0.0014,-0.0068,0.009,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.0001,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13490000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.015,-0.0032,-0.0079,0.0051,-0.00079,-0.006,-0.00011,0.057,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,0.0001,0.0001,0.051,0.053,0.053,0.009,0.067,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13590000,-0.29,0.016,-0.0049,0.96,-0.014,-0.0075,0.016,0.0017,-0.0056,0.0036,-0.00077,-0.006,-0.00011,0.059,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,9.3e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0059,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13690000,-0.29,0.016,-0.0048,0.96,-0.015,-0.0066,0.016,0.00026,-0.0063,0.0062,-0.00079,-0.0059,-0.00011,0.059,0.0093,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,9.4e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +13790000,-0.29,0.015,-0.0048,0.96,-0.011,-0.0047,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.061,0.0092,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.7e-05,8.7e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +13890000,-0.29,0.015,-0.0047,0.96,-0.012,-0.0058,0.017,0.0044,-0.0039,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0093,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.8e-05,8.8e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +13990000,-0.29,0.015,-0.0047,0.96,-0.014,-0.0096,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0097,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.3e-05,8.3e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0047,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +14090000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0037,0.017,0.0022,-0.0049,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14190000,-0.29,0.015,-0.0048,0.96,-0.01,-0.0025,0.017,0.0035,-0.0039,0.0033,-0.00073,-0.006,-0.00011,0.063,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0046,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14290000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0029,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.063,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.1e-05,8e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14390000,-0.29,0.015,-0.0048,0.96,-0.012,-0.0025,0.017,0.0036,-0.0047,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0043,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14490000,-0.29,0.015,-0.005,0.96,-0.012,-0.0018,0.02,0.0022,-0.0047,0.014,-0.00071,-0.0059,-0.00012,0.064,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.8e-05,7.7e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14590000,-0.29,0.015,-0.005,0.96,-0.015,-0.0035,0.018,0.00068,-0.0052,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.5e-05,7.4e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0038,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14690000,-0.29,0.015,-0.005,0.96,-0.016,-0.0038,0.018,-0.00092,-0.0057,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14790000,-0.29,0.015,-0.0051,0.96,-0.019,-0.0012,0.018,-0.00061,-0.0012,0.013,-0.00072,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.0007,0.022,-0.0027,-0.0016,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +14990000,-0.29,0.015,-0.005,0.96,-0.02,-0.0013,0.025,-0.0022,-0.0028,0.016,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +15090000,-0.29,0.016,-0.0049,0.96,-0.021,-0.0024,0.029,-0.0043,-0.0029,0.018,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00056,0.029,-0.0034,-0.0023,0.02,-0.00073,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +15290000,-0.29,0.016,-0.0051,0.96,-0.024,-0.00067,0.029,-0.0059,-0.0028,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15390000,-0.29,0.016,-0.0052,0.96,-0.023,-0.0026,0.028,-0.0046,-0.0023,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15490000,-0.29,0.016,-0.0052,0.96,-0.025,-0.00012,0.028,-0.007,-0.0025,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0045,0.028,-0.0033,-0.0057,0.017,-0.00078,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15690000,-0.29,0.016,-0.0051,0.96,-0.024,-0.0024,0.028,-0.0049,-0.0061,0.018,-0.00083,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +15790000,-0.29,0.015,-0.0051,0.96,-0.021,-0.0012,0.028,-0.0035,-0.0052,0.019,-0.00087,-0.0058,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +15890000,-0.29,0.016,-0.0052,0.96,-0.021,-0.0024,0.029,-0.0059,-0.0052,0.019,-0.00084,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0019,0.026,-0.0049,-0.0044,0.018,-0.00083,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00065,0.024,-0.0072,-0.0044,0.018,-0.00082,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00046,0.023,-0.0071,-0.0036,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16290000,-0.29,0.016,-0.0051,0.96,-0.022,0.00049,0.022,-0.0091,-0.0037,0.017,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16390000,-0.29,0.016,-0.005,0.96,-0.023,-6.6e-05,0.023,-0.007,-0.0036,0.017,-0.00082,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16490000,-0.29,0.016,-0.0051,0.96,-0.027,0.0009,0.025,-0.0098,-0.0035,0.021,-0.00081,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16590000,-0.29,0.016,-0.0051,0.96,-0.031,0.0013,0.029,-0.0085,-0.003,0.021,-0.00082,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16690000,-0.29,0.015,-0.0051,0.96,-0.034,0.0049,0.029,-0.011,-0.0028,0.021,-0.00084,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16790000,-0.29,0.015,-0.005,0.96,-0.035,0.0046,0.028,-0.0096,-0.0025,0.021,-0.00086,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0028,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16890000,-0.29,0.015,-0.0049,0.96,-0.035,0.0041,0.029,-0.013,-0.0025,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6.1e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +16990000,-0.29,0.015,-0.005,0.96,-0.032,0.0045,0.029,-0.011,-0.0027,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +17090000,-0.29,0.015,-0.0051,0.96,-0.037,0.0065,0.028,-0.015,-0.0022,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +17190000,-0.29,0.015,-0.0052,0.96,-0.036,0.0083,0.03,-0.014,-0.0038,0.021,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +17290000,-0.29,0.015,-0.0052,0.96,-0.039,0.009,0.03,-0.018,-0.0026,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17390000,-0.29,0.015,-0.0051,0.96,-0.029,0.014,0.029,-0.01,-0.0013,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17490000,-0.29,0.015,-0.0052,0.96,-0.029,0.015,0.029,-0.013,0.00029,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17590000,-0.29,0.015,-0.0052,0.96,-0.029,0.013,0.028,-0.012,-0.00011,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17690000,-0.29,0.015,-0.0052,0.96,-0.03,0.014,0.029,-0.016,0.001,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 +17790000,-0.29,0.015,-0.0053,0.96,-0.031,0.014,0.029,-0.015,0.0018,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0026,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 +17890000,-0.29,0.015,-0.0052,0.96,-0.035,0.015,0.029,-0.017,0.003,0.032,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 +17990000,-0.29,0.015,-0.0052,0.96,-0.034,0.016,0.029,-0.014,0.0053,0.033,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.5 +18090000,-0.29,0.015,-0.0052,0.96,-0.036,0.017,0.028,-0.018,0.0068,0.031,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18190000,-0.29,0.015,-0.0052,0.96,-0.032,0.014,0.028,-0.013,0.0046,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18290000,-0.29,0.015,-0.0052,0.96,-0.036,0.014,0.027,-0.017,0.0057,0.028,-0.00098,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18390000,-0.29,0.015,-0.0051,0.96,-0.032,0.014,0.027,-0.012,0.0048,0.027,-0.00099,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18490000,-0.29,0.015,-0.0051,0.96,-0.036,0.013,0.026,-0.015,0.0057,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0025,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18590000,-0.29,0.015,-0.005,0.96,-0.034,0.013,0.026,-0.013,0.0051,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18690000,-0.29,0.015,-0.005,0.96,-0.034,0.012,0.025,-0.015,0.006,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18790000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.024,-0.012,0.0052,0.028,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18890000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.022,-0.015,0.0065,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +18990000,-0.29,0.015,-0.0049,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +19090000,-0.29,0.015,-0.0049,0.96,-0.028,0.013,0.024,-0.016,0.0064,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +19190000,-0.29,0.015,-0.0049,0.96,-0.026,0.014,0.023,-0.014,0.0063,0.023,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19390000,-0.29,0.015,-0.005,0.96,-0.026,0.012,0.025,-0.015,0.0074,0.021,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19690000,-0.29,0.015,-0.0049,0.96,-0.025,0.013,0.025,-0.018,0.0078,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +19790000,-0.29,0.015,-0.005,0.96,-0.022,0.013,0.023,-0.018,0.0085,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +19890000,-0.29,0.015,-0.005,0.96,-0.023,0.013,0.023,-0.02,0.0098,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +19990000,-0.29,0.015,-0.005,0.96,-0.02,0.014,0.021,-0.016,0.009,0.012,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +20090000,-0.29,0.015,-0.005,0.96,-0.023,0.016,0.021,-0.018,0.01,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5.1 +20190000,-0.29,0.015,-0.005,0.96,-0.024,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 +20290000,-0.29,0.015,-0.005,0.96,-0.022,0.016,0.022,-0.021,0.012,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 +20390000,-0.29,0.015,-0.005,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 +20490000,-0.29,0.015,-0.005,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.3e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20590000,-0.29,0.015,-0.0049,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.2e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20690000,-0.29,0.015,-0.0048,0.96,-0.017,0.016,0.023,-0.025,0.014,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.5e-05,5.1e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20790000,-0.29,0.015,-0.0042,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20890000,-0.29,0.01,0.0044,0.96,-0.0063,0.0016,-0.11,-0.021,0.011,0.0066,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.11,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20990000,-0.29,0.0063,0.0074,0.96,0.0088,-0.015,-0.25,-0.017,0.0081,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.092,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.2e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21090000,-0.29,0.0069,0.0058,0.96,0.023,-0.028,-0.37,-0.015,0.0062,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.061,5.3e-05,4.9e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21190000,-0.29,0.0088,0.0033,0.96,0.029,-0.033,-0.5,-0.013,0.0046,-0.075,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.025,5.1e-05,4.8e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21290000,-0.29,0.01,0.0012,0.96,0.027,-0.036,-0.63,-0.01,0.002,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.034,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21390000,-0.29,0.011,-0.00024,0.96,0.021,-0.029,-0.75,-0.012,0.0052,-0.2,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.099,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21490000,-0.29,0.012,-0.00099,0.96,0.014,-0.028,-0.89,-0.0097,0.0021,-0.28,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.18,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21590000,-0.29,0.012,-0.0015,0.96,0.0028,-0.022,-1,-0.014,0.0068,-0.37,-0.0011,-0.0058,-0.00012,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.27,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.002,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21690000,-0.29,0.012,-0.0018,0.96,-0.0025,-0.019,-1.1,-0.014,0.004,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.39,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21790000,-0.29,0.012,-0.0022,0.96,-0.0083,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.51,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0072,-1.4,-0.016,0.0097,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.65,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.001,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22090000,-0.29,0.013,-0.0039,0.96,-0.023,0.0043,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.93,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22190000,-0.29,0.013,-0.0043,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.1,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22290000,-0.29,0.014,-0.005,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.2,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22390000,-0.29,0.014,-0.0053,0.96,-0.045,0.022,-1.4,-0.038,0.029,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.4,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22490000,-0.29,0.015,-0.0054,0.96,-0.052,0.028,-1.4,-0.043,0.032,-1.6,-0.001,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.5,5e-05,4.6e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22590000,-0.29,0.015,-0.0052,0.96,-0.057,0.034,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.6,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22690000,-0.29,0.015,-0.0052,0.96,-0.062,0.039,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.8,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22790000,-0.29,0.016,-0.0051,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.9,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +22890000,-0.29,0.016,-0.0052,0.96,-0.073,0.048,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.1,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +22990000,-0.29,0.016,-0.005,0.96,-0.076,0.048,-1.4,-0.065,0.045,-2.3,-0.0011,-0.0058,-7e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.2,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23090000,-0.29,0.017,-0.005,0.96,-0.082,0.052,-1.4,-0.072,0.05,-2.5,-0.0011,-0.0058,-6.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.4,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23190000,-0.29,0.017,-0.0049,0.96,-0.084,0.047,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.1e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.5,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23290000,-0.29,0.017,-0.0054,0.96,-0.09,0.051,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.7,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23390000,-0.29,0.017,-0.0053,0.96,-0.09,0.054,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.8e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.8,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23490000,-0.29,0.017,-0.0053,0.96,-0.096,0.054,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.9,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23590000,-0.29,0.017,-0.0055,0.96,-0.095,0.048,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.1,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23690000,-0.29,0.018,-0.006,0.96,-0.094,0.051,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.2e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.2,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23790000,-0.29,0.021,-0.0075,0.96,-0.079,0.048,-0.95,-0.08,0.047,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.3,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23890000,-0.29,0.025,-0.01,0.96,-0.074,0.051,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.4,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23990000,-0.29,0.028,-0.012,0.96,-0.065,0.05,-0.13,-0.074,0.046,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +24090000,-0.29,0.027,-0.012,0.96,-0.072,0.058,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.7e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +24190000,-0.29,0.023,-0.0092,0.96,-0.076,0.055,0.088,-0.066,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24290000,-0.29,0.019,-0.0072,0.96,-0.08,0.057,0.066,-0.074,0.044,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24390000,-0.29,0.018,-0.0064,0.96,-0.064,0.05,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24490000,-0.29,0.018,-0.0066,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24590000,-0.29,0.018,-0.0072,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24690000,-0.29,0.018,-0.0077,0.96,-0.045,0.044,0.075,-0.046,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24790000,-0.29,0.017,-0.0078,0.96,-0.039,0.042,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24890000,-0.29,0.017,-0.0077,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25090000,-0.29,0.016,-0.0078,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25190000,-0.29,0.016,-0.008,0.96,-0.011,0.042,0.047,-0.0079,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25290000,-0.3,0.016,-0.0082,0.96,-0.006,0.045,0.042,-0.0086,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25390000,-0.3,0.015,-0.0083,0.96,0.003,0.043,0.04,0.0014,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25490000,-0.3,0.015,-0.0084,0.96,0.0074,0.044,0.04,0.0011,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25590000,-0.3,0.015,-0.0085,0.96,0.012,0.04,0.041,0.0086,0.0097,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25690000,-0.3,0.014,-0.008,0.96,0.013,0.039,0.03,0.0099,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25790000,-0.3,0.014,-0.0078,0.96,0.024,0.034,0.03,0.017,0.0035,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25890000,-0.3,0.014,-0.0079,0.96,0.03,0.034,0.033,0.02,0.0078,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25990000,-0.3,0.014,-0.0079,0.96,0.032,0.029,0.026,0.017,-0.0034,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26090000,-0.3,0.014,-0.0076,0.96,0.037,0.029,0.025,0.021,-0.0013,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26190000,-0.3,0.014,-0.0074,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26290000,-0.3,0.015,-0.0074,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26390000,-0.3,0.015,-0.0068,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26490000,-0.3,0.015,-0.0066,0.96,0.043,0.0087,0.028,0.023,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26590000,-0.3,0.015,-0.006,0.96,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26690000,-0.3,0.015,-0.0059,0.96,0.044,-0.0049,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26790000,-0.3,0.014,-0.0057,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26990000,-0.3,0.015,-0.0045,0.96,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +27090000,-0.3,0.015,-0.0043,0.96,0.057,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27290000,-0.3,0.016,-0.0044,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27390000,-0.3,0.018,-0.0056,0.96,0.067,-0.026,0.46,0.007,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27490000,-0.3,0.02,-0.0067,0.95,0.072,-0.028,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27590000,-0.3,0.019,-0.0067,0.96,0.063,-0.03,0.87,0.0077,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.3,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27690000,-0.3,0.016,-0.0058,0.96,0.058,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.2,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27790000,-0.3,0.015,-0.0047,0.96,0.054,-0.026,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27890000,-0.3,0.015,-0.0043,0.96,0.061,-0.031,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27990000,-0.3,0.015,-0.0047,0.96,0.061,-0.034,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28090000,-0.3,0.015,-0.005,0.96,0.065,-0.034,0.8,0.026,-0.027,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.9,4.5e-05,4e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28190000,-0.3,0.015,-0.0044,0.96,0.062,-0.033,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28290000,-0.3,0.016,-0.0038,0.96,0.066,-0.036,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28390000,-0.3,0.016,-0.0038,0.96,0.068,-0.038,0.81,0.035,-0.034,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.7,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28490000,-0.3,0.017,-0.004,0.96,0.07,-0.041,0.81,0.043,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.6,4.5e-05,4e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28590000,-0.29,0.017,-0.004,0.96,0.063,-0.042,0.81,0.043,-0.041,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.5,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28690000,-0.29,0.016,-0.0039,0.96,0.062,-0.043,0.81,0.049,-0.045,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.5,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28790000,-0.29,0.016,-0.0032,0.96,0.06,-0.042,0.81,0.05,-0.044,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.4,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28890000,-0.29,0.015,-0.0031,0.96,0.064,-0.044,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.3,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28990000,-0.29,0.016,-0.0028,0.96,0.062,-0.042,0.81,0.058,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29090000,-0.29,0.016,-0.0027,0.96,0.065,-0.043,0.81,0.065,-0.053,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29190000,-0.29,0.016,-0.0026,0.96,0.066,-0.043,0.8,0.067,-0.052,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.1,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29290000,-0.29,0.016,-0.0028,0.96,0.071,-0.048,0.81,0.075,-0.056,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29390000,-0.29,0.015,-0.0033,0.96,0.067,-0.045,0.81,0.074,-0.053,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29490000,-0.29,0.015,-0.0033,0.96,0.07,-0.046,0.81,0.081,-0.059,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29590000,-0.29,0.015,-0.0032,0.96,0.068,-0.045,0.81,0.079,-0.057,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.8,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29690000,-0.29,0.015,-0.0032,0.96,0.072,-0.044,0.81,0.087,-0.062,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.7,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29790000,-0.29,0.015,-0.003,0.96,0.069,-0.038,0.8,0.084,-0.059,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29890000,-0.29,0.015,-0.0024,0.96,0.071,-0.039,0.8,0.092,-0.063,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29990000,-0.29,0.016,-0.0025,0.96,0.066,-0.038,0.8,0.087,-0.062,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.5,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30090000,-0.29,0.016,-0.0027,0.96,0.067,-0.037,0.8,0.094,-0.064,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.4,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30190000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.089,-0.056,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.4,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30290000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.096,-0.059,-1.4,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.3,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30390000,-0.29,0.015,-0.0027,0.96,0.06,-0.026,0.8,0.095,-0.053,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.2,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30490000,-0.29,0.015,-0.0027,0.96,0.063,-0.026,0.8,0.1,-0.056,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30590000,-0.29,0.016,-0.0029,0.96,0.062,-0.024,0.8,0.098,-0.053,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30690000,-0.29,0.016,-0.0033,0.96,0.059,-0.023,0.8,0.1,-0.056,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30790000,-0.29,0.016,-0.0031,0.96,0.053,-0.014,0.79,0.096,-0.044,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.92,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30890000,-0.29,0.015,-0.0025,0.96,0.052,-0.01,0.79,0.1,-0.044,-0.95,-0.0013,-0.0058,-4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.85,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30990000,-0.29,0.015,-0.0026,0.96,0.047,-0.0087,0.79,0.095,-0.043,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.78,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31090000,-0.29,0.015,-0.0028,0.96,0.046,-0.0074,0.79,0.1,-0.043,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.71,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31190000,-0.29,0.016,-0.0029,0.96,0.043,-0.0043,0.8,0.094,-0.04,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.64,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31290000,-0.29,0.016,-0.0031,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.57,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31390000,-0.29,0.015,-0.0029,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.49,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31490000,-0.29,0.016,-0.0026,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31590000,-0.29,0.016,-0.0024,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.35,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.28,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-6.8e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31890000,-0.29,0.017,-0.0023,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.14,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31990000,-0.29,0.016,-0.0026,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,8.4e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.068,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32090000,-0.29,0.016,-0.003,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,4.1e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32190000,-0.29,0.016,-0.0033,0.96,0.028,0.028,0.8,0.094,-0.0047,-0.028,-0.0012,-0.0058,3.5e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.072,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32290000,-0.29,0.016,-0.0031,0.96,0.027,0.03,0.79,0.098,-0.002,0.042,-0.0012,-0.0058,7.3e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.14,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32390000,-0.29,0.016,-0.0033,0.96,0.024,0.032,0.79,0.094,0.0016,0.12,-0.0012,-0.0058,5.5e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0093,0.12,-0.0012,-0.0058,3.2e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32590000,-0.29,0.015,-0.0064,0.96,-0.014,0.084,-0.081,0.093,0.0024,0.1,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.2,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.19,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32790000,-0.29,0.015,-0.0062,0.96,-0.0057,0.09,-0.083,0.093,0.0036,0.072,-0.0012,-0.0058,-7.2e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32890000,-0.29,0.015,-0.0062,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-2.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32990000,-0.29,0.015,-0.0061,0.96,-0.0024,0.091,-0.084,0.092,-0.00064,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33090000,-0.29,0.015,-0.006,0.96,0.0014,0.097,-0.081,0.092,0.0086,0.036,-0.0013,-0.0058,-9.8e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.006,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0027,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33390000,-0.3,0.015,-0.0059,0.96,0.014,0.093,-0.078,0.094,-0.0055,0.011,-0.0013,-0.0058,-2.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 +33490000,-0.3,0.015,-0.0059,0.96,0.019,0.097,-0.077,0.097,0.0039,0.0017,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 +33590000,-0.3,0.015,-0.0057,0.95,0.023,0.095,-0.074,0.096,-0.009,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 +33690000,-0.3,0.015,-0.0057,0.95,0.026,0.098,-0.075,0.097,-3.1e-05,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 +33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.069,0.094,-0.013,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 +33890000,-0.3,0.015,-0.0056,0.95,0.033,0.098,-0.069,0.097,-0.0041,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 +33990000,-0.3,0.015,-0.0055,0.95,0.035,0.096,-0.065,0.096,-0.012,-0.032,-0.0013,-0.0058,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 +34090000,-0.3,0.015,-0.0055,0.95,0.038,0.1,-0.064,0.099,-0.0028,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 +34190000,-0.3,0.015,-0.0054,0.95,0.039,0.098,-0.061,0.094,-0.014,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 +34290000,-0.3,0.015,-0.0053,0.95,0.04,0.1,-0.06,0.098,-0.0048,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 +34390000,-0.3,0.015,-0.0052,0.95,0.042,0.097,-0.055,0.093,-0.016,-0.049,-0.0013,-0.0057,-3.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 +34490000,-0.3,0.015,-0.0052,0.95,0.045,0.1,-0.053,0.097,-0.0069,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 +34590000,-0.3,0.014,-0.0051,0.95,0.045,0.098,0.74,0.092,-0.021,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 +34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 +34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38 +34890000,-0.3,0.014,-0.0051,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41 diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp index fe2c3a88ff7c..148f30cfe427 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp @@ -240,16 +240,6 @@ bool EkfWrapper::isWindVelocityEstimated() const return _ekf->control_status_flags().wind; } -void EkfWrapper::enableTerrainRngFusion() -{ - _ekf_params->terrain_fusion_mode |= TerrainFusionMask::TerrainFuseRangeFinder; -} - -void EkfWrapper::disableTerrainRngFusion() -{ - _ekf_params->terrain_fusion_mode &= ~TerrainFusionMask::TerrainFuseRangeFinder; -} - bool EkfWrapper::isIntendingTerrainRngFusion() const { terrain_fusion_status_u terrain_status; @@ -257,16 +247,6 @@ bool EkfWrapper::isIntendingTerrainRngFusion() const return terrain_status.flags.range_finder; } -void EkfWrapper::enableTerrainFlowFusion() -{ - _ekf_params->terrain_fusion_mode |= TerrainFusionMask::TerrainFuseOpticalFlow; -} - -void EkfWrapper::disableTerrainFlowFusion() -{ - _ekf_params->terrain_fusion_mode &= ~TerrainFusionMask::TerrainFuseOpticalFlow; -} - bool EkfWrapper::isIntendingTerrainFlowFusion() const { terrain_fusion_status_u terrain_status; diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h index e1d35f093408..69b72475dca9 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h @@ -110,12 +110,8 @@ class EkfWrapper bool isWindVelocityEstimated() const; - void enableTerrainRngFusion(); - void disableTerrainRngFusion(); bool isIntendingTerrainRngFusion() const; - void enableTerrainFlowFusion(); - void disableTerrainFlowFusion(); bool isIntendingTerrainFlowFusion() const; Eulerf getEulerAngles() const; diff --git a/src/modules/ekf2/test/test_EKF_flow.cpp b/src/modules/ekf2/test/test_EKF_flow.cpp index f39249190ada..42f27028a04c 100644 --- a/src/modules/ekf2/test/test_EKF_flow.cpp +++ b/src/modules/ekf2/test/test_EKF_flow.cpp @@ -120,7 +120,7 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir) _sensor_simulator.runSeconds(5.f); - const float estimated_distance_to_ground = _ekf->getTerrainVertPos(); + const float estimated_distance_to_ground = _ekf->getHagl(); EXPECT_FLOAT_EQ(estimated_distance_to_ground, simulated_distance_to_ground); reset_logging_checker.capturePreResetState(); @@ -133,10 +133,7 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir) _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); // THEN: estimated velocity should match simulated velocity const Vector3f estimated_velocity = _ekf->getVelocity(); @@ -144,7 +141,11 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir) simulated_velocity.print(); EXPECT_TRUE(isEqual(estimated_velocity, simulated_velocity)) << "estimated vel = " << estimated_velocity(0) << ", " - << estimated_velocity(1); + << estimated_velocity(1) << "\n" + << "simulated vel = " << simulated_velocity(0) << ", " + << simulated_velocity(1); + + EXPECT_NEAR(simulated_distance_to_ground, _ekf->getHagl(), 0.1f); // AND: the reset in velocity should be saved correctly reset_logging_checker.capturePostResetState(); @@ -158,7 +159,7 @@ TEST_F(EkfFlowTest, resetToFlowVelocityOnGround) ResetLoggingChecker reset_logging_checker(_ekf); // WHEN: being on ground - const float estimated_distance_to_ground = _ekf->getTerrainVertPos(); + const float estimated_distance_to_ground = _ekf->getHagl(); EXPECT_LT(estimated_distance_to_ground, 0.3f); reset_logging_checker.capturePreResetState(); @@ -177,11 +178,10 @@ TEST_F(EkfFlowTest, resetToFlowVelocityOnGround) EXPECT_TRUE(isEqual(estimated_horz_velocity, Vector2f(0.f, 0.f))) << estimated_horz_velocity(0) << ", " << estimated_horz_velocity(1); - // AND: the reset in velocity should be saved correctly + // AND: the velocity isn't reset as it is already correct reset_logging_checker.capturePostResetState(); - EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1)); + EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(0)); EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); - EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-9f)); } TEST_F(EkfFlowTest, inAirConvergence) @@ -222,9 +222,9 @@ TEST_F(EkfFlowTest, inAirConvergence) // THEN: estimated velocity should converge to the simulated velocity // This takes a bit of time because the data is inconsistent with IMU measurements estimated_velocity = _ekf->getVelocity(); - EXPECT_NEAR(estimated_velocity(0), simulated_velocity(0), 0.05f) + EXPECT_NEAR(estimated_velocity(0), simulated_velocity(0), 0.01f) << "estimated vel = " << estimated_velocity(0); - EXPECT_NEAR(estimated_velocity(1), simulated_velocity(1), 0.05f) + EXPECT_NEAR(estimated_velocity(1), simulated_velocity(1), 0.01f) << estimated_velocity(1); } diff --git a/src/modules/ekf2/test/test_EKF_flow_generated.cpp b/src/modules/ekf2/test/test_EKF_flow_generated.cpp new file mode 100644 index 000000000000..58a0eabdeb6a --- /dev/null +++ b/src/modules/ekf2/test/test_EKF_flow_generated.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 +#include +#include "EKF/ekf.h" +#include "test_helper/comparison_helper.h" + +#include "../EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h" +#include "../EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h" + +using namespace matrix; + +TEST(FlowGenerated, distBottom0xy) +{ + // GIVEN: 0 distance to the ground (singularity) + StateSample state{}; + state.quat_nominal = Quatf(); + + const float R = sq(radians(sq(0.5f))); + SquareMatrixState P = createRandomCovarianceMatrix(); + + VectorState H; + Vector2f innov_var; + sym::ComputeFlowXyInnovVarAndHx(state.vector(), P, R, FLT_EPSILON, &innov_var, &H); + EXPECT_GT(innov_var(0), 1e12); + EXPECT_GT(innov_var(1), 1e12); +} + +TEST(FlowGenerated, distBottom0y) +{ + // GIVEN: 0 distance to the ground (singularity) + StateSample state{}; + state.quat_nominal = Quatf(); + + const float R = sq(radians(sq(0.5f))); + SquareMatrixState P = createRandomCovarianceMatrix(); + + VectorState H; + float innov_var; + sym::ComputeFlowYInnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var, &H); + EXPECT_GT(innov_var, 1e12); +} diff --git a/src/modules/ekf2/test/test_EKF_height_fusion.cpp b/src/modules/ekf2/test/test_EKF_height_fusion.cpp index 329015dc4a40..c80939f1ba6e 100644 --- a/src/modules/ekf2/test/test_EKF_height_fusion.cpp +++ b/src/modules/ekf2/test/test_EKF_height_fusion.cpp @@ -60,6 +60,7 @@ class EkfHeightFusionTest : public ::testing::Test { _ekf->init(0); _ekf_wrapper.disableBaroHeightFusion(); + _ekf_wrapper.disableRangeHeightFusion(); _sensor_simulator.runSeconds(0.1); _ekf->set_in_air_status(false); _ekf->set_vehicle_at_rest(true); @@ -111,7 +112,7 @@ TEST_F(EkfHeightFusionTest, baroRef) EXPECT_FALSE(_ekf_wrapper.isIntendingExternalVisionHeightFusion()); // AND WHEN: the baro data increases - const float baro_increment = 5.f; + const float baro_increment = 4.f; _sensor_simulator._baro.setData(_sensor_simulator._baro.getData() + baro_increment); _sensor_simulator.runSeconds(60); @@ -124,8 +125,8 @@ TEST_F(EkfHeightFusionTest, baroRef) const BiasEstimator::status &gps_status = _ekf->getGpsHgtBiasEstimatorStatus(); EXPECT_NEAR(gps_status.bias, -baro_increment, 0.2f); - const BiasEstimator::status &rng_status = _ekf->getRngHgtBiasEstimatorStatus(); - EXPECT_NEAR(rng_status.bias, -baro_increment, 1.2f); + const float terrain = _ekf->getTerrainVertPos(); + EXPECT_NEAR(terrain, -baro_increment, 1.2f); const BiasEstimator::status &ev_status = _ekf->getEvHgtBiasEstimatorStatus(); EXPECT_EQ(ev_status.bias, 0.f); @@ -150,8 +151,8 @@ TEST_F(EkfHeightFusionTest, baroRef) // the estimated height follows the GPS height EXPECT_NEAR(_ekf->getPosition()(2), -(baro_increment + gps_increment), 0.3f); // and the range finder bias is adjusted to follow the new reference - const BiasEstimator::status &rng_status_2 = _ekf->getRngHgtBiasEstimatorStatus(); - EXPECT_NEAR(rng_status_2.bias, -(baro_increment + gps_increment), 1.3f); + const float terrain2 = _ekf->getTerrainVertPos(); + EXPECT_NEAR(terrain2, -(baro_increment + gps_increment), 1.3f); } TEST_F(EkfHeightFusionTest, gpsRef) @@ -181,8 +182,8 @@ TEST_F(EkfHeightFusionTest, gpsRef) const BiasEstimator::status &baro_status = _ekf->getBaroBiasEstimatorStatus(); EXPECT_NEAR(baro_status.bias, baro_initial + baro_increment, 1.3f); - const BiasEstimator::status &rng_status = _ekf->getRngHgtBiasEstimatorStatus(); - EXPECT_NEAR(rng_status.bias, 0.f, 1.1f); // TODO: why? + const float terrain = _ekf->getTerrainVertPos(); + EXPECT_NEAR(terrain, 0.f, 1.1f); // TODO: why? // BUT WHEN: the GPS jumps by a lot const float gps_step = 100.f; @@ -290,7 +291,7 @@ TEST_F(EkfHeightFusionTest, changeEkfOriginAlt) reset_logging_checker.capturePostResetState(); EXPECT_NEAR(_ekf->getBaroBiasEstimatorStatus().bias, _sensor_simulator._baro.getData() + alt_increment, 0.2f); - EXPECT_NEAR(_ekf->getRngHgtBiasEstimatorStatus().bias, alt_increment, 1.f); + EXPECT_NEAR(_ekf->getTerrainVertPos(), alt_increment, 1.f); EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); } diff --git a/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp b/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp index ccd7dbc76a6b..e07d4e8d5d73 100644 --- a/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp +++ b/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp @@ -116,18 +116,22 @@ class EkfTerrainTest : public ::testing::Test TEST_F(EkfTerrainTest, setFlowAndRangeTerrainFusion) { + // GIVEN: flow and range are enabled + _ekf_wrapper.enableFlowFusion(); + _ekf_wrapper.enableRangeHeightFusion(); + // WHEN: simulate being 5m above ground const float simulated_distance_to_ground = 1.f; runFlowAndRngScenario(simulated_distance_to_ground, simulated_distance_to_ground); - // THEN: By default, both rng and flow aiding are active + // THEN: both should start terrain aiding EXPECT_TRUE(_ekf_wrapper.isIntendingTerrainRngFusion()); - EXPECT_FALSE(_ekf_wrapper.isIntendingTerrainFlowFusion()); - const float estimated_distance_to_ground = _ekf->getTerrainVertPos(); - EXPECT_NEAR(estimated_distance_to_ground, simulated_distance_to_ground, 0.01); + EXPECT_TRUE(_ekf_wrapper.isIntendingTerrainFlowFusion()); + const float estimated_distance_to_ground = _ekf->getHagl(); + EXPECT_NEAR(estimated_distance_to_ground, simulated_distance_to_ground, 0.02); // WHEN: rng fusion is disabled - _ekf_wrapper.disableTerrainRngFusion(); + _ekf_wrapper.disableRangeHeightFusion(); _sensor_simulator.runSeconds(5.1); // THEN: rng fusion should be disabled and flow fusion should take over @@ -135,7 +139,7 @@ TEST_F(EkfTerrainTest, setFlowAndRangeTerrainFusion) EXPECT_TRUE(_ekf_wrapper.isIntendingTerrainFlowFusion()); // WHEN: flow is now diabled - _ekf_wrapper.disableTerrainFlowFusion(); + _ekf_wrapper.disableFlowFusion(); _sensor_simulator.runSeconds(0.2); // THEN: flow is now also disabled @@ -146,8 +150,8 @@ TEST_F(EkfTerrainTest, setFlowAndRangeTerrainFusion) TEST_F(EkfTerrainTest, testFlowForTerrainFusion) { // GIVEN: flow for terrain enabled but not range finder - _ekf_wrapper.enableTerrainFlowFusion(); - _ekf_wrapper.disableTerrainRngFusion(); + _ekf_wrapper.enableFlowFusion(); + _ekf_wrapper.disableRangeHeightFusion(); // WHEN: the sensors do not agree const float rng_height = 1.f; @@ -158,16 +162,17 @@ TEST_F(EkfTerrainTest, testFlowForTerrainFusion) // should converge to the simulated height EXPECT_FALSE(_ekf_wrapper.isIntendingTerrainRngFusion()); EXPECT_TRUE(_ekf_wrapper.isIntendingTerrainFlowFusion()); + EXPECT_TRUE(_ekf->isTerrainEstimateValid()); - const float estimated_distance_to_ground = _ekf->getTerrainVertPos(); - EXPECT_NEAR(estimated_distance_to_ground, flow_height, 0.5f); + const float estimated_distance_to_ground = _ekf->getHagl(); + EXPECT_NEAR(estimated_distance_to_ground, flow_height, 0.9f); } TEST_F(EkfTerrainTest, testRngForTerrainFusion) { // GIVEN: rng for terrain but not flow - _ekf_wrapper.disableTerrainFlowFusion(); - _ekf_wrapper.enableTerrainRngFusion(); + _ekf_wrapper.disableFlowFusion(); + _ekf_wrapper.enableRangeHeightFusion(); // WHEN: the sensors do not agree const float rng_height = 1.f; @@ -178,22 +183,23 @@ TEST_F(EkfTerrainTest, testRngForTerrainFusion) // should converge to the simulated height EXPECT_TRUE(_ekf_wrapper.isIntendingTerrainRngFusion()); EXPECT_FALSE(_ekf_wrapper.isIntendingTerrainFlowFusion()); + EXPECT_TRUE(_ekf->isTerrainEstimateValid()); - const float estimated_distance_to_ground = _ekf->getTerrainVertPos(); + const float estimated_distance_to_ground = _ekf->getHagl(); EXPECT_NEAR(estimated_distance_to_ground, rng_height, 0.01f); } TEST_F(EkfTerrainTest, testHeightReset) { // GIVEN: rng for terrain but not flow - _ekf_wrapper.disableTerrainFlowFusion(); - _ekf_wrapper.enableTerrainRngFusion(); + _ekf_wrapper.disableFlowFusion(); + _ekf_wrapper.enableRangeHeightFusion(); const float rng_height = 1.f; const float flow_height = 1.f; runFlowAndRngScenario(rng_height, flow_height); - const float estimated_distance_to_ground = _ekf->getTerrainVertPos() - _ekf->getPosition()(2); + const float estimated_distance_to_ground = _ekf->getHagl(); ResetLoggingChecker reset_logging_checker(_ekf); reset_logging_checker.capturePreResetState(); @@ -207,5 +213,5 @@ TEST_F(EkfTerrainTest, testHeightReset) // THEN: a height reset occured and the estimated distance to the ground remains constant reset_logging_checker.capturePostResetState(); EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); - EXPECT_NEAR(estimated_distance_to_ground, _ekf->getTerrainVertPos() - _ekf->getPosition()(2), 1e-3f); + EXPECT_NEAR(estimated_distance_to_ground, _ekf->getHagl(), 1e-3f); } diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 9452cebd2dfc..fedadaf47458 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -165,7 +165,6 @@ void LoggedTopics::add_default_topics() // always add the first instance add_topic("estimator_baro_bias", 500); add_topic("estimator_gnss_hgt_bias", 500); - add_topic("estimator_rng_hgt_bias", 500); add_topic("estimator_ev_pos_bias", 500); add_topic("estimator_event_flags", 0); add_topic("estimator_gps_status", 1000); @@ -181,7 +180,6 @@ void LoggedTopics::add_default_topics() add_optional_topic_multi("estimator_baro_bias", 500, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_gnss_hgt_bias", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_rng_hgt_bias", 500, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_ev_pos_bias", 500, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_event_flags", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_gps_status", 1000, MAX_ESTIMATOR_INSTANCES); @@ -209,7 +207,6 @@ void LoggedTopics::add_default_topics() // add_optional_topic_multi("estimator_aid_src_gnss_pos", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_mag", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_optical_flow", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_terrain_optical_flow", 100, MAX_ESTIMATOR_INSTANCES); // add_optional_topic_multi("estimator_aid_src_ev_yaw", 100, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_aux_global_position", 100, MAX_ESTIMATOR_INSTANCES); @@ -267,7 +264,6 @@ void LoggedTopics::add_default_topics() // EKF replay add_topic("estimator_baro_bias"); add_topic("estimator_gnss_hgt_bias"); - add_topic("estimator_rng_hgt_bias"); add_topic("estimator_ev_pos_bias"); add_topic("estimator_event_flags"); add_topic("estimator_gps_status"); @@ -301,8 +297,6 @@ void LoggedTopics::add_default_topics() add_optional_topic_multi("estimator_aid_src_gravity", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_mag", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_optical_flow", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_terrain_optical_flow", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_terrain_range_finder", 0, MAX_ESTIMATOR_INSTANCES); add_optional_topic_multi("estimator_aid_src_sideslip", 0, MAX_ESTIMATOR_INSTANCES); #endif /* CONFIG_ARCH_BOARD_PX4_SITL */ From 9001c23926477e215e646efc90f235e5e23d3277 Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 20 Jun 2024 14:42:33 +0200 Subject: [PATCH 398/652] ekf2: clean up hagl vs terrain naming Terrain is the state: terrain vertical position Hagl (height above ground level) is the vertical distance between the vertical position and the terrain vertical position --- .../optical_flow/optical_flow_control.cpp | 6 ++--- .../range_finder/range_height_control.cpp | 22 +++++++------------ src/modules/ekf2/EKF/control.cpp | 4 ++++ src/modules/ekf2/EKF/covariance.cpp | 5 +++++ src/modules/ekf2/EKF/ekf.cpp | 14 +++++------- src/modules/ekf2/EKF/ekf.h | 17 +++++--------- src/modules/ekf2/EKF/height_control.cpp | 2 +- .../terrain_estimator/terrain_estimator.cpp | 13 ++++------- src/modules/ekf2/Kconfig | 1 - 9 files changed, 36 insertions(+), 48 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 ec2aec1ba4fd..27e05af75666 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 @@ -133,7 +133,7 @@ void Ekf::startFlowFusion() fuseOptFlow(_hagl_sensor_status.flags.flow); } else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) { - resetHaglFlow(); + resetTerrainToFlow(); } else { ECL_INFO("optical flow fusion failed to start"); @@ -146,7 +146,7 @@ void Ekf::startFlowFusion() resetFlowFusion(); } else if (_hagl_sensor_status.flags.flow) { - resetHaglFlow(); + resetTerrainToFlow(); } } @@ -172,7 +172,7 @@ void Ekf::resetFlowFusion() _aid_src_optical_flow.time_last_fuse = _time_delayed_us; } -void Ekf::resetHaglFlow() +void Ekf::resetTerrainToFlow() { ECL_INFO("reset hagl to flow"); // TODO: use the flow data 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 d085579956bc..104ec47d9190 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 @@ -39,7 +39,7 @@ #include "ekf.h" #include "ekf_derivation/generated/compute_hagl_innov_var.h" -void Ekf::controlRangeHeightFusion() +void Ekf::controlRangeHaglFusion() { static constexpr const char *HGT_SRC_NAME = "RNG"; @@ -97,7 +97,7 @@ void Ekf::controlRangeHeightFusion() if (rng_data_ready && _range_sensor.getSampleAddress()) { - updateRangeHeight(aid_src); + updateRangeHagl(aid_src); const bool measurement_valid = PX4_ISFINITE(aid_src.observation) && PX4_ISFINITE(aid_src.observation_variance); const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast(RngCtrl::ENABLED)) @@ -136,7 +136,7 @@ void Ekf::controlRangeHeightFusion() stopRngTerrFusion(); if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) { - resetHaglRng(aid_src); + resetTerrainToRng(aid_src); } } else if (do_range_aid) { @@ -160,7 +160,7 @@ void Ekf::controlRangeHeightFusion() _control_status.flags.rng_hgt = true; if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) { - resetHaglRng(aid_src); + resetTerrainToRng(aid_src); } } } @@ -193,7 +193,7 @@ void Ekf::controlRangeHeightFusion() stopRngTerrFusion(); } else { - resetHaglRng(aid_src); + resetTerrainToRng(aid_src); } } @@ -213,7 +213,7 @@ void Ekf::controlRangeHeightFusion() } else { if (aid_src.innovation_rejected) { - resetHaglRng(aid_src); + resetTerrainToRng(aid_src); } _hagl_sensor_status.flags.range_finder = true; @@ -230,7 +230,7 @@ void Ekf::controlRangeHeightFusion() } } -void Ekf::updateRangeHeight(estimator_aid_source1d_s &aid_src) +void Ekf::updateRangeHagl(estimator_aid_source1d_s &aid_src) { aid_src.observation = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance); aid_src.innovation = getHagl() - aid_src.observation; @@ -266,7 +266,7 @@ float Ekf::getRngVar() const 0.f); } -void Ekf::resetHaglRng(estimator_aid_source1d_s &aid_src) +void Ekf::resetTerrainToRng(estimator_aid_source1d_s &aid_src) { _state.terrain = _state.pos(2) + aid_src.observation; P.uncorrelateCovarianceSetVariance(State::terrain.idx, aid_src.observation_variance); @@ -277,8 +277,6 @@ void Ekf::resetHaglRng(estimator_aid_source1d_s &aid_src) bool Ekf::isConditionalRangeAidSuitable() { -#if defined(CONFIG_EKF2_TERRAIN) - // check if we can use range finder measurements to estimate height, use hysteresis to avoid rapid switching // Note that the 0.7 coefficients and the innovation check are arbitrary values but work well in practice float range_hagl_max = _params.max_hagl_for_range_aid; @@ -303,10 +301,6 @@ bool Ekf::isConditionalRangeAidSuitable() } return is_in_range && is_hagl_stable && is_below_max_speed; - -#endif // CONFIG_EKF2_TERRAIN - - return false; } void Ekf::stopRngHgtFusion() diff --git a/src/modules/ekf2/EKF/control.cpp b/src/modules/ekf2/EKF/control.cpp index 34d26273e78b..5215570d14c7 100644 --- a/src/modules/ekf2/EKF/control.cpp +++ b/src/modules/ekf2/EKF/control.cpp @@ -144,6 +144,10 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) // Additional horizontal velocity data from an auxiliary sensor can be fused controlAuxVelFusion(); #endif // CONFIG_EKF2_AUXVEL + // +#if defined(CONFIG_EKF2_TERRAIN) + controlTerrainFakeFusion(); +#endif // CONFIG_EKF2_TERRAIN controlZeroInnovationHeadingUpdate(); diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 2310e644a036..60a865d2dea2 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -99,6 +99,11 @@ void Ekf::initialiseCovariance() #if defined(CONFIG_EKF2_WIND) resetWindCov(); #endif // CONFIG_EKF2_WIND + +#if defined(CONFIG_EKF2_TERRAIN) + // use the ground clearance value as our uncertainty + P.uncorrelateCovarianceSetVariance(State::terrain.idx, sq(_params.rng_gnd_clearance)); +#endif // CONFIG_EKF2_TERRAIN } void Ekf::predictCovariance(const imuSample &imu_delayed) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 61036e4bc7fb..c16ca24476cc 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -71,6 +71,11 @@ void Ekf::reset() #if defined(CONFIG_EKF2_WIND) _state.wind_vel.setZero(); #endif // CONFIG_EKF2_WIND + // +#if defined(CONFIG_EKF2_TERRAIN) + // assume a ground clearance + _state.terrain = _state.pos(2) + _params.rng_gnd_clearance; +#endif // CONFIG_EKF2_TERRAIN #if defined(CONFIG_EKF2_RANGE_FINDER) _range_sensor.setPitchOffset(_params.rng_sens_pitch); @@ -160,10 +165,6 @@ bool Ekf::update() // control fusion of observation data controlFusionModes(imu_sample_delayed); -#if defined(CONFIG_EKF2_TERRAIN) - runTerrainEstimator(imu_sample_delayed); -#endif // CONFIG_EKF2_TERRAIN - _output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, _state.gyro_bias, _state.accel_bias); return true; @@ -199,11 +200,6 @@ bool Ekf::initialiseFilter() // initialise the state covariance matrix now we have starting values for all the states initialiseCovariance(); -#if defined(CONFIG_EKF2_TERRAIN) - // Initialise the terrain state - initHagl(); -#endif // CONFIG_EKF2_TERRAIN - // reset the output predictor state history to match the EKF initial values _output_predictor.alignOutputFilter(_state.quat_nominal, _state.vel, _state.pos); diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index ac953e570bc3..46e03bcaaef4 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -807,32 +807,27 @@ class Ekf final : public EstimatorInterface bool fuseVelocity(estimator_aid_source3d_s &vel_aid_src); #if defined(CONFIG_EKF2_TERRAIN) - // terrain vertical position estimator - void initHagl(); - void runTerrainEstimator(const imuSample &imu_delayed); - + void initTerrain(); float getTerrainVPos() const { return isTerrainEstimateValid() ? _state.terrain : _last_on_ground_posD; } - - void controlHaglFakeFusion(); + void controlTerrainFakeFusion(); # if defined(CONFIG_EKF2_RANGE_FINDER) // update the terrain vertical position estimate using a height above ground measurement from the range finder bool fuseHaglRng(estimator_aid_source1d_s &aid_src, bool update_height, bool update_terrain); - void updateRangeHeight(estimator_aid_source1d_s &aid_src); - void resetHaglRng(estimator_aid_source1d_s &aid_src); + void updateRangeHagl(estimator_aid_source1d_s &aid_src); + void resetTerrainToRng(estimator_aid_source1d_s &aid_src); float getRngVar() const; # endif // CONFIG_EKF2_RANGE_FINDER # if defined(CONFIG_EKF2_OPTICAL_FLOW) - // update the terrain vertical position estimate using an optical flow measurement - void resetHaglFlow(); + void resetTerrainToFlow(); # endif // CONFIG_EKF2_OPTICAL_FLOW #endif // CONFIG_EKF2_TERRAIN #if defined(CONFIG_EKF2_RANGE_FINDER) // range height - void controlRangeHeightFusion(); + void controlRangeHaglFusion(); bool isConditionalRangeAidSuitable(); void stopRngHgtFusion(); void stopRngTerrFusion(); diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index d81c2848386d..aad5c286b8d3 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -53,7 +53,7 @@ void Ekf::controlHeightFusion(const imuSample &imu_delayed) #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_RANGE_FINDER) - controlRangeHeightFusion(); + controlRangeHaglFusion(); #endif // CONFIG_EKF2_RANGE_FINDER checkHeightSensorRefFallback(); diff --git a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp index ea6a4259d106..2afafce2d0f7 100644 --- a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp +++ b/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp @@ -42,7 +42,7 @@ #include -void Ekf::initHagl() +void Ekf::initTerrain() { // assume a ground clearance _state.terrain = _state.pos(2) + _params.rng_gnd_clearance; @@ -51,7 +51,7 @@ void Ekf::initHagl() P.uncorrelateCovarianceSetVariance(State::terrain.idx, sq(_params.rng_gnd_clearance)); } -void Ekf::runTerrainEstimator(const imuSample &imu_delayed) +void Ekf::controlTerrainFakeFusion() { // If we are on ground, store the local position and time to use as a reference if (!_control_status.flags.in_air) { @@ -62,14 +62,9 @@ void Ekf::runTerrainEstimator(const imuSample &imu_delayed) // Let the estimator run freely before arming for bench testing purposes, but reset on takeoff // because when using optical flow measurements, it is safer to start with a small distance to ground // as an overestimated distance leads to an overestimated velocity, causing a dangerous behavior. - initHagl(); + initTerrain(); } - controlHaglFakeFusion(); -} - -void Ekf::controlHaglFakeFusion() -{ if (!_control_status.flags.in_air && !_hagl_sensor_status.flags.range_finder && !_hagl_sensor_status.flags.flow) { @@ -85,7 +80,7 @@ void Ekf::controlHaglFakeFusion() #endif // CONFIG_EKF2_OPTICAL_FLOW if (_control_status.flags.vehicle_at_rest || !recent_terrain_aiding) { - initHagl(); + initTerrain(); } } } diff --git a/src/modules/ekf2/Kconfig b/src/modules/ekf2/Kconfig index a1899344154f..93f96a656c1e 100644 --- a/src/modules/ekf2/Kconfig +++ b/src/modules/ekf2/Kconfig @@ -110,7 +110,6 @@ depends on MODULES_EKF2 bool "optical flow fusion support" default y select EKF2_TERRAIN - depends on EKF2_RANGE_FINDER ---help--- EKF2 optical flow fusion support. From 7903ddf5df301361b2c24471df39a25921805a63 Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 20 Jun 2024 14:57:06 +0200 Subject: [PATCH 399/652] ekf2-terrain: terrain is not a separate estimator --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../optical_flow/optical_flow_fusion.cpp | 6 -- ...rain_estimator.cpp => terrain_control.cpp} | 4 +- .../derivation_terrain_estimator.py | 99 ------------------- ...err_est_compute_flow_xy_innov_var_and_hx.h | 66 ------------- .../terr_est_compute_flow_y_innov_var_and_h.h | 65 ------------ src/modules/ekf2/test/CMakeLists.txt | 2 +- ...ain_estimator.cpp => test_EKF_terrain.cpp} | 3 +- 9 files changed, 5 insertions(+), 244 deletions(-) rename src/modules/ekf2/EKF/{terrain_estimator/terrain_estimator.cpp => terrain_control.cpp} (96%) delete mode 100755 src/modules/ekf2/EKF/terrain_estimator/derivation/derivation_terrain_estimator.py delete mode 100644 src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h delete mode 100644 src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h rename src/modules/ekf2/test/{test_EKF_terrain_estimator.cpp => test_EKF_terrain.cpp} (98%) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 6d0f72dcbd68..3f5d9d142f36 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -213,7 +213,7 @@ if(CONFIG_EKF2_SIDESLIP) endif() if(CONFIG_EKF2_TERRAIN) - list(APPEND EKF_SRCS EKF/terrain_estimator/terrain_estimator.cpp) + list(APPEND EKF_SRCS EKF/terrain_control.cpp) endif() add_subdirectory(EKF) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index bd9770c9014f..1134d1942b12 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -135,7 +135,7 @@ if(CONFIG_EKF2_SIDESLIP) endif() if(CONFIG_EKF2_TERRAIN) - list(APPEND EKF_SRCS terrain_estimator/terrain_estimator.cpp) + list(APPEND EKF_SRCS terrain_control.cpp) endif() include_directories(${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index bfed5a7fa1b4..8cd8f559f2a4 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -33,12 +33,6 @@ /** * @file optflow_fusion.cpp - * Function for fusing gps and baro measurements/ - * equations generated using EKF/python/ekf_derivation/main.py - * - * @author Paul Riseborough - * @author Siddharth Bharat Purohit - * */ #include "ekf.h" diff --git a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp b/src/modules/ekf2/EKF/terrain_control.cpp similarity index 96% rename from src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp rename to src/modules/ekf2/EKF/terrain_control.cpp index 2afafce2d0f7..4de72ddd490e 100644 --- a/src/modules/ekf2/EKF/terrain_estimator/terrain_estimator.cpp +++ b/src/modules/ekf2/EKF/terrain_control.cpp @@ -32,9 +32,7 @@ ****************************************************************************/ /** - * @file terrain_estimator.cpp - * Function for fusing rangefinder and optical flow measurements - * to estimate terrain vertical position + * @file terrain_control.cpp */ #include "ekf.h" diff --git a/src/modules/ekf2/EKF/terrain_estimator/derivation/derivation_terrain_estimator.py b/src/modules/ekf2/EKF/terrain_estimator/derivation/derivation_terrain_estimator.py deleted file mode 100755 index 8ecba2c03ebd..000000000000 --- a/src/modules/ekf2/EKF/terrain_estimator/derivation/derivation_terrain_estimator.py +++ /dev/null @@ -1,99 +0,0 @@ -#!/usr/bin/env python3 -# -*- coding: utf-8 -*- -""" - Copyright (c) 2023-2024 PX4 Development Team - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions - are met: - - 1. Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in - the documentation and/or other materials provided with the - distribution. - 3. Neither the name PX4 nor the names of its contributors may be - used to endorse or promote products derived from this software - without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - POSSIBILITY OF SUCH DAMAGE. - -File: derivation_terrain_estimator.py -Description: -""" - -import symforce -symforce.set_epsilon_to_symbol() - -import symforce.symbolic as sf - -# generate_px4_function from derivation_utils in EKF/ekf_derivation/utils -import os, sys -derivation_utils_dir = os.path.dirname(os.path.abspath(__file__)) + "/../../python/ekf_derivation/utils" -sys.path.append(derivation_utils_dir) -import derivation_utils - -def predict_opt_flow( - terrain_vpos: sf.Scalar, - q_att: sf.V4, - v: sf.V3, - pos_z: sf.Scalar, - epsilon : sf.Scalar -): - R_to_earth = sf.Rot3(sf.Quaternion(xyz=q_att[1:4], w=q_att[0])).to_rotation_matrix() - flow_pred = sf.V2() - dist = - (pos_z - terrain_vpos) - dist = derivation_utils.add_epsilon_sign(dist, dist, epsilon) - flow_pred[0] = -v[1] / dist * R_to_earth[2, 2] - flow_pred[1] = v[0] / dist * R_to_earth[2, 2] - return flow_pred - -def terr_est_compute_flow_xy_innov_var_and_hx( - terrain_vpos: sf.Scalar, - P: sf.Scalar, - q_att: sf.V4, - v: sf.V3, - pos_z: sf.Scalar, - R: sf.Scalar, - epsilon : sf.Scalar -): - flow_pred = predict_opt_flow(terrain_vpos, q_att, v, pos_z, epsilon) - Hx = sf.V1(flow_pred[0]).jacobian(terrain_vpos) - Hy = sf.V1(flow_pred[1]).jacobian(terrain_vpos) - - innov_var = sf.V2() - innov_var[0] = (Hx * P * Hx.T + R)[0,0] - innov_var[1] = (Hy * P * Hy.T + R)[0,0] - - return (innov_var, Hx[0, 0]) - -def terr_est_compute_flow_y_innov_var_and_h( - terrain_vpos: sf.Scalar, - P: sf.Scalar, - q_att: sf.V4, - v: sf.V3, - pos_z: sf.Scalar, - R: sf.Scalar, - epsilon : sf.Scalar -): - flow_pred = predict_opt_flow(terrain_vpos, q_att, v, pos_z, epsilon) - Hy = sf.V1(flow_pred[1]).jacobian(terrain_vpos) - - innov_var = (Hy * P * Hy.T + R)[0,0] - - return (innov_var, Hy[0, 0]) - -print("Derive terrain estimator equations...") -derivation_utils.generate_px4_function(terr_est_compute_flow_xy_innov_var_and_hx, output_names=["innov_var", "H"]) -derivation_utils.generate_px4_function(terr_est_compute_flow_y_innov_var_and_h, output_names=["innov_var", "H"]) diff --git a/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h b/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h deleted file mode 100644 index 6b82a6534f74..000000000000 --- a/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_xy_innov_var_and_hx.h +++ /dev/null @@ -1,66 +0,0 @@ -// ----------------------------------------------------------------------------- -// This file was autogenerated by symforce from template: -// function/FUNCTION.h.jinja -// Do NOT modify by hand. -// ----------------------------------------------------------------------------- - -#pragma once - -#include - -namespace sym { - -/** - * This function was autogenerated from a symbolic function. Do not modify by hand. - * - * Symbolic function: terr_est_compute_flow_xy_innov_var_and_hx - * - * Args: - * terrain_vpos: Scalar - * P: Scalar - * q_att: Matrix41 - * v: Matrix31 - * pos_z: Scalar - * R: Scalar - * epsilon: Scalar - * - * Outputs: - * innov_var: Matrix21 - * H: Scalar - */ -template -void TerrEstComputeFlowXyInnovVarAndHx(const Scalar terrain_vpos, const Scalar P, - const matrix::Matrix& q_att, - const matrix::Matrix& v, const Scalar pos_z, - const Scalar R, const Scalar epsilon, - matrix::Matrix* const innov_var = nullptr, - Scalar* const H = nullptr) { - // Total ops: 27 - - // Input arrays - - // Intermediate terms (4) - const Scalar _tmp0 = - -2 * std::pow(q_att(1, 0), Scalar(2)) - 2 * std::pow(q_att(2, 0), Scalar(2)) + 1; - const Scalar _tmp1 = pos_z - terrain_vpos; - const Scalar _tmp2 = - -_tmp1 + epsilon * (2 * math::min(0, -(((_tmp1) > 0) - ((_tmp1) < 0))) + 1); - const Scalar _tmp3 = P * std::pow(_tmp0, Scalar(2)) / std::pow(_tmp2, Scalar(4)); - - // Output terms (2) - if (innov_var != nullptr) { - matrix::Matrix& _innov_var = (*innov_var); - - _innov_var(0, 0) = R + _tmp3 * std::pow(v(1, 0), Scalar(2)); - _innov_var(1, 0) = R + _tmp3 * std::pow(v(0, 0), Scalar(2)); - } - - if (H != nullptr) { - Scalar& _h = (*H); - - _h = _tmp0 * v(1, 0) / std::pow(_tmp2, Scalar(2)); - } -} // NOLINT(readability/fn_size) - -// NOLINTNEXTLINE(readability/fn_size) -} // namespace sym diff --git a/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h b/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h deleted file mode 100644 index 461db323cfdd..000000000000 --- a/src/modules/ekf2/EKF/terrain_estimator/derivation/generated/terr_est_compute_flow_y_innov_var_and_h.h +++ /dev/null @@ -1,65 +0,0 @@ -// ----------------------------------------------------------------------------- -// This file was autogenerated by symforce from template: -// function/FUNCTION.h.jinja -// Do NOT modify by hand. -// ----------------------------------------------------------------------------- - -#pragma once - -#include - -namespace sym { - -/** - * This function was autogenerated from a symbolic function. Do not modify by hand. - * - * Symbolic function: terr_est_compute_flow_y_innov_var_and_h - * - * Args: - * terrain_vpos: Scalar - * P: Scalar - * q_att: Matrix41 - * v: Matrix31 - * pos_z: Scalar - * R: Scalar - * epsilon: Scalar - * - * Outputs: - * innov_var: Scalar - * H: Scalar - */ -template -void TerrEstComputeFlowYInnovVarAndH(const Scalar terrain_vpos, const Scalar P, - const matrix::Matrix& q_att, - const matrix::Matrix& v, const Scalar pos_z, - const Scalar R, const Scalar epsilon, - Scalar* const innov_var = nullptr, Scalar* const H = nullptr) { - // Total ops: 25 - - // Input arrays - - // Intermediate terms (3) - const Scalar _tmp0 = - -2 * std::pow(q_att(1, 0), Scalar(2)) - 2 * std::pow(q_att(2, 0), Scalar(2)) + 1; - const Scalar _tmp1 = pos_z - terrain_vpos; - const Scalar _tmp2 = - -_tmp1 + epsilon * (2 * math::min(0, -(((_tmp1) > 0) - ((_tmp1) < 0))) + 1); - - // Output terms (2) - if (innov_var != nullptr) { - Scalar& _innov_var = (*innov_var); - - _innov_var = - P * std::pow(_tmp0, Scalar(2)) * std::pow(v(0, 0), Scalar(2)) / std::pow(_tmp2, Scalar(4)) + - R; - } - - if (H != nullptr) { - Scalar& _h = (*H); - - _h = -_tmp0 * v(0, 0) / std::pow(_tmp2, Scalar(2)); - } -} // NOLINT(readability/fn_size) - -// NOLINTNEXTLINE(readability/fn_size) -} // namespace sym diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index bb3627dedb33..424a2a208a6e 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -54,7 +54,7 @@ px4_add_unit_gtest(SRC test_EKF_mag.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_mag_declination_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_measurementSampling.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_ringbuffer.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_terrain_estimator.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) +px4_add_unit_gtest(SRC test_EKF_terrain.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_utils.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_withReplayData.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_yaw_estimator.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) diff --git a/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp b/src/modules/ekf2/test/test_EKF_terrain.cpp similarity index 98% rename from src/modules/ekf2/test/test_EKF_terrain_estimator.cpp rename to src/modules/ekf2/test/test_EKF_terrain.cpp index e07d4e8d5d73..964cd43822f4 100644 --- a/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp +++ b/src/modules/ekf2/test/test_EKF_terrain.cpp @@ -32,8 +32,7 @@ ****************************************************************************/ /** - * Test the terrain estimator - * @author Mathieu Bresciani + * Test the terrain estimate */ #include From a665764b0ea3feca23c079b545919bd958411b58 Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 20 Jun 2024 15:10:59 +0200 Subject: [PATCH 400/652] ekf2: remove unused EKF2_TERR_MASK --- .../init.d/airframes/4061_atl_mantis_edu | 1 - src/modules/ekf2/EKF/common.h | 3 --- src/modules/ekf2/EKF2.cpp | 1 - src/modules/ekf2/EKF2.hpp | 1 - src/modules/ekf2/module.yaml | 16 +--------------- 5 files changed, 1 insertion(+), 21 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index d3f48bcc0780..95df14d54ec0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -36,7 +36,6 @@ param set-default COM_RC_LOSS_T 3 # ekf2 -param set-default EKF2_TERR_MASK 1 param set-default EKF2_BARO_NOISE 2 param set-default EKF2_BCOEF_X 31.5 diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 70be1885720f..ae1d185860d9 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -382,9 +382,6 @@ struct parameters { #endif // CONFIG_EKF2_SIDESLIP #if defined(CONFIG_EKF2_TERRAIN) - int32_t terrain_fusion_mode{static_cast(TerrainFusionMask::TerrainFuseRangeFinder) - | static_cast(TerrainFusionMask::TerrainFuseOpticalFlow)}; ///< aiding source(s) selection bitmask for the terrain estimation - float terrain_p_noise{5.0f}; ///< process noise for terrain offset (m/sec) float terrain_gradient{0.5f}; ///< gradient of terrain used to estimate process noise due to changing position (m/m) const float terrain_timeout{10.f}; ///< maximum time for invalid bottom distance measurements before resetting terrain estimate (s) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 430ed52db5b0..32933b5c86bd 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -147,7 +147,6 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): _param_ekf2_min_rng(_params->rng_gnd_clearance), #endif // CONFIG_EKF2_TERRAIN || CONFIG_EKF2_OPTICAL_FLOW || CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_TERRAIN) - _param_ekf2_terr_mask(_params->terrain_fusion_mode), _param_ekf2_terr_noise(_params->terrain_p_noise), _param_ekf2_terr_grad(_params->terrain_gradient), #endif // CONFIG_EKF2_TERRAIN diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 10a51c9dcd79..fc50610fd282 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -604,7 +604,6 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem (ParamExtFloat) _param_ekf2_min_rng, #endif // CONFIG_EKF2_TERRAIN || CONFIG_EKF2_OPTICAL_FLOW || CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_TERRAIN) - (ParamExtInt) _param_ekf2_terr_mask, (ParamExtFloat) _param_ekf2_terr_noise, (ParamExtFloat) _param_ekf2_terr_grad, #endif // CONFIG_EKF2_TERRAIN diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 77a6ab547dfa..49cceb3fb0ef 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -549,8 +549,7 @@ parameters: unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing - and takeoff. To en-/disable range finder for terrain height estimation, - use EKF2_TERR_MASK instead. If this parameter is enabled then the estimator + and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in "conditional" mode. Conditional @@ -565,19 +564,6 @@ parameters: 1: Enabled (conditional mode) 2: Enabled default: 1 - EKF2_TERR_MASK: - description: - short: Integer bitmask controlling fusion sources of the terrain estimator - long: 'Set bits in the following positions to enable: 0 : Set to true to use - range finder data if available 1 : Set to true to use optical flow data - if available' - type: bitmask - bit: - 0: use range finder - 1: use optical flow - default: 3 - min: 0 - max: 3 EKF2_NOAID_TOUT: description: short: Maximum inertial dead-reckoning time From a50ef2eb5e40dce4f81e560f8612edcd3cf319e4 Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 25 Jun 2024 12:05:05 +0200 Subject: [PATCH 401/652] ekf2-terrain: make terrain validity based on uncertainty When using optical flow for terrain aiding, we cannot assume that the terrain estimate is valid if flow is fused as is can only be observed during motion. When no direct observation is available, the terrain is assumed to be valid if its 1sigma uncertainty is < 10% of the hagl. --- src/modules/ekf2/EKF/terrain_control.cpp | 15 ++--- .../test/change_indication/ekf_gsf_reset.csv | 62 +++++++++---------- .../ekf2/test/change_indication/iris_gps.csv | 28 ++++----- src/modules/ekf2/test/test_EKF_flow.cpp | 4 +- src/modules/ekf2/test/test_EKF_terrain.cpp | 4 +- 5 files changed, 54 insertions(+), 59 deletions(-) diff --git a/src/modules/ekf2/EKF/terrain_control.cpp b/src/modules/ekf2/EKF/terrain_control.cpp index 4de72ddd490e..c21b7b35d847 100644 --- a/src/modules/ekf2/EKF/terrain_control.cpp +++ b/src/modules/ekf2/EKF/terrain_control.cpp @@ -36,7 +36,7 @@ */ #include "ekf.h" -#include "ekf_derivation/generated/state.h" +#include "ekf_derivation/generated/compute_hagl_innov_var.h" #include @@ -86,23 +86,18 @@ void Ekf::controlTerrainFakeFusion() bool Ekf::isTerrainEstimateValid() const { // Assume being valid when the uncertainty is small compared to the height above ground - bool valid = getTerrainVariance() < sq(0.1f * getHagl()); + float hagl_var = INFINITY; + sym::ComputeHaglInnovVar(P, 0.f, &hagl_var); + bool valid = hagl_var < fmaxf(sq(0.1f * getHagl()), 0.2f); #if defined(CONFIG_EKF2_RANGE_FINDER) + // Assume that the terrain estimate is always valid when direct observations are fused if (_hagl_sensor_status.flags.range_finder && isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)5e6)) { valid = true; } #endif // CONFIG_EKF2_RANGE_FINDER -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - - if (_hagl_sensor_status.flags.flow && isRecent(_aid_src_optical_flow.time_last_fuse, (uint64_t)5e6)) { - valid = true; - } - -#endif // CONFIG_EKF2_OPTICAL_FLOW - return valid; } 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 07045ce2c9da..285204826673 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -358,34 +358,34 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 35590000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00042,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 35790000,0.64,-0.0065,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 -35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 -35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 -36090000,0.64,-0.0066,0.02,0.77,-3.4,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 -36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 -36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 -36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 -36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00055,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 -36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 -36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00061,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 -36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00064,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 -36890000,0.64,-0.0069,0.021,0.77,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0041,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 -36990000,0.64,-0.0069,0.021,0.77,-3.7,-4.1,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0042,-0.11,-0.2,-0.047,0.46,0.00069,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 -37090000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0064,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.44 -37190000,0.64,-0.0069,0.021,0.77,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 -37290000,0.64,-0.0069,0.021,0.77,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.7e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 -37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.017,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00071,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 -37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.067,0.0044,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 -37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.067,0.0045,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 -37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 -37790000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 -37890000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0046,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 -37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 -38090000,0.64,-0.0071,0.021,0.77,-4,-4.9,0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 -38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00079,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 -38290000,0.64,-0.0071,0.021,0.77,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0044,-0.11,-0.2,-0.047,0.46,0.00079,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 -38390000,0.64,-0.007,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 -38490000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 -38590000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.0045,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 -38690000,0.64,-0.007,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0065,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 -38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0046,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 -38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0047,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 +35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 +35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 +36090000,0.64,-0.0066,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00049,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 +36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0042,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 +36290000,0.64,-0.0066,0.02,0.77,-3.5,-3.6,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 +36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 +36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00055,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 +36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 +36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00061,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 +36790000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00064,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 +36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 +36990000,0.64,-0.0069,0.021,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0042,-0.11,-0.2,-0.047,0.46,0.00069,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 +37090000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.014,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 +37190000,0.64,-0.0069,0.021,0.77,-3.8,-4.2,-0.0055,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 +37290000,0.64,-0.0069,0.021,0.77,-3.8,-4.3,0.003,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.7e-05,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 +37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00071,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 +37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.7e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 +37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,8.3e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 +37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.7e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 +37790000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.069,0.0041,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 +37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.2e-05,0.069,0.0043,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 +37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.2e-05,0.069,0.0041,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 +38090000,0.64,-0.0071,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.069,0.004,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 +38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.069,0.004,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 +38290000,0.64,-0.0071,0.021,0.77,-4.1,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.069,0.004,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 +38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.069,0.0038,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 +38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.069,0.0039,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 +38590000,0.64,-0.007,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.069,0.0041,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 +38690000,0.64,-0.007,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0043,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 +38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.068,0.0041,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 +38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.069,0.0042,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index af5d55ea1550..efd262eaf455 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -333,19 +333,19 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 33090000,-0.29,0.015,-0.006,0.96,0.0014,0.097,-0.081,0.092,0.0086,0.036,-0.0013,-0.0058,-9.8e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.006,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0027,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33390000,-0.3,0.015,-0.0059,0.96,0.014,0.093,-0.078,0.094,-0.0055,0.011,-0.0013,-0.0058,-2.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 -33490000,-0.3,0.015,-0.0059,0.96,0.019,0.097,-0.077,0.097,0.0039,0.0017,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 -33590000,-0.3,0.015,-0.0057,0.95,0.023,0.095,-0.074,0.096,-0.009,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 -33690000,-0.3,0.015,-0.0057,0.95,0.026,0.098,-0.075,0.097,-3.1e-05,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 -33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.069,0.094,-0.013,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 -33890000,-0.3,0.015,-0.0056,0.95,0.033,0.098,-0.069,0.097,-0.0041,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 -33990000,-0.3,0.015,-0.0055,0.95,0.035,0.096,-0.065,0.096,-0.012,-0.032,-0.0013,-0.0058,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 -34090000,-0.3,0.015,-0.0055,0.95,0.038,0.1,-0.064,0.099,-0.0028,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 -34190000,-0.3,0.015,-0.0054,0.95,0.039,0.098,-0.061,0.094,-0.014,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 -34290000,-0.3,0.015,-0.0053,0.95,0.04,0.1,-0.06,0.098,-0.0048,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 -34390000,-0.3,0.015,-0.0052,0.95,0.042,0.097,-0.055,0.093,-0.016,-0.049,-0.0013,-0.0057,-3.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 -34490000,-0.3,0.015,-0.0052,0.95,0.045,0.1,-0.053,0.097,-0.0069,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 -34590000,-0.3,0.014,-0.0051,0.95,0.045,0.098,0.74,0.092,-0.021,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 -34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 +33390000,-0.3,0.015,-0.0059,0.96,0.014,0.093,-0.078,0.094,-0.0055,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 +33490000,-0.3,0.015,-0.0059,0.96,0.019,0.097,-0.078,0.097,0.0039,-0.00071,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 +33590000,-0.3,0.015,-0.0057,0.95,0.023,0.095,-0.075,0.096,-0.009,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 +33690000,-0.3,0.015,-0.0057,0.95,0.026,0.098,-0.076,0.097,-3.5e-05,-0.019,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 +33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.071,0.094,-0.013,-0.028,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 +33890000,-0.3,0.015,-0.0056,0.95,0.033,0.098,-0.071,0.097,-0.0041,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 +33990000,-0.3,0.015,-0.0055,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 +34090000,-0.3,0.015,-0.0055,0.95,0.038,0.1,-0.066,0.099,-0.0028,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 +34190000,-0.3,0.015,-0.0054,0.95,0.039,0.098,-0.064,0.094,-0.015,-0.05,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 +34290000,-0.3,0.015,-0.0053,0.95,0.04,0.1,-0.062,0.098,-0.0048,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 +34390000,-0.3,0.015,-0.0052,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 +34490000,-0.3,0.015,-0.0052,0.95,0.045,0.1,-0.055,0.097,-0.0069,-0.061,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 +34590000,-0.3,0.014,-0.0051,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 +34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38 34890000,-0.3,0.014,-0.0051,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41 diff --git a/src/modules/ekf2/test/test_EKF_flow.cpp b/src/modules/ekf2/test/test_EKF_flow.cpp index 42f27028a04c..787560ce1bf6 100644 --- a/src/modules/ekf2/test/test_EKF_flow.cpp +++ b/src/modules/ekf2/test/test_EKF_flow.cpp @@ -178,9 +178,9 @@ TEST_F(EkfFlowTest, resetToFlowVelocityOnGround) EXPECT_TRUE(isEqual(estimated_horz_velocity, Vector2f(0.f, 0.f))) << estimated_horz_velocity(0) << ", " << estimated_horz_velocity(1); - // AND: the velocity isn't reset as it is already correct + // AND: the horizontal velocity is reset to the flow value reset_logging_checker.capturePostResetState(); - EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1)); EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); } diff --git a/src/modules/ekf2/test/test_EKF_terrain.cpp b/src/modules/ekf2/test/test_EKF_terrain.cpp index 964cd43822f4..c3c2ad6714a9 100644 --- a/src/modules/ekf2/test/test_EKF_terrain.cpp +++ b/src/modules/ekf2/test/test_EKF_terrain.cpp @@ -154,7 +154,7 @@ TEST_F(EkfTerrainTest, testFlowForTerrainFusion) // WHEN: the sensors do not agree const float rng_height = 1.f; - const float flow_height = 5.f; + const float flow_height = 8.f; runFlowAndRngScenario(rng_height, flow_height); // THEN: the estimator should use flow for terrain and the estimated terrain height @@ -175,7 +175,7 @@ TEST_F(EkfTerrainTest, testRngForTerrainFusion) // WHEN: the sensors do not agree const float rng_height = 1.f; - const float flow_height = 5.f; + const float flow_height = 8.f; runFlowAndRngScenario(rng_height, flow_height); // THEN: the estimator should use rng for terrain and the estimated terrain height From 1ae96d6509e000c05b05bf609709116fba9bc25f Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 26 Jun 2024 10:13:29 +0200 Subject: [PATCH 402/652] EKF2: fix builds without CONFIG_EKF2_RANGE_FINDER Signed-off-by: Silvan Fuhrer --- .../optical_flow/optical_flow_control.cpp | 22 +++++++++++++------ src/modules/ekf2/EKF2.cpp | 4 ++++ 2 files changed, 19 insertions(+), 7 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 27e05af75666..d9b0887237dd 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 @@ -53,7 +53,13 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) const bool is_quality_good = (_flow_sample_delayed.quality >= min_quality); const bool is_magnitude_good = _flow_sample_delayed.flow_rate.isAllFinite() && !_flow_sample_delayed.flow_rate.longerThan(_flow_max_rate); - const bool is_tilt_good = (_R_to_earth(2, 2) > _params.range_cos_max_tilt); + + bool is_tilt_good = true; + +#if defined(CONFIG_EKF2_RANGE_FINDER) + is_tilt_good = (_R_to_earth(2, 2) > _params.range_cos_max_tilt); + +#endif // CONFIG_EKF2_RANGE_FINDER if (is_quality_good && is_magnitude_good @@ -75,16 +81,16 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) // Check if we are in-air and require optical flow to control position drift bool is_flow_required = _control_status.flags.in_air && (_control_status.flags.inertial_dead_reckoning // is doing inertial dead-reckoning so must constrain drift urgently - || isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)); + || isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)); const bool is_within_max_sensor_dist = getHagl() <= _flow_max_distance; const bool continuing_conditions_passing = (_params.flow_ctrl == 1) - && _control_status.flags.tilt_align - && is_within_max_sensor_dist; + && _control_status.flags.tilt_align + && is_within_max_sensor_dist; const bool starting_conditions_passing = continuing_conditions_passing - && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching + && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching // If the height is relative to the ground, terrain height cannot be observed. _hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); @@ -198,7 +204,8 @@ void Ekf::stopFlowFusion() void Ekf::calcOptFlowBodyRateComp(const imuSample &imu_delayed) { if (imu_delayed.delta_ang_dt > FLT_EPSILON) { - _ref_body_rate = -imu_delayed.delta_ang / imu_delayed.delta_ang_dt - getGyroBias(); // flow gyro has opposite sign convention + _ref_body_rate = -imu_delayed.delta_ang / imu_delayed.delta_ang_dt - + getGyroBias(); // flow gyro has opposite sign convention } else { _ref_body_rate.zero(); @@ -213,5 +220,6 @@ void Ekf::calcOptFlowBodyRateComp(const imuSample &imu_delayed) } // calculate the bias estimate using a combined LPF and spike filter - _flow_gyro_bias = _flow_gyro_bias * 0.99f + matrix::constrain(_flow_sample_delayed.gyro_rate - _ref_body_rate, -0.1f, 0.1f) * 0.01f; + _flow_gyro_bias = _flow_gyro_bias * 0.99f + matrix::constrain(_flow_sample_delayed.gyro_rate - _ref_body_rate, -0.1f, + 0.1f) * 0.01f; } diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 32933b5c86bd..967a6627b2f8 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2314,6 +2314,8 @@ bool EKF2::UpdateFlowSample(ekf2_timestamps_s &ekf2_timestamps) new_optical_flow = true; } +#if defined(CONFIG_EKF2_RANGE_FINDER) + // use optical_flow distance as range sample if distance_sensor unavailable if (PX4_ISFINITE(optical_flow.distance_m) && (ekf2_timestamps.timestamp > _last_range_sensor_update + 1_s)) { @@ -2330,6 +2332,8 @@ bool EKF2::UpdateFlowSample(ekf2_timestamps_s &ekf2_timestamps) _ekf.set_rangefinder_limits(optical_flow.min_ground_distance, optical_flow.max_ground_distance); } +#endif // CONFIG_EKF2_RANGE_FINDER + ekf2_timestamps.optical_flow_timestamp_rel = (int16_t)((int64_t)optical_flow.timestamp / 100 - (int64_t)ekf2_timestamps.timestamp / 100); } From 9cc4e2ac0153de744be7843dd4bc08dcf928a7c7 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Mon, 24 Jun 2024 12:54:01 -0600 Subject: [PATCH 403/652] boards ark pi6x add vl53l0x --- boards/ark/pi6x/default.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 4d07a0e8c44d..8646ea006e29 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y +CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y From 338bcc6ca3bd4094b33de2df6793a112f2a0e71d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 20 Jun 2024 15:36:12 -0400 Subject: [PATCH 404/652] ekf2: disable EKF2_EV_CTRL and EKF2_AGP_CTRL by default --- src/modules/ekf2/module.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 49cceb3fb0ef..a2cf1a5e1390 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -524,7 +524,7 @@ parameters: 1: Vertical position 2: 3D velocity 3: Yaw - default: 15 + default: 0 min: 0 max: 15 EKF2_GPS_CTRL: @@ -1303,7 +1303,7 @@ parameters: bit: 0: Horizontal position 1: Vertical position - default: 1 + default: 0 min: 0 max: 3 EKF2_AGP_DELAY: From 78fd9a15f8ce93acaef690d89865c903423f669d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 17:28:39 -0400 Subject: [PATCH 405/652] flight_mode_manager: delete unused avoidance waypoint --- .../tasks/FlightTask/FlightTask.hpp | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp index 3b9ddbd46660..7e938bb0a9d7 100644 --- a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp +++ b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp @@ -52,7 +52,6 @@ #include #include #include -#include #include #include @@ -132,12 +131,6 @@ class FlightTask : public ModuleParams */ const landing_gear_s &getGear() { return _gear; } - /** - * Get avoidance desired waypoint - * @return desired waypoints - */ - const vehicle_trajectory_waypoint_s &getAvoidanceWaypoint() { return _desired_waypoint; } - /** * All setpoints are set to NAN (uncontrolled), timestamp to zero */ @@ -251,12 +244,6 @@ class FlightTask : public ModuleParams landing_gear_s _gear{}; - /** - * Desired waypoints. - * Goals set by the FCU to be sent to the obstacle avoidance system. - */ - vehicle_trajectory_waypoint_s _desired_waypoint{}; - DEFINE_PARAMETERS_CUSTOM_PARENT(ModuleParams, (ParamFloat) _param_mpc_xy_vel_max, (ParamFloat) _param_mpc_z_vel_max_dn, From 8070c70f2c5e25b206ebf52e901f52cef4677a67 Mon Sep 17 00:00:00 2001 From: Patrik Dominik Pordi <119634185+patrikpordi@users.noreply.github.com> Date: Wed, 26 Jun 2024 23:10:04 -0600 Subject: [PATCH 406/652] uxrce_dds_client: dds_topics.yaml add vehicle_land_detected - px4_msgs::msg::VehicleLandDetected has been added to dds_topics.yaml --- src/modules/uxrce_dds_client/dds_topics.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index 255c8e0b5417..67b1e9456cee 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -44,6 +44,9 @@ publications: # - topic: /fmu/out/vehicle_angular_velocity # type: px4_msgs::msg::VehicleAngularVelocity + - topic: /fmu/out/vehicle_land_detected + type: px4_msgs::msg::VehicleLandDetected + - topic: /fmu/out/vehicle_attitude type: px4_msgs::msg::VehicleAttitude From 30b854da3582645910cbb8c40c649e9650e12ee4 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 27 Jun 2024 01:10:57 -0400 Subject: [PATCH 407/652] ekf2: verbose logging control (new EKF2_LOG_VERBOSE) - new parameter EKF2_LOG_VERBOSE to enable (currently enabled by default) - force advertise topics immediately (based on EKF2_LOG_VERBOSE and per aid source configuration) - logger optionally log all estimator topics at minimal rate --- src/modules/ekf2/EKF2.cpp | 219 ++++++++++++++++----------- src/modules/ekf2/EKF2.hpp | 2 + src/modules/ekf2/module.yaml | 5 + src/modules/logger/logged_topics.cpp | 125 +++++---------- 4 files changed, 172 insertions(+), 179 deletions(-) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 967a6627b2f8..17d55ab740b4 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -213,18 +213,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): _param_ekf2_abl_tau(_params->acc_bias_learn_tc), _param_ekf2_gyr_b_lim(_params->gyro_bias_lim) { - // advertise expected minimal topic set immediately to ensure logging - _attitude_pub.advertise(); - _local_position_pub.advertise(); - - _estimator_event_flags_pub.advertise(); - _estimator_innovation_test_ratios_pub.advertise(); - _estimator_innovation_variances_pub.advertise(); - _estimator_innovations_pub.advertise(); - _estimator_sensor_bias_pub.advertise(); - _estimator_states_pub.advertise(); - _estimator_status_flags_pub.advertise(); - _estimator_status_pub.advertise(); + AdvertiseTopics(); } EKF2::~EKF2() @@ -233,120 +222,164 @@ EKF2::~EKF2() perf_free(_msg_missed_imu_perf); } -#if defined(CONFIG_EKF2_MULTI_INSTANCE) -bool EKF2::multi_init(int imu, int mag) +void EKF2::AdvertiseTopics() { - // advertise all topics to ensure consistent uORB instance numbering + // advertise expected minimal topic set immediately for logging + _attitude_pub.advertise(); + _local_position_pub.advertise(); _estimator_event_flags_pub.advertise(); - _estimator_innovation_test_ratios_pub.advertise(); - _estimator_innovation_variances_pub.advertise(); - _estimator_innovations_pub.advertise(); -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - _estimator_optical_flow_vel_pub.advertise(); -#endif // CONFIG_EKF2_OPTICAL_FLOW _estimator_sensor_bias_pub.advertise(); - _estimator_states_pub.advertise(); - _estimator_status_flags_pub.advertise(); _estimator_status_pub.advertise(); + _estimator_status_flags_pub.advertise(); + + if (_multi_mode) { + // only force advertise these in multi mode to ensure consistent uORB instance numbering + _global_position_pub.advertise(); + _odometry_pub.advertise(); + +#if defined(CONFIG_EKF2_WIND) + _wind_pub.advertise(); +#endif // CONFIG_EKF2_WIND + } #if defined(CONFIG_EKF2_GNSS) - _yaw_est_pub.advertise(); + + if (_param_ekf2_gps_ctrl.get()) { + _estimator_gps_status_pub.advertise(); + _yaw_est_pub.advertise(); + } + #endif // CONFIG_EKF2_GNSS + // verbose logging + if (_param_ekf2_log_verbose.get()) { + _estimator_innovation_test_ratios_pub.advertise(); + _estimator_innovation_variances_pub.advertise(); + _estimator_innovations_pub.advertise(); + _estimator_states_pub.advertise(); + +#if defined(CONFIG_EKF2_AIRSPEED) + + if (_param_ekf2_arsp_thr.get() > 0.f) { + _estimator_aid_src_airspeed_pub.advertise(); + } + +#endif // CONFIG_EKF2_AIRSPEED + #if defined(CONFIG_EKF2_BAROMETER) - // baro advertise - if (_param_ekf2_baro_ctrl.get()) { - _estimator_aid_src_baro_hgt_pub.advertise(); - _estimator_baro_bias_pub.advertise(); - } + if (_param_ekf2_baro_ctrl.get()) { + _estimator_aid_src_baro_hgt_pub.advertise(); + _estimator_baro_bias_pub.advertise(); + } #endif // CONFIG_EKF2_BAROMETER +#if defined(CONFIG_EKF2_DRAG_FUSION) + + if (_param_ekf2_drag_ctrl.get()) { + _estimator_aid_src_drag_pub.advertise(); + } + +#endif // CONFIG_EKF2_DRAG_FUSION + #if defined(CONFIG_EKF2_EXTERNAL_VISION) - // EV advertise - if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::VPOS)) { - _estimator_aid_src_ev_hgt_pub.advertise(); - _estimator_ev_pos_bias_pub.advertise(); - } + if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::VPOS)) { + _estimator_aid_src_ev_hgt_pub.advertise(); + _estimator_ev_pos_bias_pub.advertise(); + } - if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::HPOS)) { - _estimator_aid_src_ev_pos_pub.advertise(); - _estimator_ev_pos_bias_pub.advertise(); - } + if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::HPOS)) { + _estimator_aid_src_ev_pos_pub.advertise(); + _estimator_ev_pos_bias_pub.advertise(); + } - if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::VEL)) { - _estimator_aid_src_ev_vel_pub.advertise(); - } + if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::VEL)) { + _estimator_aid_src_ev_vel_pub.advertise(); + } - if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::YAW)) { - _estimator_aid_src_ev_yaw_pub.advertise(); - } + if (_param_ekf2_ev_ctrl.get() & static_cast(EvCtrl::YAW)) { + _estimator_aid_src_ev_yaw_pub.advertise(); + } #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_GNSS) - // GNSS advertise - if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::VPOS)) { - _estimator_aid_src_gnss_hgt_pub.advertise(); - _estimator_gnss_hgt_bias_pub.advertise(); - } + if (_param_ekf2_gps_ctrl.get()) { + if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::VPOS)) { + _estimator_aid_src_gnss_hgt_pub.advertise(); + _estimator_gnss_hgt_bias_pub.advertise(); + } - if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::HPOS)) { - _estimator_aid_src_gnss_pos_pub.advertise(); - _estimator_gps_status_pub.advertise(); - } + if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::HPOS)) { + _estimator_aid_src_gnss_pos_pub.advertise(); + } - if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::VEL)) { - _estimator_aid_src_gnss_vel_pub.advertise(); - } + if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::VEL)) { + _estimator_aid_src_gnss_vel_pub.advertise(); + } # if defined(CONFIG_EKF2_GNSS_YAW) - if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::YAW)) { - _estimator_aid_src_gnss_yaw_pub.advertise(); - } + if (_param_ekf2_gps_ctrl.get() & static_cast(GnssCtrl::YAW)) { + _estimator_aid_src_gnss_yaw_pub.advertise(); + } # endif // CONFIG_EKF2_GNSS_YAW + } + #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_GRAVITY_FUSION) - if (_param_ekf2_imu_ctrl.get() & static_cast(ImuCtrl::GravityVector)) { - _estimator_aid_src_gravity_pub.advertise(); - } + if (_param_ekf2_imu_ctrl.get() & static_cast(ImuCtrl::GravityVector)) { + _estimator_aid_src_gravity_pub.advertise(); + } #endif // CONFIG_EKF2_GRAVITY_FUSION +#if defined(CONFIG_EKF2_MAGNETOMETER) + + if (_param_ekf2_mag_type.get() != MagFuseType::NONE) { + _estimator_aid_src_mag_pub.advertise(); + } + +#endif // CONFIG_EKF2_MAGNETOMETER + +#if defined(CONFIG_EKF2_OPTICAL_FLOW) + + if (_param_ekf2_of_ctrl.get()) { + _estimator_optical_flow_vel_pub.advertise(); + _estimator_aid_src_optical_flow_pub.advertise(); + } + +#endif // CONFIG_EKF2_OPTICAL_FLOW + #if defined(CONFIG_EKF2_RANGE_FINDER) - // RNG advertise - if (_param_ekf2_rng_ctrl.get()) { - _estimator_aid_src_rng_hgt_pub.advertise(); - } + // RNG advertise + if (_param_ekf2_rng_ctrl.get()) { + _estimator_aid_src_rng_hgt_pub.advertise(); + } #endif // CONFIG_EKF2_RANGE_FINDER -#if defined(CONFIG_EKF2_MAGNETOMETER) - - // mag advertise - if (_param_ekf2_mag_type.get() != MagFuseType::NONE) { - _estimator_aid_src_mag_pub.advertise(); - } +#if defined(CONFIG_EKF2_SIDESLIP) -#endif // CONFIG_EKF2_MAGNETOMETER + if (_param_ekf2_fuse_beta.get()) { + _estimator_aid_src_sideslip_pub.advertise(); + } - _attitude_pub.advertise(); - _local_position_pub.advertise(); - _global_position_pub.advertise(); - _odometry_pub.advertise(); +#endif // CONFIG_EKF2_SIDESLIP -#if defined(CONFIG_EKF2_WIND) - _wind_pub.advertise(); -#endif // CONFIG_EKF2_WIND + } // end verbose logging +} +#if defined(CONFIG_EKF2_MULTI_INSTANCE) +bool EKF2::multi_init(int imu, int mag) +{ bool changed_instance = _vehicle_imu_sub.ChangeInstance(imu); #if defined(CONFIG_EKF2_MAGNETOMETER) @@ -415,6 +448,9 @@ void EKF2::Run() VerifyParams(); + // force advertise topics immediately for logging (EKF2_LOG_VERBOSE, per aid source control) + AdvertiseTopics(); + #if defined(CONFIG_EKF2_GNSS) _ekf.set_min_required_gps_health_time(_param_ekf2_req_gps_h.get() * 1_s); #endif // CONFIG_EKF2_GNSS @@ -714,24 +750,31 @@ void EKF2::Run() // publish status/logging messages PublishEventFlags(now); - PublishInnovations(now); - PublishInnovationTestRatios(now); - PublishInnovationVariances(now); - PublishStates(now); PublishStatus(now); PublishStatusFlags(now); - PublishAidSourceStatus(now); + + if (_param_ekf2_log_verbose.get()) { + PublishAidSourceStatus(now); + PublishInnovations(now); + PublishInnovationTestRatios(now); + PublishInnovationVariances(now); + PublishStates(now); #if defined(CONFIG_EKF2_BAROMETER) - PublishBaroBias(now); + PublishBaroBias(now); #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_EXTERNAL_VISION) - PublishEvPosBias(now); + PublishEvPosBias(now); #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_GNSS) - PublishGnssHgtBias(now); + PublishGnssHgtBias(now); +#endif // CONFIG_EKF2_GNSS + + } + +#if defined(CONFIG_EKF2_GNSS) PublishGpsStatus(now); PublishYawEstimatorStatus(now); #endif // CONFIG_EKF2_GNSS diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index fc50610fd282..2de08049cb53 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -162,6 +162,7 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem void Run() override; + void AdvertiseTopics(); void VerifyParams(); void PublishAidSourceStatus(const hrt_abstime ×tamp); @@ -482,6 +483,7 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem parameters *_params; ///< pointer to ekf parameter struct (located in _ekf class instance) DEFINE_PARAMETERS( + (ParamBool) _param_ekf2_log_verbose, (ParamExtInt) _param_ekf2_predict_us, (ParamExtFloat) _param_ekf2_delay_max, (ParamExtInt) _param_ekf2_imu_ctrl, diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index a2cf1a5e1390..be11bd97b353 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -1335,3 +1335,8 @@ parameters: min: 1.0 unit: SD decimal: 1 + EKF2_LOG_VERBOSE: + description: + short: Verbose logging + type: boolean + default: 1 diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index fedadaf47458..7dd0a43e9401 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -150,65 +150,27 @@ void LoggedTopics::add_default_topics() add_topic_multi("timesync_status", 1000, 3); add_optional_topic_multi("telemetry_status", 1000, 4); - // EKF multi topics (currently max 9 estimators) -#if CONSTRAINED_MEMORY - static constexpr uint8_t MAX_ESTIMATOR_INSTANCES = 1; -#else - static constexpr uint8_t MAX_ESTIMATOR_INSTANCES = 6; // artificially limited until PlotJuggler fixed - add_optional_topic("estimator_selector_status"); - add_optional_topic_multi("estimator_attitude", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_global_position", 1000, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_local_position", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_wind", 1000, MAX_ESTIMATOR_INSTANCES); -#endif - - // always add the first instance - add_topic("estimator_baro_bias", 500); - add_topic("estimator_gnss_hgt_bias", 500); - add_topic("estimator_ev_pos_bias", 500); - add_topic("estimator_event_flags", 0); - add_topic("estimator_gps_status", 1000); - add_topic("estimator_innovation_test_ratios", 500); - add_topic("estimator_innovation_variances", 500); - add_topic("estimator_innovations", 500); - add_topic("estimator_optical_flow_vel", 200); - add_topic("estimator_sensor_bias", 0); - add_topic("estimator_states", 1000); - add_topic("estimator_status", 200); - add_topic("estimator_status_flags", 0); - add_topic("yaw_estimator_status", 1000); - - add_optional_topic_multi("estimator_baro_bias", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_gnss_hgt_bias", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_ev_pos_bias", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_event_flags", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_gps_status", 1000, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_innovation_test_ratios", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_innovation_variances", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_innovations", 500, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_optical_flow_vel", 200, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_sensor_bias", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_states", 1000, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_status", 200, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_status_flags", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("yaw_estimator_status", 1000, MAX_ESTIMATOR_INSTANCES); - - // add_optional_topic_multi("estimator_aid_src_airspeed", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_baro_hgt", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_ev_pos", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_ev_vel", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_ev_yaw", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_gravity", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_rng_hgt", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_fake_hgt", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_fake_pos", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_gnss_yaw", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_gnss_vel", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_gnss_pos", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_mag", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_optical_flow", 100, MAX_ESTIMATOR_INSTANCES); - // add_optional_topic_multi("estimator_aid_src_ev_yaw", 100, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_aux_global_position", 100, MAX_ESTIMATOR_INSTANCES); + // EKF multi topics + { + // optionally log all estimator* topics at minimal rate + const uint16_t kEKFVerboseIntervalMilliseconds = 500; // 2 Hz + const struct orb_metadata *const *topic_list = orb_get_topics(); + + for (size_t i = 0; i < orb_topics_count(); i++) { + if (strncmp(topic_list[i]->o_name, "estimator", 9) == 0) { + add_optional_topic_multi(topic_list[i]->o_name, kEKFVerboseIntervalMilliseconds); + } + } + } + + // important EKF topics (higher rate) + add_optional_topic("estimator_selector_status", 10); + add_optional_topic_multi("estimator_event_flags", 10); + add_optional_topic_multi("estimator_optical_flow_vel", 200); + add_optional_topic_multi("estimator_sensor_bias", 1000); + add_optional_topic_multi("estimator_status", 200); + add_optional_topic_multi("estimator_status_flags", 10); + add_optional_topic_multi("yaw_estimator_status", 1000); // log all raw sensors at minimal rate (at least 1 Hz) add_topic_multi("battery_status", 200, 2); @@ -262,42 +224,23 @@ void LoggedTopics::add_default_topics() add_topic("vehicle_local_position_groundtruth", 20); // EKF replay - add_topic("estimator_baro_bias"); - add_topic("estimator_gnss_hgt_bias"); - add_topic("estimator_ev_pos_bias"); - add_topic("estimator_event_flags"); - add_topic("estimator_gps_status"); - add_topic("estimator_innovation_test_ratios"); - add_topic("estimator_innovation_variances"); - add_topic("estimator_innovations"); - add_topic("estimator_optical_flow_vel"); - add_topic("estimator_sensor_bias"); - add_topic("estimator_states"); - add_topic("estimator_status"); - add_topic("estimator_status_flags"); + { + // optionally log all estimator* topics at minimal rate + const uint16_t kEKFVerboseIntervalMilliseconds = 10; // 100 Hz + const struct orb_metadata *const *topic_list = orb_get_topics(); + + for (size_t i = 0; i < orb_topics_count(); i++) { + if (strncmp(topic_list[i]->o_name, "estimator", 9) == 0) { + add_optional_topic_multi(topic_list[i]->o_name, kEKFVerboseIntervalMilliseconds); + } + } + } + add_topic("vehicle_attitude"); add_topic("vehicle_global_position"); add_topic("vehicle_local_position"); add_topic("wind"); - add_topic("yaw_estimator_status"); - - add_optional_topic_multi("estimator_aid_src_airspeed", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_baro_hgt", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_rng_hgt", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_fake_hgt", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_fake_pos", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_ev_hgt", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_ev_pos", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_ev_vel", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_ev_yaw", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_gnss_hgt", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_gnss_pos", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_gnss_vel", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_gnss_yaw", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_gravity", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_mag", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_optical_flow", 0, MAX_ESTIMATOR_INSTANCES); - add_optional_topic_multi("estimator_aid_src_sideslip", 0, MAX_ESTIMATOR_INSTANCES); + add_optional_topic_multi("yaw_estimator_status"); #endif /* CONFIG_ARCH_BOARD_PX4_SITL */ } From e4446adba159146342f1a17eb2f9a04e13bef811 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 26 Jun 2024 18:44:14 +0200 Subject: [PATCH 408/652] Add check for high RAM usage We had a case where someone took off with an experimental system with 100% RAM usage on the embedded system without noticing. This lead to problems during flight. Since we already have a CPU load check it seems natural to also check the reported RAM usage. --- ROMFS/px4fmu_common/init.d-posix/rcS | 1 + .../checks/cpuResourceCheck.cpp | 36 +++++++++++++++---- .../checks/cpuResourceCheck.hpp | 3 +- src/modules/commander/commander_params.c | 15 ++++++++ 4 files changed, 48 insertions(+), 7 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index 0fd28a0f13ca..8902b3664f07 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -157,6 +157,7 @@ param set-default CBRK_SUPPLY_CHK 894281 # disable check, no CPU load reported on posix yet param set-default COM_CPU_MAX -1 +param set-default COM_RAM_MAX -1 # Don't require RC calibration and configuration param set-default COM_RC_IN_MODE 1 diff --git a/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.cpp index c3651910c3c5..b433e47ba428 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.cpp @@ -43,7 +43,10 @@ CpuResourceChecks::CpuResourceChecks() void CpuResourceChecks::checkAndReport(const Context &context, Report &reporter) { - if (_param_com_cpu_max.get() < FLT_EPSILON) { + const bool cpu_load_check_enabled = _param_com_cpu_max.get() > FLT_EPSILON; + const bool ram_usage_check_enabled = _param_com_ram_max.get() > FLT_EPSILON; + + if (!cpu_load_check_enabled && !ram_usage_check_enabled) { return; } @@ -54,15 +57,15 @@ void CpuResourceChecks::checkAndReport(const Context &context, Report &reporter) /* EVENT * @description * - * If the system does not provide any CPU load information, use the parameter COM_CPU_MAX - * to disable the check. + * If the system does not provide any CPU and RAM load information, use the parameters COM_CPU_MAX + * and COM_RAM_MAX to disable the checks. * */ reporter.healthFailure(NavModes::All, health_component_t::system, events::ID("check_missing_cpuload"), - events::Log::Error, "No CPU load information"); + events::Log::Error, "No CPU and RAM load information"); if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: No CPU load information"); + mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: No CPU and RAM load information"); } } else { @@ -71,7 +74,7 @@ void CpuResourceChecks::checkAndReport(const Context &context, Report &reporter) _high_cpu_load_hysteresis.set_state_and_update(high_cpu_load, hrt_absolute_time()); // fail check if CPU load is above the threshold for 2 seconds - if (_high_cpu_load_hysteresis.get_state()) { + if (cpu_load_check_enabled && _high_cpu_load_hysteresis.get_state()) { /* EVENT * @description * The CPU load can be reduced for example by disabling unused modules (e.g. mavlink instances) or reducing the gyro update @@ -88,5 +91,26 @@ void CpuResourceChecks::checkAndReport(const Context &context, Report &reporter) mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: CPU load too high: %3.1f%%", (double)cpuload_percent); } } + + const float ram_usage_percent = cpuload.ram_usage * 100.f; + const bool high_ram_usage = ram_usage_percent > _param_com_ram_max.get(); + + if (ram_usage_check_enabled && high_ram_usage) { + /* EVENT + * @description + * The RAM usage can be reduced for example by disabling unused modules (e.g. mavlink instances). + * + * + * The threshold can be adjusted via COM_RAM_MAX parameter. + * + */ + reporter.healthFailure(NavModes::All, health_component_t::system, events::ID("check_ram_usage_too_high"), + events::Log::Error, "RAM usage too high: {1:.1}%", ram_usage_percent); + + if (reporter.mavlink_log_pub()) { + mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: RAM usage too high: %3.1f%%", + (double)ram_usage_percent); + } + } } } diff --git a/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.hpp index 10db83ad6bd7..d95c03d2908d 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/cpuResourceCheck.hpp @@ -54,6 +54,7 @@ class CpuResourceChecks : public HealthAndArmingCheckBase systemlib::Hysteresis _high_cpu_load_hysteresis{false}; DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, - (ParamFloat) _param_com_cpu_max + (ParamFloat) _param_com_cpu_max, + (ParamFloat) _param_com_ram_max ) }; diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 8f2c3d51ced0..e9d5f4de3acc 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -802,6 +802,21 @@ PARAM_DEFINE_FLOAT(COM_KILL_DISARM, 5.0f); */ PARAM_DEFINE_FLOAT(COM_CPU_MAX, 95.0f); +/** + * Maximum allowed RAM usage to pass checks + * + * The check fails if the RAM usage is above this threshold. + * + * A negative value disables the check. + * + * @group Commander + * @unit % + * @min -1 + * @max 100 + * @increment 1 + */ +PARAM_DEFINE_FLOAT(COM_RAM_MAX, 95.0f); + /** * Required number of redundant power modules * From 8b26e5e2528586b42fd12050c30ae4f72d39b9d6 Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Thu, 27 Jun 2024 12:39:19 +0000 Subject: [PATCH 409/652] Update submodule libevents to latest Thu Jun 27 12:39:19 UTC 2024 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - libevents in PX4/Firmware (4e3561cad8d24fefe66d266e969652d7ab20162b): https://github.com/mavlink/libevents/commit/8d5c44661bf79106361eb0b5170025b86e85a525 - libevents current upstream: https://github.com/mavlink/libevents/commit/9474657606d13301d426e044450c4f84de2221be - Changes: https://github.com/mavlink/libevents/compare/8d5c44661bf79106361eb0b5170025b86e85a525...9474657606d13301d426e044450c4f84de2221be 9474657 2024-06-13 Beat Küng - cmake: add namespaced target & installation include dir 9f2e68d 2024-06-12 Beat Küng - CMakeLists: set CMAKE_CXX_STANDARD if not set 3204e8f 2024-06-12 Beat Küng - parser.h: use std::vector::size_type eab8144 2024-04-29 Beat Küng - fix parser: avoid signed to unsigned conversion 159f83e 2024-04-29 Beat Küng - cpp: only enable Wall and others for GCC --- src/lib/events/libevents | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/events/libevents b/src/lib/events/libevents index 8d5c44661bf7..9474657606d1 160000 --- a/src/lib/events/libevents +++ b/src/lib/events/libevents @@ -1 +1 @@ -Subproject commit 8d5c44661bf79106361eb0b5170025b86e85a525 +Subproject commit 9474657606d13301d426e044450c4f84de2221be From 58f7c3e9c95a453fa850275e50542ead1f73db6f Mon Sep 17 00:00:00 2001 From: Peter van der Perk <57130844+PetervdPerk-NXP@users.noreply.github.com> Date: Thu, 27 Jun 2024 22:21:45 +0200 Subject: [PATCH 410/652] NuttX with imxrt1170 soc vdd backport (#23333) --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 9583e2d9cec7..d72688cba139 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 9583e2d9cec78c45a183d764a2fa206756ee3a3f +Subproject commit d72688cba1396c882ab74fc921483c8decb0b094 From 053b4a442336c07aac8418824281153a3abe9414 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Thu, 27 Jun 2024 19:35:45 -0600 Subject: [PATCH 411/652] drivers/uavcan: GNSS set system time based on fix_type instead of valid_pos_cov --- src/drivers/uavcan/sensors/gnss.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/uavcan/sensors/gnss.cpp b/src/drivers/uavcan/sensors/gnss.cpp index 49c033e43beb..db88941a564b 100644 --- a/src/drivers/uavcan/sensors/gnss.cpp +++ b/src/drivers/uavcan/sensors/gnss.cpp @@ -436,7 +436,7 @@ void UavcanGnssBridge::process_fixx(const uavcan::ReceivedDataStructure } // If we haven't already done so, set the system clock using GPS data - if (valid_pos_cov && !_system_clock_set) { + if ((fix_type >= sensor_gps_s::FIX_TYPE_2D) && !_system_clock_set) { timespec ts{}; // get the whole microseconds From 408d8abe959d71d843d48843bd6c050d70973e31 Mon Sep 17 00:00:00 2001 From: bluedisk Date: Fri, 28 Jun 2024 23:20:26 +0900 Subject: [PATCH 412/652] Tools/setup: fix the wrong - deprecated - expression in the requirements.txt - Fixes matplotlib version expression from ">=3.0.*" ro ">=3.0" which is the right syntax Fixes issue #23329 Co-authored-by: lee wonwoo --- Tools/setup/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/setup/requirements.txt b/Tools/setup/requirements.txt index b130bd55a0f9..0202963fd773 100644 --- a/Tools/setup/requirements.txt +++ b/Tools/setup/requirements.txt @@ -7,7 +7,7 @@ jinja2>=2.8 jsonschema kconfiglib lxml -matplotlib>=3.0.* +matplotlib>=3.0 numpy>=1.13 nunavut>=1.1.0 packaging From 0742d356f53190ef9f3705026da50327717237f8 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 28 Jun 2024 16:45:08 -0400 Subject: [PATCH 413/652] ekf2: more conservative clipping checks for bad_acc_clipping fault status (#23337) - track accel clipping count per axis - only set bad_acc_clipping fault_status if at least one axis is clipping continuously or if all have been clipping at warning level - Note: this doesn't impact the clipping projections that boost the accel process noise, pause bias estimation, and skip gravity fusion on a per sample basis --- src/modules/ekf2/EKF/ekf.cpp | 5 +++- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF/height_control.cpp | 32 ++++++++++++++++--------- 3 files changed, 26 insertions(+), 13 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index c16ca24476cc..1571aa06ca86 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -127,7 +127,10 @@ void Ekf::reset() _time_bad_vert_accel = 0; _time_good_vert_accel = 0; - _clip_counter = 0; + + for (auto &clip_count : _clip_counter) { + clip_count = 0; + } _zero_velocity_update.reset(); } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 46e03bcaaef4..45917b6348f9 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -706,7 +706,7 @@ class Ekf final : public EstimatorInterface // imu fault status uint64_t _time_bad_vert_accel{0}; ///< last time a bad vertical accel was detected (uSec) uint64_t _time_good_vert_accel{0}; ///< last time a good vertical accel was detected (uSec) - uint16_t _clip_counter{0}; ///< counter that increments when clipping ad decrements when not + uint16_t _clip_counter[3]; ///< counter per axis that increments when clipping ad decrements when not // initialise filter states of both the delayed ekf and the real time complementary filter bool initialiseFilter(void); diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index aad5c286b8d3..51da34e343a5 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -230,22 +230,32 @@ void Ekf::checkVerticalAccelerationHealth(const imuSample &imu_delayed) Likelihood inertial_nav_falling_likelihood = estimateInertialNavFallingLikelihood(); - // Check for more than 50% clipping affected IMU samples within the past 1 second - const uint16_t clip_count_limit = 1.f / _dt_ekf_avg; - const bool is_clipping = imu_delayed.delta_vel_clipping[0] || - imu_delayed.delta_vel_clipping[1] || - imu_delayed.delta_vel_clipping[2]; + const uint16_t kClipCountLimit = 1.f / _dt_ekf_avg; - if (is_clipping && _clip_counter < clip_count_limit) { - _clip_counter++; + bool acc_clip_warning[3] {}; + bool acc_clip_critical[3] {}; - } else if (_clip_counter > 0) { - _clip_counter--; + for (int axis = 0; axis < 3; axis++) { + if (imu_delayed.delta_vel_clipping[axis] && (_clip_counter[axis] < kClipCountLimit)) { + _clip_counter[axis]++; + + } else if (_clip_counter[axis] > 0) { + _clip_counter[axis]--; + } + + // warning if more than 50% clipping affected IMU samples within the past 1 second + acc_clip_warning[axis] = _clip_counter[axis] >= kClipCountLimit / 2; + acc_clip_critical[axis] = _clip_counter[axis] >= kClipCountLimit; } - _fault_status.flags.bad_acc_clipping = _clip_counter > clip_count_limit / 2; + // bad_acc_clipping if ALL axes are reporting warning or if ANY axis is critical + const bool all_axis_warning = (acc_clip_warning[0] && acc_clip_warning[1] && acc_clip_warning[2]); + const bool any_axis_critical = (acc_clip_critical[0] || acc_clip_critical[1] || acc_clip_critical[2]); + + _fault_status.flags.bad_acc_clipping = all_axis_warning || any_axis_critical; - const bool is_clipping_frequently = _clip_counter > 0; + // if Z axis is warning or any other axis critical + const bool is_clipping_frequently = acc_clip_warning[2] || _fault_status.flags.bad_acc_clipping; // Do not require evidence of clipping if the likelihood of having the INS falling is high const bool bad_vert_accel = (is_clipping_frequently && (inertial_nav_falling_likelihood == Likelihood::MEDIUM)) From 3880073716c1b46ed9ecbd25f8c2d23055c0d42f Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Tue, 2 Jul 2024 16:38:49 +0200 Subject: [PATCH 414/652] ekf2: fix timeout after gps failure (#23346) --- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 3 +- .../test/change_indication/ekf_gsf_reset.csv | 748 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 666 ++++++++-------- src/modules/ekf2/test/test_EKF_gps.cpp | 2 +- src/modules/ekf2/test/test_EKF_mag.cpp | 4 +- 5 files changed, 712 insertions(+), 711 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index a6bb067f4b73..afff48dcb7da 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -63,7 +63,8 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) if (_gps_data_ready) { const gnssSample &gnss_sample = _gps_sample_delayed; - if (runGnssChecks(gnss_sample) && isTimedOut(_last_gps_fail_us, (uint64_t)_min_gps_health_time_us / 2)) { + if (runGnssChecks(gnss_sample) + && isTimedOut(_last_gps_fail_us, max((uint64_t)1e6, (uint64_t)_min_gps_health_time_us / 10))) { if (isTimedOut(_last_gps_fail_us, (uint64_t)_min_gps_health_time_us)) { // First time checks are passing, latching. _gps_checks_passed = true; diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv index 285204826673..50f65f6fa51c 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -15,377 +15,377 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 -2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -2190000,1,-0.011,-0.014,5.9e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.011,-0.013,5.9e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.011,-0.013,4.9e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.011,-0.013,-1.1e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.011,-0.013,4.9e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.011,-0.013,-8e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.011,-0.013,3.2e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.011,-0.012,3.2e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.011,-0.013,-4.5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.011,-0.012,1.9e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.01,-0.012,8.1e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.01,-0.012,0.00019,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.01,-0.012,0.00018,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0096,-0.011,0.00033,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0094,-0.011,0.00031,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0094,-0.011,0.00021,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-3.6e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0093,-0.011,0.00023,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-3.6e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.5e-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.0094,-0.011,0.00016,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-7.6e-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,9e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.6e-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.78,-0.024,0.0048,-0.62,-0.22,-0.051,-0.11,-0.13,-0.03,-3.7e+02,-0.00029,-0.01,-0.0002,0,0,0.0012,-0.092,-0.021,0.51,-0.00079,-0.075,-0.061,0,0,-3.6e+02,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1,1.7 -6890000,0.78,-0.025,0.0057,-0.62,-0.27,-0.065,-0.12,-0.16,-0.04,-3.7e+02,-0.0001,-0.011,-0.00022,0,0,0.0012,-0.1,-0.023,0.51,-0.0012,-0.083,-0.067,0,0,-3.6e+02,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00025,0.0013,0.00089,0.0014,0.0013,1,1,1.8 -6990000,0.78,-0.025,0.006,-0.62,-0.3,-0.077,-0.12,-0.2,-0.05,-3.7e+02,-6.9e-06,-0.011,-0.00022,-0.00057,-7.3e-05,0.00095,-0.1,-0.024,0.5,-0.0016,-0.084,-0.067,0,0,-3.6e+02,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1,1.8 -7090000,0.78,-0.025,0.0062,-0.62,-0.33,-0.088,-0.12,-0.23,-0.063,-3.7e+02,0.00011,-0.011,-0.00023,-0.0013,-0.0003,0.00061,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00016,0.0013,0.00083,0.0014,0.0013,1,1,1.8 -7190000,0.78,-0.025,0.0064,-0.62,-0.36,-0.097,-0.15,-0.26,-0.075,-3.7e+02,0.00017,-0.011,-0.00023,-0.0017,-0.00046,0.00083,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00082,0.0013,0.0013,1,1,1.8 -7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.099,-0.14,-0.3,-0.082,-3.7e+02,0.00012,-0.011,-0.00023,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1,1.9 -7390000,0.78,-0.025,0.0069,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,0.00014,-0.011,-0.00022,-0.0016,-0.00046,9.1e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1,1.9 -7490000,0.78,-0.025,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00027,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.0019,-0.085,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 -7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00026,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 -7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1,2 -7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0062,-0.16,-0.44,-0.14,-3.7e+02,0.00041,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1,2 -7890000,0.78,-0.024,0.0073,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00045,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 -7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.00046,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 -8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.0005,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1,2.1 -8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00049,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 -8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00059,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 -8390000,0.78,-0.024,0.0071,-0.63,-0.18,-0.036,-0.17,-0.49,-0.15,-3.7e+02,0.0006,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 -8490000,0.78,-0.024,0.0071,-0.63,-0.2,-0.039,-0.17,-0.49,-0.15,-3.7e+02,0.00061,-0.0099,-0.00021,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 -8590000,0.78,-0.023,0.0073,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00041,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 -8690000,0.78,-0.023,0.0069,-0.63,-0.24,-0.044,-0.16,-0.53,-0.15,-3.7e+02,0.00042,-0.0096,-0.00019,-0.0019,-0.00051,-0.033,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,29,29,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,8.6e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 -8790000,0.78,-0.023,0.007,-0.63,-0.25,-0.047,-0.15,-0.53,-0.15,-3.7e+02,0.00045,-0.0095,-0.00019,-0.0019,-0.00051,-0.039,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.096,25,25,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,8.5e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.2 -8890000,0.78,-0.023,0.0069,-0.63,-0.27,-0.051,-0.15,-0.55,-0.16,-3.7e+02,0.00044,-0.0094,-0.00018,-0.0019,-0.00051,-0.043,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.095,27,27,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0012,8.4e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.3 -8990000,0.78,-0.023,0.0069,-0.63,-0.28,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00049,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 -9090000,0.78,-0.022,0.0069,-0.63,-0.29,-0.053,-0.14,-0.58,-0.17,-3.7e+02,0.00041,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 -9190000,0.78,-0.022,0.0062,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00042,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.3 -9290000,0.78,-0.022,0.0059,-0.63,-0.31,-0.072,-0.14,-0.62,-0.18,-3.7e+02,0.00044,-0.0086,-0.00016,-0.0018,-6.2e-05,-0.059,-0.11,-0.025,0.5,-0.0028,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 -9390000,0.78,-0.022,0.0058,-0.63,-0.33,-0.081,-0.13,-0.65,-0.19,-3.7e+02,0.00046,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 -9490000,0.78,-0.022,0.0053,-0.63,-0.34,-0.094,-0.13,-0.67,-0.21,-3.7e+02,0.00049,-0.0082,-0.00015,-0.0018,0.00039,-0.067,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 -9590000,0.78,-0.022,0.005,-0.63,-0.34,-0.093,-0.13,-0.7,-0.21,-3.7e+02,0.00034,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 -9690000,0.78,-0.022,0.0052,-0.63,-0.36,-0.09,-0.12,-0.73,-0.22,-3.7e+02,0.00025,-0.008,-0.00014,-0.0021,0.00091,-0.075,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 -9790000,0.78,-0.022,0.0048,-0.63,-0.37,-0.1,-0.11,-0.75,-0.23,-3.7e+02,0.00026,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 -9890000,0.78,-0.021,0.0046,-0.63,-0.38,-0.1,-0.11,-0.78,-0.24,-3.7e+02,0.00017,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 -9990000,0.78,-0.021,0.0046,-0.63,-0.39,-0.1,-0.1,-0.82,-0.25,-3.7e+02,0.00012,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.5 -10090000,0.78,-0.021,0.0043,-0.63,-0.4,-0.1,-0.096,-0.84,-0.26,-3.7e+02,1.3e-05,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 -10190000,0.78,-0.021,0.0046,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-2e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 -10290000,0.78,-0.021,0.0048,-0.63,-0.44,-0.1,-0.083,-0.93,-0.27,-3.7e+02,-4.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 -10390000,0.78,-0.021,0.0046,-0.63,-0.0086,-0.022,0.0097,7.5e-05,-0.0019,-3.7e+02,-3.9e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 -10490000,0.78,-0.021,0.0047,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-6.2e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 -10590000,0.78,-0.02,0.0044,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00025,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 -10690000,0.78,-0.02,0.0043,-0.63,-0.044,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00026,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0027,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 -10790000,0.78,-0.02,0.0039,-0.63,-0.041,-0.01,0.024,0.001,-0.0011,-3.7e+02,-0.00032,-0.0072,-0.00011,-0.00017,0.0013,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 -10890000,0.78,-0.02,0.0038,-0.63,-0.057,-0.013,0.02,-0.0037,-0.0023,-3.7e+02,-0.00033,-0.0071,-0.0001,-0.00011,0.0014,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 -10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.01,0.015,0.00013,-0.0011,-3.7e+02,-0.00036,-0.0069,-9.7e-05,0.0036,-0.00089,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.069,0,0,-3.6e+02,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 -11090000,0.78,-0.02,0.0027,-0.63,-0.06,-0.014,0.02,-0.0048,-0.0026,-3.7e+02,-0.00041,-0.0068,-9.2e-05,0.0036,-0.00047,-0.11,-0.11,-0.025,0.5,-0.003,-0.089,-0.07,0,0,-3.6e+02,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 -11190000,0.78,-0.019,0.0022,-0.63,-0.054,-0.01,0.0082,0.00068,-0.00048,-3.7e+02,-0.00051,-0.0067,-8.9e-05,0.0082,-0.0037,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 -11290000,0.78,-0.019,0.0023,-0.63,-0.07,-0.012,0.008,-0.0058,-0.0016,-3.7e+02,-0.00047,-0.0067,-9.1e-05,0.0083,-0.0039,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.9 -11390000,0.78,-0.019,0.0019,-0.63,-0.064,-0.011,0.0024,0.00033,-0.00038,-3.7e+02,-0.00057,-0.0067,-9e-05,0.012,-0.0076,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 -11490000,0.78,-0.019,0.0021,-0.63,-0.078,-0.012,0.0032,-0.0072,-0.0013,-3.7e+02,-0.00055,-0.0068,-9.3e-05,0.012,-0.0081,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 -11590000,0.78,-0.019,0.0016,-0.63,-0.069,-0.012,-0.0027,-0.0022,-0.00077,-3.7e+02,-0.0006,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,-3.6e+02,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 -11690000,0.78,-0.019,0.0017,-0.63,-0.08,-0.015,-0.0071,-0.0098,-0.0023,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.013,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,-3.6e+02,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 -11790000,0.78,-0.019,0.0011,-0.63,-0.072,-0.011,-0.0089,-0.0062,-0.00016,-3.7e+02,-0.0006,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 -11890000,0.78,-0.019,0.0012,-0.63,-0.084,-0.011,-0.0098,-0.014,-0.0012,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 -11990000,0.78,-0.019,0.0006,-0.63,-0.072,-0.0062,-0.015,-0.009,0.00097,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3 -12090000,0.78,-0.018,0.00044,-0.63,-0.078,-0.0083,-0.021,-0.016,0.00015,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0033,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1 -12190000,0.78,-0.018,-0.00024,-0.62,-0.064,-0.011,-0.016,-0.0086,-0.00028,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 -12290000,0.78,-0.019,-0.00026,-0.62,-0.07,-0.013,-0.015,-0.015,-0.0019,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 -12390000,0.78,-0.018,-0.00067,-0.62,-0.058,-0.011,-0.013,-0.0083,-0.00087,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 -12490000,0.78,-0.018,-0.00053,-0.62,-0.065,-0.013,-0.016,-0.015,-0.002,-3.7e+02,-0.00082,-0.0064,-8.5e-05,0.038,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.2 -12590000,0.78,-0.018,-0.00073,-0.62,-0.06,-0.011,-0.022,-0.013,-0.00087,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 -12690000,0.78,-0.018,-0.00066,-0.62,-0.065,-0.01,-0.025,-0.019,-0.0011,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.025,0.5,-0.0034,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 -12790000,0.78,-0.018,-0.00094,-0.62,-0.061,-0.0093,-0.029,-0.017,-0.001,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 -12890000,0.78,-0.018,-0.00093,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0025,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 -12990000,0.78,-0.018,-0.0014,-0.62,-0.055,-0.0099,-0.028,-0.018,-0.0024,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 -13090000,0.78,-0.018,-0.0013,-0.62,-0.061,-0.0097,-0.028,-0.024,-0.0032,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0012,0.0012,1,1,3.3 -13190000,0.78,-0.018,-0.0016,-0.62,-0.049,-0.0091,-0.025,-0.017,-0.0026,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.036,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00029,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.3 -13290000,0.78,-0.018,-0.0017,-0.62,-0.054,-0.012,-0.022,-0.023,-0.0046,-3.7e+02,-0.00094,-0.0062,-8.3e-05,0.049,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13390000,0.78,-0.018,-0.002,-0.62,-0.044,-0.011,-0.018,-0.016,-0.0038,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00027,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13490000,0.78,-0.018,-0.002,-0.62,-0.047,-0.013,-0.016,-0.021,-0.0055,-3.7e+02,-0.00097,-0.0061,-8e-05,0.052,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.4e-06,2.3e-06,0.017,0.018,0.0087,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13590000,0.78,-0.018,-0.0022,-0.62,-0.038,-0.011,-0.019,-0.014,-0.004,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13690000,0.78,-0.018,-0.0022,-0.62,-0.041,-0.015,-0.023,-0.018,-0.0057,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -13790000,0.78,-0.018,-0.0024,-0.62,-0.03,-0.013,-0.024,-0.0067,-0.0045,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -13890000,0.78,-0.018,-0.0024,-0.62,-0.033,-0.014,-0.029,-0.01,-0.0064,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -13990000,0.78,-0.018,-0.0026,-0.62,-0.026,-0.013,-0.028,-0.0037,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.5 -14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0069,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00028,-0.0049,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14290000,0.78,-0.017,-0.0028,-0.62,-0.022,-0.014,-0.03,-0.0023,-0.0062,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.037,-0.12,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0017,-0.0048,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.06,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14490000,0.78,-0.017,-0.003,-0.62,-0.019,-0.017,-0.035,-0.00051,-0.0068,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0064,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.063,-0.037,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14690000,0.78,-0.017,-0.003,-0.62,-0.023,-0.017,-0.032,-0.0035,-0.0084,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0078,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.019,-0.031,-0.0061,-0.0097,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -14990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0047,-0.0076,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -15090000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0092,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -15190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0074,-3.7e+02,-0.00097,-0.006,-7.5e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -15290000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.017,-0.025,-0.0081,-0.0091,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15390000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.023,-0.0076,-0.0093,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15490000,0.78,-0.017,-0.0029,-0.62,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0098,-0.01,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -15790000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.015,-0.025,-0.0086,-0.0097,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.039,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -15890000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -15990000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.016,-0.018,-0.0079,-0.01,-3.7e+02,-0.001,-0.006,-7.1e-05,0.066,-0.038,-0.13,-0.11,-0.026,0.5,-0.004,-0.091,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -16090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.014,-0.0074,-0.0094,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.065,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0096,0.011,0.0025,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16290000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0098,-0.012,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0095,0.01,0.0024,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.015,-0.014,-0.0074,-0.0089,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0093,0.01,0.0022,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16490000,0.78,-0.017,-0.003,-0.62,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0021,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16590000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.012,-0.018,-0.0097,-0.0064,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.8e-06,2.4e-06,0.0091,0.01,0.002,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16690000,0.78,-0.017,-0.003,-0.62,-0.024,-0.013,-0.014,-0.012,-0.0074,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.009,0.0099,0.0019,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.0094,-0.013,-0.012,-0.0041,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0089,0.0098,0.0018,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16890000,0.78,-0.017,-0.003,-0.62,-0.024,-0.01,-0.01,-0.014,-0.0049,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.036,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0088,0.0097,0.0017,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -16990000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.01,-0.0099,-0.013,-0.0048,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.037,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0087,0.0095,0.0016,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -17090000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.012,-0.0098,-0.015,-0.0059,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.037,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0086,0.0094,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -17190000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.014,-0.011,-0.014,-0.0061,-3.7e+02,-0.0012,-0.006,-6e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.3e-06,1.6e-06,2.4e-06,0.0085,0.0093,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -17290000,0.78,-0.017,-0.0028,-0.62,-0.026,-0.016,-0.0061,-0.016,-0.0072,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0084,0.0092,0.0014,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 -17390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.017,-0.0042,-0.013,-0.0075,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.091,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0083,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 -17490000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0093,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 -17590000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.018,0.003,-0.014,-0.009,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 -17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17890000,0.78,-0.017,-0.003,-0.62,-0.026,-0.023,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -18090000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18190000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18290000,0.78,-0.017,-0.0028,-0.62,-0.025,-0.02,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.036,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18390000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18490000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18590000,0.78,-0.016,-0.0029,-0.62,-0.022,-0.022,0.0062,-0.011,-0.013,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0074,0.0082,0.00076,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18690000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0074,0.0081,0.00074,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18790000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0073,0.008,0.0007,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18890000,0.78,-0.016,-0.003,-0.62,-0.022,-0.024,0.0046,-0.013,-0.015,-3.7e+02,-0.0013,-0.006,-4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0072,0.008,0.00068,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -18990000,0.78,-0.016,-0.003,-0.62,-0.019,-0.023,0.0033,-0.0093,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.061,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.00065,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -19090000,0.78,-0.016,-0.003,-0.62,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.0071,0.0079,0.00063,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -19190000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0063,-0.0072,-0.014,-3.7e+02,-0.0013,-0.006,-3.2e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.0006,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -19290000,0.78,-0.016,-0.003,-0.62,-0.016,-0.024,0.0091,-0.0089,-0.016,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.06,-0.034,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.007,0.0077,0.00058,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 -19390000,0.78,-0.016,-0.003,-0.62,-0.015,-0.022,0.013,-0.008,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.007,0.0077,0.00056,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 -19490000,0.78,-0.016,-0.003,-0.62,-0.015,-0.024,0.0093,-0.0095,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0069,0.0076,0.00055,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 -19590000,0.78,-0.016,-0.0031,-0.62,-0.013,-0.022,0.0085,-0.008,-0.015,-3.7e+02,-0.0013,-0.0059,-2e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,8e-07,9.7e-07,2.3e-06,0.0069,0.0075,0.00052,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,4.9 -19690000,0.78,-0.016,-0.0031,-0.62,-0.014,-0.021,0.01,-0.0088,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.8e-07,9.6e-07,2.3e-06,0.0068,0.0075,0.00051,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -19790000,0.78,-0.016,-0.0031,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.8e-05,0.059,-0.032,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -19890000,0.78,-0.016,-0.0031,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.4e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-4.8e-06,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,-8.7e-08,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20190000,0.78,-0.016,-0.0033,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,5.9e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20290000,0.78,-0.016,-0.0033,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,7.6e-06,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20390000,0.78,-0.016,-0.0033,-0.62,-0.0085,-0.017,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20490000,0.78,-0.016,-0.0033,-0.62,-0.0087,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,9.9e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20590000,0.78,-0.016,-0.0033,-0.62,-0.0082,-0.014,0.014,-0.0085,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.6e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0064,0.007,0.00038,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20690000,0.78,-0.016,-0.0033,-0.62,-0.0089,-0.015,0.015,-0.0094,-0.018,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.6e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0064,0.007,0.00037,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20790000,0.78,-0.016,-0.0034,-0.62,-0.0066,-0.014,0.015,-0.0078,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0063,0.0069,0.00036,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20890000,0.78,-0.016,-0.0034,-0.62,-0.0068,-0.014,0.014,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,2.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.5e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0063,0.0069,0.00035,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -20990000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.012,0.015,-0.008,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0063,0.0069,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -21090000,0.78,-0.016,-0.0034,-0.62,-0.0063,-0.012,0.015,-0.009,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0062,0.0068,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -21190000,0.78,-0.016,-0.0034,-0.62,-0.0064,-0.011,0.014,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.3e-05,0.0001,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00033,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -21290000,0.78,-0.016,-0.0036,-0.62,-0.006,-0.012,0.016,-0.0094,-0.023,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00032,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21390000,0.78,-0.016,-0.0035,-0.62,-0.0054,-0.0074,0.016,-0.0083,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.0061,0.0067,0.00031,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21490000,0.78,-0.016,-0.0035,-0.62,-0.006,-0.0084,0.016,-0.0093,-0.019,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.0061,0.0067,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21590000,0.78,-0.016,-0.0035,-0.62,-0.0046,-0.0067,0.016,-0.0078,-0.015,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.7e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.0061,0.0066,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21690000,0.78,-0.016,-0.0035,-0.62,-0.0062,-0.0078,0.017,-0.009,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.006,0.0066,0.00029,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 -21790000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.0055,0.016,-0.0079,-0.01,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 -21890000,0.78,-0.016,-0.0034,-0.62,-0.0059,-0.0064,0.016,-0.0086,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.6e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 -21990000,0.78,-0.016,-0.0033,-0.62,-0.0057,-0.0036,0.017,-0.008,-0.007,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22090000,0.78,-0.016,-0.0033,-0.62,-0.0054,-0.0052,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22190000,0.78,-0.016,-0.0033,-0.62,-0.0041,-0.0057,0.015,-0.007,-0.0067,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0054,0.016,-0.0077,-0.0071,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22390000,0.78,-0.016,-0.0034,-0.62,-0.0012,-0.0053,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22490000,0.78,-0.016,-0.0034,-0.62,-3.2e-06,-0.006,0.018,-0.0053,-0.0068,-3.7e+02,-0.0014,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22590000,0.78,-0.016,-0.0034,-0.62,0.0018,-0.0049,0.017,-0.0036,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22690000,0.78,-0.016,-0.0034,-0.62,0.0034,-0.0063,0.019,-0.0029,-0.0073,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0027,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22790000,0.78,-0.016,-0.0033,-0.62,0.0044,-0.0055,0.02,-0.0024,-0.0059,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22890000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0065,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0066,0.022,-0.0026,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0063,0.023,-0.0024,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23190000,0.78,-0.016,-0.0033,-0.62,0.0027,-0.0052,0.024,-0.0051,-0.0072,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0057,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23290000,0.78,-0.016,-0.0032,-0.62,0.0023,-0.005,0.025,-0.0054,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23390000,0.78,-0.016,-0.0033,-0.62,-0.001,-0.0047,0.022,-0.0096,-0.0083,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23490000,0.78,-0.013,-0.0054,-0.62,0.0046,-0.0043,-0.011,-0.01,-0.0099,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00021,-0.043,-0.0094,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23690000,0.78,0.0011,-0.0086,-0.62,0.043,0.014,-0.093,-0.007,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23790000,0.78,-0.0026,-0.0061,-0.62,0.064,0.031,-0.15,-0.007,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23890000,0.78,-0.0089,-0.0042,-0.62,0.077,0.043,-0.2,0.00048,-2.4e-05,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.062,-0.03,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23990000,0.78,-0.014,-0.0034,-0.62,0.072,0.043,-0.25,-0.005,-0.0015,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.0019,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -24190000,0.78,-0.01,-0.0054,-0.62,0.07,0.041,-0.35,-0.0059,-0.00031,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -24290000,0.78,-0.0092,-0.0058,-0.62,0.078,0.046,-0.4,0.00062,0.0041,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 -24390000,0.79,-0.0096,-0.0059,-0.62,0.075,0.044,-0.46,-0.012,-0.0023,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 -24490000,0.79,-0.0054,-0.0063,-0.62,0.086,0.051,-0.51,-0.0038,0.0024,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.066,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 -24590000,0.79,-0.0019,-0.0064,-0.62,0.09,0.055,-0.56,-0.017,-0.0064,-3.7e+02,-0.0012,-0.0059,6.4e-05,0.067,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.6e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -24690000,0.79,-0.00099,-0.0064,-0.62,0.11,0.071,-0.64,-0.0079,-0.0014,-3.7e+02,-0.0012,-0.0059,7.1e-05,0.068,-0.03,-0.13,-0.11,-0.026,0.5,-0.0028,-0.09,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -24790000,0.79,-0.0025,-0.0063,-0.62,0.11,0.08,-0.73,-0.027,-0.0061,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0026,-0.09,-0.068,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.018,0.018,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -24890000,0.79,-0.00064,-0.0078,-0.62,0.13,0.095,-0.75,-0.016,0.0027,-3.7e+02,-0.0012,-0.0059,6e-05,0.069,-0.03,-0.13,-0.11,-0.026,0.5,-0.0027,-0.089,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0058,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -24990000,0.79,0.0011,-0.0095,-0.62,0.13,0.1,-0.81,-0.038,-0.0036,-3.7e+02,-0.0011,-0.0059,4.5e-05,0.071,-0.03,-0.13,-0.11,-0.026,0.5,-0.0024,-0.089,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -25090000,0.79,0.00055,-0.0098,-0.62,0.16,0.12,-0.86,-0.024,0.0078,-3.7e+02,-0.0011,-0.0059,4.3e-05,0.071,-0.03,-0.13,-0.11,-0.027,0.5,-0.0025,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -25190000,0.79,-0.0014,-0.0096,-0.61,0.15,0.11,-0.91,-0.068,-0.014,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0022,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 -25290000,0.79,0.0056,-0.011,-0.62,0.18,0.13,-0.96,-0.052,-0.003,-3.7e+02,-0.0011,-0.0058,2.6e-05,0.075,-0.03,-0.13,-0.11,-0.027,0.5,-0.0023,-0.087,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.0011,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 -25390000,0.79,0.012,-0.011,-0.61,0.18,0.13,-1,-0.1,-0.027,-3.7e+02,-0.001,-0.0058,7.6e-06,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0021,-0.087,-0.07,0,0,-3.7e+02,8.1e-05,8.5e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.001,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 -25490000,0.79,0.013,-0.011,-0.61,0.21,0.16,-1.1,-0.081,-0.014,-3.7e+02,-0.001,-0.0058,1.6e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0024,-0.086,-0.069,0,0,-3.7e+02,8.2e-05,8.5e-05,0.046,0.022,0.022,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.2e-05,0.0012,0.00057,0.0011,0.0011,1,1,0.01 -25590000,0.79,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.058,0.0024,-3.7e+02,-0.001,-0.0058,2.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0027,-0.085,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.1e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01 -25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,3e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,-3.7e+02,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01 -25790000,0.79,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0013,0.041,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.079,-0.03,-0.13,-0.12,-0.028,0.5,-0.0035,-0.083,-0.067,0,0,-3.7e+02,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 -25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.04,0.065,-3.7e+02,-0.00099,-0.0058,5.6e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0041,-0.081,-0.066,0,0,-3.7e+02,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 -25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.5e-05,0.079,-0.031,-0.13,-0.12,-0.028,0.5,-0.0045,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01 -26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.079,-0.031,-0.13,-0.12,-0.029,0.5,-0.0046,-0.079,-0.065,0,0,-3.7e+02,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1,0.01 -26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.031,-0.13,-0.13,-0.03,0.5,-0.0054,-0.075,-0.063,0,0,-3.7e+02,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1,0.01 -26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.8e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,-3.7e+02,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00052,0.00091,0.00099,1,1,0.01 -26390000,0.78,0.041,-0.021,-0.62,0.75,0.51,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,8.5e-05,0.08,-0.032,-0.13,-0.13,-0.03,0.49,-0.0063,-0.071,-0.06,0,0,-3.7e+02,8.8e-05,9e-05,0.041,0.042,0.046,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00084,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1,0.01 -26490000,0.78,0.057,-0.027,-0.63,0.84,0.57,-1.3,0.4,0.3,-3.7e+02,-0.00097,-0.0058,9e-05,0.08,-0.032,-0.13,-0.13,-0.031,0.49,-0.0066,-0.069,-0.058,0,0,-3.7e+02,8.9e-05,9.1e-05,0.039,0.045,0.05,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00081,4.9e-05,0.00093,0.00049,0.00084,0.00093,1,1,0.01 -26590000,0.78,0.074,-0.032,-0.62,0.95,0.65,-1.3,0.49,0.36,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.081,-0.032,-0.13,-0.14,-0.032,0.49,-0.0062,-0.066,-0.057,0,0,-3.7e+02,9e-05,9.1e-05,0.038,0.049,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00076,4.6e-05,0.00088,0.00047,0.0008,0.00088,1,1,0.01 -26690000,0.77,0.077,-0.033,-0.63,1.1,0.72,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,0.0001,0.08,-0.032,-0.13,-0.14,-0.033,0.49,-0.0073,-0.061,-0.052,0,0,-3.7e+02,9.1e-05,9.2e-05,0.035,0.053,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00071,4.3e-05,0.00082,0.00045,0.00074,0.00082,1,1,0.01 -26790000,0.77,0.071,-0.032,-0.63,1.2,0.8,-1.3,0.71,0.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.032,-0.13,-0.14,-0.034,0.48,-0.0071,-0.057,-0.049,0,0,-3.7e+02,9.2e-05,9.3e-05,0.032,0.056,0.067,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0057,0.00014,0.00067,4.1e-05,0.00078,0.00042,0.00069,0.00077,1,1,0.01 -26890000,0.77,0.094,-0.039,-0.63,1.3,0.88,-1.3,0.84,0.58,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.035,0.48,-0.0077,-0.053,-0.047,0,0,-3.7e+02,9.2e-05,9.3e-05,0.03,0.059,0.072,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00063,3.9e-05,0.00073,0.00039,0.00065,0.00073,1,1,0.01 -26990000,0.76,0.12,-0.044,-0.63,1.5,0.99,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.032,-0.13,-0.15,-0.036,0.48,-0.0079,-0.047,-0.043,0,0,-3.7e+02,9.3e-05,9.4e-05,0.027,0.063,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00013,0.00057,3.5e-05,0.00066,0.00035,0.00059,0.00066,1,1,0.01 -27090000,0.76,0.12,-0.045,-0.63,1.7,1.1,-1.3,1.1,0.77,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.037,0.47,-0.0078,-0.043,-0.039,0,0,-3.7e+02,9.3e-05,9.4e-05,0.024,0.067,0.085,0.0061,0.36,0.37,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00052,3.2e-05,0.00059,0.00032,0.00053,0.00059,1,1,0.01 -27190000,0.76,0.11,-0.042,-0.63,1.9,1.2,-1.2,1.3,0.89,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.038,0.47,-0.0074,-0.04,-0.035,0,0,-3.7e+02,9.4e-05,9.5e-05,0.021,0.071,0.091,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00048,3e-05,0.00055,0.00029,0.00049,0.00054,1,1,0.01 -27290000,0.77,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0075,-0.036,-0.033,0,0,-3.7e+02,9.4e-05,9.5e-05,0.019,0.072,0.094,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00045,2.9e-05,0.00052,0.00026,0.00046,0.00051,1,1,0.01 -27390000,0.77,0.078,-0.033,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.17,-0.039,0.47,-0.0074,-0.035,-0.032,0,0,-3.7e+02,9.5e-05,9.6e-05,0.017,0.073,0.094,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00043,2.8e-05,0.0005,0.00023,0.00044,0.00049,1,1,0.01 -27490000,0.77,0.062,-0.029,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0071,-0.034,-0.032,0,0,-3.7e+02,9.6e-05,9.6e-05,0.015,0.074,0.093,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00042,2.7e-05,0.00049,0.00021,0.00043,0.00048,1,1,0.01 -27590000,0.77,0.05,-0.025,-0.63,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.028,-0.13,-0.17,-0.039,0.47,-0.0066,-0.033,-0.031,0,0,-3.7e+02,9.6e-05,9.7e-05,0.014,0.074,0.092,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00041,2.6e-05,0.00048,0.0002,0.00042,0.00048,1,1,0.01 -27690000,0.77,0.048,-0.025,-0.63,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.028,-0.13,-0.17,-0.04,0.47,-0.0062,-0.032,-0.031,0,0,-3.7e+02,9.7e-05,9.7e-05,0.013,0.074,0.09,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.0004,2.6e-05,0.00048,0.00019,0.00042,0.00047,1,1,0.01 -27790000,0.77,0.05,-0.025,-0.63,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,9.7e-05,0.082,-0.027,-0.13,-0.17,-0.04,0.47,-0.0056,-0.032,-0.031,0,0,-3.7e+02,9.8e-05,9.8e-05,0.012,0.074,0.089,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00039,2.6e-05,0.00047,0.00017,0.00041,0.00047,1,1,0.01 -27890000,0.77,0.048,-0.024,-0.63,2.3,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,9.7e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.46,-0.0056,-0.031,-0.031,0,0,-3.7e+02,9.9e-05,9.8e-05,0.011,0.075,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00039,2.5e-05,0.00047,0.00016,0.0004,0.00047,1,1,0.01 -27990000,0.77,0.044,-0.023,-0.63,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.5e-05,0.082,-0.026,-0.13,-0.17,-0.04,0.47,-0.0056,-0.031,-0.031,0,0,-3.7e+02,0.0001,9.9e-05,0.01,0.075,0.088,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.5e-05,0.00047,0.00016,0.0004,0.00046,1,1,0.01 -28090000,0.78,0.058,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,-3.7e+02,0.0001,9.9e-05,0.0096,0.076,0.088,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00038,2.4e-05,0.00046,0.00015,0.00039,0.00046,1,1,0.01 -28190000,0.77,0.071,-0.031,-0.63,2.4,1.7,-0.93,3.5,2.4,-3.7e+02,-0.00095,-0.0058,8.9e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.005,-0.03,-0.03,0,0,-3.7e+02,0.0001,0.0001,0.0091,0.077,0.088,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00037,2.4e-05,0.00046,0.00014,0.00038,0.00045,1,1,0.01 -28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.5e-05,0.083,-0.024,-0.13,-0.17,-0.04,0.46,-0.0048,-0.029,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1,0.01 -28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,8e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0082,0.077,0.084,0.0061,0.75,0.79,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 -28490000,0.78,0.0015,-0.0059,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.5e-05,0.083,-0.023,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 -28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.083,-0.022,-0.13,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 -28690000,0.78,-0.0032,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,7e-05,0.082,-0.022,-0.12,-0.17,-0.041,0.46,-0.0044,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 -28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.5e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1,0.01 -28890000,0.78,-0.0033,-0.0037,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6.1e-05,0.082,-0.021,-0.12,-0.17,-0.041,0.46,-0.0041,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1,0.01 -28990000,0.78,-0.0028,-0.0039,-0.62,2.1,1.5,0.98,5.4,3.8,-3.7e+02,-0.001,-0.0058,5.5e-05,0.081,-0.02,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 -29090000,0.78,-0.0024,-0.004,-0.62,2,1.5,0.97,5.6,4,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0037,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0063,0.081,0.085,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 -29190000,0.78,-0.0021,-0.0041,-0.62,2,1.5,0.97,5.8,4.1,-3.7e+02,-0.001,-0.0058,5e-05,0.081,-0.019,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0061,0.083,0.087,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 -29290000,0.78,-0.0013,-0.0044,-0.62,1.9,1.5,0.99,6,4.2,-3.7e+02,-0.001,-0.0058,4.6e-05,0.08,-0.019,-0.12,-0.17,-0.041,0.46,-0.0036,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.00011,0.00037,0.00043,1,1,0.01 -29390000,0.78,9e-05,-0.0046,-0.62,1.9,1.4,1,6.2,4.4,-3.7e+02,-0.001,-0.0058,3.9e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 -29490000,0.78,0.0013,-0.005,-0.62,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.7e-05,0.08,-0.018,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 -29590000,0.78,0.0023,-0.0052,-0.62,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0057,3.4e-05,0.079,-0.017,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 -29690000,0.78,0.003,-0.0055,-0.62,1.7,1.4,0.99,6.7,4.8,-3.7e+02,-0.001,-0.0057,2.9e-05,0.079,-0.016,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.9e-05,0.00037,0.00043,1,1,0.01 -29790000,0.78,0.0034,-0.0056,-0.62,1.7,1.4,0.98,6.9,5,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.015,-0.12,-0.17,-0.041,0.46,-0.0031,-0.028,-0.027,0,0,-3.7e+02,0.00011,0.0001,0.0054,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.8e-05,0.00037,0.00042,1,1,0.01 -29890000,0.78,0.0036,-0.0057,-0.62,1.7,1.3,0.97,7.1,5.1,-3.7e+02,-0.001,-0.0057,2e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.7e-05,0.00037,0.00042,1,1,0.01 -29990000,0.78,0.0036,-0.0057,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.014,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1,0.01 -30090000,0.78,0.0035,-0.0057,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1.2e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1,0.01 -30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.3e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1,0.01 -30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,1e-05,0.078,-0.013,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01 -30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,5.9e-06,0.077,-0.012,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.11,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 -30490000,0.78,0.0025,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,4.8e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 -30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,2.7e-06,0.076,-0.011,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01 -30690000,0.78,0.0017,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-6.4e-07,0.076,-0.0098,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 -30790000,0.78,0.0013,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-3.8e-06,0.076,-0.0096,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 -30890000,0.78,0.00091,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-6.7e-06,0.075,-0.0088,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01 -30990000,0.78,0.00032,-0.005,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1e-05,0.075,-0.008,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1,0.01 -31090000,0.78,-0.00023,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.5e-05,0.074,-0.0073,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 -31190000,0.78,-0.00064,-0.0047,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0064,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 -31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2e-05,0.074,-0.0057,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 -31390000,0.78,-0.002,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.074,-0.0051,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 -31490000,0.78,-0.0026,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-2.9e-05,0.073,-0.0044,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 -31590000,0.78,-0.0029,-0.0042,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3e-05,0.073,-0.0037,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1,0.01 -31690000,0.78,-0.0037,-0.004,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.072,-0.003,-0.12,-0.17,-0.041,0.46,-0.0021,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31790000,0.78,-0.0044,-0.0038,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.4e-05,0.072,-0.0021,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31890000,0.78,-0.0051,-0.0037,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-3.8e-05,0.071,-0.0012,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.071,-0.00029,-0.12,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1,0.01 -32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.95,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-4.7e-05,0.07,0.00041,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-5.7e-05,0.07,0.0014,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.1e-05,0.069,0.0024,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.1e-05,0.069,0.003,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32490000,0.78,-0.009,-0.0029,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.068,0.0038,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 -32590000,0.78,-0.0093,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0041,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 -32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.067,0.0047,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 -32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.067,0.0051,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 -32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.066,0.0056,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 -32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0062,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 -33090000,0.79,-0.0092,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0064,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 -33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.065,0.0065,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1,0.01 -33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.065,0.0064,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1,0.01 -33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.064,0.006,-0.11,-0.18,-0.041,0.46,-0.0009,-0.027,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8e-05,0.00032,0.00039,1,1,0.01 -33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.3e-05,0.064,0.0061,-0.11,-0.18,-0.043,0.46,-0.0004,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01 -33590000,0.99,-0.0083,-0.00011,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.8e-05,0.064,0.0061,-0.11,-0.19,-0.044,0.46,0.00035,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01 -33690000,1,-0.012,0.0041,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.064,0.0061,-0.11,-0.19,-0.045,0.46,0.00018,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01 -33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00053,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01 -33890000,0.93,-0.013,0.0086,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.1e-05,0.064,0.0061,-0.11,-0.2,-0.046,0.46,0.00075,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01 -33990000,0.86,-0.015,0.0072,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0058,-0.11,-0.2,-0.046,0.46,0.00053,-0.0039,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1,0.01 -34090000,0.8,-0.016,0.0064,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0052,-0.11,-0.2,-0.046,0.46,0.0002,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01 -34190000,0.75,-0.014,0.0071,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01 -34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0047,-0.11,-0.2,-0.047,0.46,0.00016,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01 -34390000,0.69,-0.0077,0.01,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0044,-0.11,-0.2,-0.047,0.46,9.4e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01 -34490000,0.67,-0.0055,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0043,-0.11,-0.2,-0.047,0.46,5.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01 -34590000,0.66,-0.0041,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0042,-0.11,-0.2,-0.047,0.46,-4.5e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01 -34690000,0.65,-0.0033,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0042,-0.11,-0.2,-0.047,0.46,1.8e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01 -34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0041,-0.11,-0.2,-0.047,0.46,0.00014,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1,0.01 -34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0039,-0.11,-0.2,-0.047,0.46,8.8e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01 -34990000,0.64,-0.0061,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1,0.01 -35090000,0.64,-0.0062,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00022,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1,0.01 -35190000,0.64,-0.0063,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00026,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01 -35290000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.0003,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01 -35390000,0.64,-0.0064,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00038,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01 -35490000,0.64,-0.0065,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00045,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01 -35590000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00042,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 -35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 -35790000,0.64,-0.0065,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 -35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00049,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 -35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0038,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 -36090000,0.64,-0.0066,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00049,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 -36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0042,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 -36290000,0.64,-0.0066,0.02,0.77,-3.5,-3.6,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 -36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.004,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 -36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0039,-0.11,-0.2,-0.047,0.46,0.00055,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 -36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00058,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 -36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00061,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 -36790000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0039,-0.11,-0.2,-0.047,0.46,0.00064,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 -36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0041,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 -36990000,0.64,-0.0069,0.021,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0042,-0.11,-0.2,-0.047,0.46,0.00069,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 -37090000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.014,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 -37190000,0.64,-0.0069,0.021,0.77,-3.8,-4.2,-0.0055,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 -37290000,0.64,-0.0069,0.021,0.77,-3.8,-4.3,0.003,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.7e-05,0.067,0.0043,-0.11,-0.2,-0.047,0.46,0.00069,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 -37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00071,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 -37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.7e-05,0.068,0.0042,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 -37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,8.3e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 -37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.7e-05,0.068,0.0043,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 -37790000,0.64,-0.007,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.069,0.0041,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 -37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.2e-05,0.069,0.0043,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 -37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.2e-05,0.069,0.0041,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 -38090000,0.64,-0.0071,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.069,0.004,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 -38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.069,0.004,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 -38290000,0.64,-0.0071,0.021,0.77,-4.1,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.069,0.004,-0.11,-0.2,-0.047,0.46,0.00078,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 -38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.069,0.0038,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 -38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.069,0.0039,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 -38590000,0.64,-0.007,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.069,0.0041,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 -38690000,0.64,-0.007,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0043,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 -38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.068,0.0041,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 -38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.069,0.0042,-0.11,-0.2,-0.047,0.46,0.0008,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 +1590000,1,-0.01,-0.014,0.00014,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.011,-0.014,0.00012,0.028,-0.00014,-0.19,0.0045,0.00062,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.011,-0.014,9.3e-05,0.035,-0.002,-0.2,0.0076,0.00053,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.011,-0.015,7.3e-05,0.043,-0.0033,-0.22,0.011,0.00027,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,8.4e-05,0.036,-0.0048,-0.23,0.0082,-0.00029,-0.19,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +2090000,1,-0.011,-0.014,4.5e-05,0.041,-0.0073,-0.24,0.012,-0.00089,-0.22,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +2190000,1,-0.011,-0.014,5.6e-05,0.033,-0.007,-0.26,0.0079,-0.00099,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,4.2e-05,0.039,-0.0095,-0.27,0.011,-0.0018,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,5.9e-05,0.03,-0.0089,-0.29,0.0074,-0.0015,-0.3,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.013,4.1e-05,0.035,-0.011,-0.3,0.011,-0.0025,-0.32,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.011,-0.013,5.5e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.011,-0.013,5.1e-05,0.03,-0.011,-0.33,0.0097,-0.0028,-0.39,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.011,-0.013,4.5e-05,0.023,-0.0096,-0.34,0.0062,-0.002,-0.42,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.011,-0.013,-5.4e-06,0.027,-0.012,-0.35,0.0087,-0.003,-0.46,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.011,-0.013,4.2e-05,0.022,-0.0098,-0.36,0.0057,-0.0021,-0.49,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.011,-0.013,4.4e-05,0.025,-0.011,-0.38,0.008,-0.0032,-0.53,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.011,-0.013,-1.3e-05,0.02,-0.009,-0.39,0.0053,-0.0022,-0.57,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.011,-0.013,2.6e-05,0.023,-0.011,-0.4,0.0074,-0.0032,-0.61,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.011,-0.012,-2.6e-06,0.018,-0.0095,-0.42,0.0049,-0.0022,-0.65,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.011,-0.013,-1.1e-05,0.022,-0.012,-0.43,0.0069,-0.0033,-0.69,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.011,-0.012,1.2e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.011,-0.012,0.00013,0.019,-0.014,-0.46,0.0065,-0.0036,-0.78,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.011,-0.012,0.00018,0.016,-0.014,-0.47,0.0044,-0.0027,-0.82,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.011,-0.012,0.00015,0.017,-0.015,-0.48,0.006,-0.0041,-0.87,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.011,-0.012,0.00015,0.02,-0.017,-0.5,0.0079,-0.0057,-0.92,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.011,-0.012,0.00014,0.017,-0.015,-0.51,0.0056,-0.0042,-0.97,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.011,-0.012,0.00012,0.02,-0.017,-0.53,0.0075,-0.0058,-1,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.01,-0.012,7.2e-05,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.01,-0.012,9.4e-05,0.018,-0.013,-0.55,0.0071,-0.0055,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.01,-0.012,0.00015,0.014,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.01,-0.012,0.00018,0.017,-0.012,-0.58,0.0067,-0.0049,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.01,-0.012,0.00018,0.014,-0.01,-0.6,0.0048,-0.0035,-1.3,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.01,-0.012,0.00017,0.015,-0.012,-0.61,0.0062,-0.0045,-1.4,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.01,-0.011,0.00016,0.012,-0.01,-0.63,0.0044,-0.0033,-1.4,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.01,-0.012,0.00014,0.015,-0.011,-0.64,0.0058,-0.0043,-1.5,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.01,-0.011,0.00018,0.011,-0.0085,-0.66,0.0041,-0.0031,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.01,-0.011,0.00021,0.013,-0.0098,-0.67,0.0053,-0.004,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.01,-0.011,0.0002,0.0086,-0.0073,-0.68,0.0037,-0.0029,-1.7,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0099,-0.011,0.00026,0.0081,-0.0081,-0.7,0.0045,-0.0036,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0098,-0.011,0.00027,0.0055,-0.0062,-0.71,0.0031,-0.0026,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0097,-0.011,0.00025,0.0061,-0.0066,-0.73,0.0036,-0.0032,-1.9,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0096,-0.011,0.00032,0.0041,-0.0038,-0.74,0.0025,-0.0022,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0095,-0.011,0.00032,0.0044,-0.0028,-0.75,0.0029,-0.0025,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0095,-0.011,0.00029,0.0038,-0.00092,0.0028,0.002,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0094,-0.011,0.00032,0.0041,0.00056,0.015,0.0023,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0094,-0.011,0.0003,0.0051,0.0017,-0.011,0.0028,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0094,-0.011,0.00022,0.0038,0.0042,-0.005,0.002,-0.00053,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0094,-0.011,0.0002,0.005,0.0043,-0.012,0.0025,-0.00012,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-3.6e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0093,-0.011,0.00022,0.0043,0.0053,-0.05,0.0019,0.00038,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-3.6e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0093,-0.011,0.00022,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.00015,0.0037,0.0055,-0.099,0.0018,0.001,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,3e-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,7.8e-05,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.78,-0.024,0.0048,-0.62,-0.22,-0.05,-0.11,-0.13,-0.029,-3.7e+02,-0.00035,-0.01,-0.0002,0,0,0.0012,-0.092,-0.021,0.51,-0.00079,-0.075,-0.061,0,0,-3.6e+02,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1,1.7 +6890000,0.78,-0.025,0.0057,-0.62,-0.27,-0.065,-0.12,-0.16,-0.04,-3.7e+02,-0.00017,-0.011,-0.00022,0,0,0.0012,-0.1,-0.023,0.51,-0.0012,-0.083,-0.067,0,0,-3.6e+02,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00025,0.0013,0.00089,0.0014,0.0013,1,1,1.8 +6990000,0.78,-0.025,0.0059,-0.62,-0.3,-0.076,-0.12,-0.2,-0.05,-3.7e+02,-7e-05,-0.011,-0.00022,-0.00057,-7.3e-05,0.00095,-0.1,-0.024,0.5,-0.0016,-0.084,-0.067,0,0,-3.6e+02,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1,1.8 +7090000,0.78,-0.025,0.0062,-0.62,-0.33,-0.088,-0.12,-0.23,-0.063,-3.7e+02,4.4e-05,-0.011,-0.00023,-0.0013,-0.0003,0.00061,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00016,0.0013,0.00083,0.0014,0.0013,1,1,1.8 +7190000,0.78,-0.025,0.0064,-0.62,-0.36,-0.097,-0.15,-0.26,-0.075,-3.7e+02,0.00011,-0.011,-0.00023,-0.0017,-0.00046,0.00083,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00082,0.0013,0.0013,1,1,1.8 +7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.098,-0.14,-0.3,-0.082,-3.7e+02,5.3e-05,-0.011,-0.00022,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1,1.9 +7390000,0.78,-0.024,0.0068,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,7.4e-05,-0.011,-0.00022,-0.0017,-0.00046,8.6e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1,1.9 +7490000,0.78,-0.024,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00021,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 +7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 +7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00029,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1,2 +7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0061,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1,2 +7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 +7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.0004,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 +8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.00044,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1,2.1 +8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 +8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 +8390000,0.78,-0.024,0.007,-0.63,-0.18,-0.036,-0.17,-0.48,-0.15,-3.7e+02,0.00055,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 +8490000,0.78,-0.024,0.007,-0.63,-0.2,-0.04,-0.17,-0.49,-0.15,-3.7e+02,0.00056,-0.0099,-0.0002,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 +8590000,0.78,-0.023,0.0072,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 +8690000,0.78,-0.023,0.0068,-0.63,-0.23,-0.044,-0.16,-0.53,-0.15,-3.7e+02,0.00037,-0.0096,-0.00019,-0.0019,-0.00051,-0.033,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,29,29,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,8.6e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 +8790000,0.78,-0.023,0.0069,-0.63,-0.25,-0.047,-0.15,-0.53,-0.15,-3.7e+02,0.0004,-0.0095,-0.00019,-0.0019,-0.00051,-0.039,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.096,25,25,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,8.5e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.2 +8890000,0.78,-0.023,0.0068,-0.63,-0.27,-0.051,-0.15,-0.55,-0.16,-3.7e+02,0.0004,-0.0094,-0.00018,-0.0019,-0.00051,-0.043,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.095,27,27,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0012,8.4e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.3 +8990000,0.78,-0.023,0.0068,-0.63,-0.27,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00045,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0026,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 +9090000,0.78,-0.022,0.0068,-0.63,-0.29,-0.054,-0.14,-0.58,-0.17,-3.7e+02,0.00037,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 +9190000,0.78,-0.022,0.0061,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00038,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.3 +9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.5e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 +9390000,0.78,-0.022,0.0057,-0.63,-0.33,-0.082,-0.13,-0.65,-0.19,-3.7e+02,0.00043,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 +9490000,0.78,-0.022,0.0052,-0.63,-0.33,-0.095,-0.13,-0.67,-0.21,-3.7e+02,0.00046,-0.0082,-0.00015,-0.0018,0.00038,-0.067,-0.11,-0.025,0.5,-0.0032,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 +9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 +9690000,0.78,-0.022,0.0051,-0.63,-0.36,-0.092,-0.12,-0.73,-0.22,-3.7e+02,0.00022,-0.008,-0.00014,-0.0021,0.0009,-0.075,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 +9790000,0.78,-0.022,0.0047,-0.63,-0.37,-0.1,-0.11,-0.75,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 +9890000,0.78,-0.021,0.0045,-0.63,-0.37,-0.11,-0.11,-0.78,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,2.9e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 +9990000,0.78,-0.021,0.0045,-0.63,-0.39,-0.11,-0.1,-0.81,-0.25,-3.7e+02,9.8e-05,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.0031,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.5 +10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.1e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 +10190000,0.78,-0.021,0.0045,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-4.1e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 +10290000,0.78,-0.021,0.0047,-0.63,-0.44,-0.1,-0.083,-0.92,-0.27,-3.7e+02,-6.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 +10390000,0.78,-0.021,0.0045,-0.63,-0.0085,-0.022,0.0097,8e-05,-0.0019,-3.7e+02,-5.8e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 +10490000,0.78,-0.021,0.0046,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-8e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 +10590000,0.78,-0.02,0.0043,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00026,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 +10690000,0.78,-0.02,0.0042,-0.63,-0.043,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 +10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00016,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 +10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.0001,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 +10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.011,0.015,0.00017,-0.0012,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0036,-0.00085,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.069,0,0,-3.6e+02,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 +11090000,0.78,-0.02,0.0026,-0.63,-0.06,-0.015,0.02,-0.0047,-0.0027,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0037,-0.00042,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 +11190000,0.78,-0.019,0.0021,-0.63,-0.053,-0.011,0.0082,0.00075,-0.00057,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.0082,-0.0036,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 +11290000,0.78,-0.019,0.0022,-0.63,-0.069,-0.013,0.008,-0.0056,-0.0018,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0083,-0.0038,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 +11390000,0.78,-0.019,0.0018,-0.63,-0.064,-0.011,0.0024,0.00037,-0.00044,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 +11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0015,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 +11590000,0.78,-0.019,0.0015,-0.63,-0.069,-0.012,-0.0027,-0.0021,-0.00084,-3.7e+02,-0.00061,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,-3.6e+02,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 +11690000,0.78,-0.019,0.0016,-0.63,-0.08,-0.016,-0.0071,-0.0097,-0.0025,-3.7e+02,-0.00057,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,-3.6e+02,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 +11790000,0.78,-0.019,0.001,-0.63,-0.072,-0.011,-0.0089,-0.0061,-0.00025,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 +11890000,0.78,-0.019,0.0011,-0.63,-0.083,-0.012,-0.0098,-0.014,-0.0014,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 +11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0069,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3 +12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.3e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1 +12190000,0.78,-0.018,-0.00031,-0.62,-0.064,-0.011,-0.016,-0.0085,-0.0004,-3.7e+02,-0.00082,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 +12290000,0.78,-0.019,-0.00032,-0.62,-0.07,-0.014,-0.015,-0.015,-0.0021,-3.7e+02,-0.00079,-0.0064,-8.3e-05,0.033,-0.021,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 +12390000,0.78,-0.018,-0.00073,-0.62,-0.057,-0.012,-0.013,-0.0083,-0.001,-3.7e+02,-0.00086,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 +12490000,0.78,-0.018,-0.00059,-0.62,-0.064,-0.013,-0.016,-0.015,-0.0022,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.038,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.2 +12590000,0.78,-0.018,-0.00079,-0.62,-0.06,-0.011,-0.022,-0.013,-0.001,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.039,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 +12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0014,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 +12790000,0.78,-0.018,-0.001,-0.62,-0.061,-0.0098,-0.029,-0.017,-0.0012,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.04,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 +12890000,0.78,-0.018,-0.00099,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0027,-3.7e+02,-0.00093,-0.0063,-8.2e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 +12990000,0.78,-0.018,-0.0015,-0.62,-0.055,-0.01,-0.028,-0.018,-0.0026,-3.7e+02,-0.00097,-0.0062,-8e-05,0.045,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 +13090000,0.78,-0.018,-0.0014,-0.62,-0.061,-0.01,-0.028,-0.024,-0.0034,-3.7e+02,-0.00095,-0.0063,-8.3e-05,0.045,-0.032,-0.11,-0.11,-0.025,0.5,-0.0039,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0012,0.0012,1,1,3.3 +13190000,0.78,-0.018,-0.0017,-0.62,-0.049,-0.0096,-0.025,-0.017,-0.0028,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.035,-0.11,-0.11,-0.025,0.5,-0.0039,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00029,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.3 +13290000,0.78,-0.018,-0.0018,-0.62,-0.053,-0.013,-0.022,-0.022,-0.0049,-3.7e+02,-0.00095,-0.0062,-8.2e-05,0.05,-0.034,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13390000,0.78,-0.018,-0.002,-0.62,-0.044,-0.012,-0.018,-0.016,-0.004,-3.7e+02,-0.00099,-0.0062,-8e-05,0.051,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00027,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13490000,0.78,-0.018,-0.0021,-0.62,-0.046,-0.013,-0.016,-0.021,-0.0057,-3.7e+02,-0.00097,-0.0062,-7.9e-05,0.052,-0.034,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.4e-06,2.3e-06,0.017,0.018,0.0087,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13590000,0.78,-0.018,-0.0022,-0.62,-0.038,-0.012,-0.019,-0.014,-0.0042,-3.7e+02,-0.001,-0.0062,-8e-05,0.053,-0.036,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 +13690000,0.78,-0.018,-0.0023,-0.62,-0.041,-0.015,-0.023,-0.018,-0.006,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.035,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +13790000,0.78,-0.018,-0.0024,-0.62,-0.029,-0.013,-0.024,-0.0067,-0.0046,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +13890000,0.78,-0.018,-0.0025,-0.62,-0.033,-0.015,-0.029,-0.01,-0.0066,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0071,-3.7e+02,-0.0011,-0.0061,-7.6e-05,0.056,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00023,-0.005,-3.7e+02,-0.0011,-0.0061,-7.5e-05,0.058,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14290000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.015,-0.03,-0.0022,-0.0063,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.057,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.005,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14490000,0.78,-0.017,-0.0031,-0.62,-0.019,-0.018,-0.035,-0.00044,-0.0069,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0065,-3.7e+02,-0.001,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14690000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.017,-0.032,-0.0034,-0.0085,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.064,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.019,-0.031,-0.006,-0.0098,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +14990000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.016,-0.027,-0.0046,-0.0077,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +15090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0093,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +15190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0075,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0043,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 +15290000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.025,-0.0081,-0.0092,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.067,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.9 +15390000,0.78,-0.017,-0.0031,-0.62,-0.025,-0.018,-0.023,-0.0075,-0.0094,-3.7e+02,-0.001,-0.006,-7e-05,0.067,-0.035,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0097,-0.01,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.012,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +15890000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +15990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.018,-0.0078,-0.01,-3.7e+02,-0.0011,-0.006,-7e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +16090000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0099,-0.012,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16190000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.016,-0.014,-0.0073,-0.0094,-3.7e+02,-0.0011,-0.006,-6.6e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0096,0.011,0.0025,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16290000,0.78,-0.017,-0.0032,-0.62,-0.026,-0.018,-0.015,-0.0098,-0.012,-3.7e+02,-0.0011,-0.0059,-6.4e-05,0.066,-0.034,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0095,0.01,0.0024,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16390000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.015,-0.014,-0.0073,-0.009,-3.7e+02,-0.0011,-0.006,-6.3e-05,0.065,-0.034,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0093,0.01,0.0022,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 +16490000,0.78,-0.017,-0.0031,-0.62,-0.022,-0.016,-0.017,-0.0093,-0.01,-3.7e+02,-0.0011,-0.006,-6.3e-05,0.064,-0.034,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0021,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16590000,0.78,-0.017,-0.0031,-0.62,-0.022,-0.012,-0.018,-0.0097,-0.0065,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.034,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.8e-06,2.4e-06,0.0091,0.01,0.002,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16690000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.013,-0.014,-0.012,-0.0075,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.009,0.0099,0.0019,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.0094,-0.013,-0.012,-0.0042,-3.7e+02,-0.0011,-0.006,-5.9e-05,0.065,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0089,0.0098,0.0018,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 +16890000,0.78,-0.017,-0.003,-0.62,-0.024,-0.01,-0.01,-0.014,-0.005,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0088,0.0097,0.0017,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +16990000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.01,-0.0099,-0.013,-0.0049,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0087,0.0095,0.0016,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +17090000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.012,-0.0098,-0.015,-0.0059,-3.7e+02,-0.0012,-0.006,-6e-05,0.063,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0086,0.0094,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +17190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.014,-0.011,-0.013,-0.0062,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.3e-06,1.6e-06,2.4e-06,0.0085,0.0093,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 +17290000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.0061,-0.016,-0.0073,-3.7e+02,-0.0012,-0.006,-6e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0084,0.0093,0.0014,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.4 +17390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.017,-0.0042,-0.013,-0.0075,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.091,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0083,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 +17490000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0094,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 +17590000,0.78,-0.017,-0.003,-0.62,-0.024,-0.018,0.003,-0.013,-0.009,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 +17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +18090000,0.78,-0.017,-0.003,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18290000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0072,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.063,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18490000,0.78,-0.017,-0.003,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.7e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18590000,0.78,-0.016,-0.003,-0.62,-0.022,-0.022,0.0062,-0.011,-0.013,-3.7e+02,-0.0013,-0.006,-4.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0074,0.0082,0.00076,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18690000,0.78,-0.017,-0.003,-0.62,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.063,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0074,0.0081,0.00074,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18790000,0.78,-0.016,-0.0029,-0.62,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0073,0.008,0.0007,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 +18890000,0.78,-0.016,-0.003,-0.62,-0.022,-0.023,0.0046,-0.013,-0.015,-3.7e+02,-0.0013,-0.006,-3.9e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0072,0.008,0.00068,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +18990000,0.78,-0.016,-0.003,-0.62,-0.019,-0.023,0.0033,-0.0092,-0.013,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.061,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.00065,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +19090000,0.78,-0.016,-0.003,-0.62,-0.018,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.061,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.0071,0.0079,0.00063,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +19190000,0.78,-0.016,-0.0031,-0.62,-0.015,-0.024,0.0063,-0.0072,-0.014,-3.7e+02,-0.0013,-0.006,-3.1e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.0006,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 +19290000,0.78,-0.016,-0.003,-0.62,-0.016,-0.024,0.0091,-0.0089,-0.016,-3.7e+02,-0.0013,-0.006,-3.2e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.007,0.0077,0.00058,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 +19390000,0.78,-0.016,-0.003,-0.62,-0.015,-0.022,0.013,-0.0079,-0.014,-3.7e+02,-0.0013,-0.006,-2.8e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.007,0.0077,0.00056,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 +19490000,0.78,-0.016,-0.0031,-0.62,-0.015,-0.024,0.0093,-0.0095,-0.017,-3.7e+02,-0.0013,-0.006,-2.5e-05,0.061,-0.032,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0069,0.0076,0.00055,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 +19590000,0.78,-0.016,-0.0032,-0.62,-0.013,-0.022,0.0085,-0.0079,-0.015,-3.7e+02,-0.0013,-0.0059,-1.8e-05,0.061,-0.031,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,7.9e-07,9.7e-07,2.3e-06,0.0069,0.0075,0.00052,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 +19690000,0.78,-0.016,-0.0031,-0.62,-0.013,-0.021,0.01,-0.0088,-0.017,-3.7e+02,-0.0013,-0.006,-2e-05,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.8e-07,9.6e-07,2.3e-06,0.0068,0.0075,0.00051,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,5 +19790000,0.78,-0.016,-0.0032,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.6e-05,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 +19890000,0.78,-0.016,-0.0032,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.3e-05,0.061,-0.031,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 +19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-3.8e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 +20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,1e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,7e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20290000,0.78,-0.016,-0.0034,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,8.7e-06,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20390000,0.78,-0.016,-0.0033,-0.62,-0.0084,-0.016,0.017,-0.009,-0.017,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20490000,0.78,-0.016,-0.0034,-0.62,-0.0087,-0.017,0.017,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20590000,0.78,-0.016,-0.0033,-0.62,-0.0081,-0.014,0.014,-0.0085,-0.016,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.5e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0064,0.007,0.00038,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20690000,0.78,-0.016,-0.0034,-0.62,-0.0089,-0.015,0.015,-0.0094,-0.018,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.6e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0064,0.007,0.00037,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20790000,0.78,-0.016,-0.0034,-0.62,-0.0065,-0.014,0.015,-0.0078,-0.016,-3.7e+02,-0.0013,-0.0059,1.9e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0063,0.0069,0.00036,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 +20890000,0.78,-0.016,-0.0035,-0.62,-0.0068,-0.014,0.014,-0.0083,-0.018,-3.7e+02,-0.0013,-0.0059,2.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.5e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0063,0.0069,0.00035,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +20990000,0.78,-0.016,-0.0035,-0.62,-0.0052,-0.012,0.015,-0.008,-0.018,-3.7e+02,-0.0013,-0.0059,2.5e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0063,0.0069,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +21090000,0.78,-0.016,-0.0035,-0.62,-0.0063,-0.012,0.015,-0.0089,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0062,0.0068,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +21190000,0.78,-0.016,-0.0035,-0.62,-0.0064,-0.011,0.014,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,2.8e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.3e-05,0.0001,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00033,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 +21290000,0.78,-0.016,-0.0036,-0.62,-0.0059,-0.012,0.016,-0.0094,-0.023,-3.7e+02,-0.0013,-0.0059,3.3e-05,0.062,-0.027,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.3e-05,0.0001,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00032,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21390000,0.78,-0.016,-0.0036,-0.62,-0.0053,-0.0073,0.016,-0.0082,-0.017,-3.7e+02,-0.0013,-0.0059,3.6e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.0061,0.0067,0.00031,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21490000,0.78,-0.016,-0.0036,-0.62,-0.006,-0.0083,0.016,-0.0093,-0.019,-3.7e+02,-0.0013,-0.0059,3.8e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.0061,0.0067,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21590000,0.78,-0.016,-0.0035,-0.62,-0.0046,-0.0066,0.016,-0.0077,-0.014,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.7e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.0061,0.0066,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 +21690000,0.78,-0.016,-0.0036,-0.62,-0.0061,-0.0077,0.017,-0.009,-0.016,-3.7e+02,-0.0013,-0.0059,4.4e-05,0.063,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.006,0.0066,0.00029,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 +21790000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.0054,0.016,-0.0079,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 +21890000,0.78,-0.016,-0.0034,-0.62,-0.0058,-0.0063,0.016,-0.0086,-0.011,-3.7e+02,-0.0013,-0.0059,4.9e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.6e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 +21990000,0.78,-0.016,-0.0034,-0.62,-0.0057,-0.0035,0.017,-0.008,-0.0069,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01 +22090000,0.78,-0.016,-0.0034,-0.62,-0.0054,-0.0051,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01 +22190000,0.78,-0.016,-0.0034,-0.62,-0.0041,-0.0056,0.015,-0.007,-0.0066,-3.7e+02,-0.0013,-0.0059,5.9e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22390000,0.78,-0.016,-0.0034,-0.62,-0.0011,-0.0052,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22490000,0.78,-0.016,-0.0034,-0.62,1.2e-05,-0.0059,0.018,-0.0053,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22590000,0.78,-0.016,-0.0034,-0.62,0.0019,-0.0048,0.017,-0.0036,-0.0061,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22690000,0.78,-0.016,-0.0035,-0.62,0.0034,-0.0061,0.019,-0.0029,-0.0072,-3.7e+02,-0.0014,-0.0059,7e-05,0.06,-0.027,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22790000,0.78,-0.016,-0.0034,-0.62,0.0044,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22890000,0.78,-0.016,-0.0034,-0.62,0.0051,-0.0063,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0065,0.022,-0.0026,-0.0074,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0062,0.023,-0.0023,-0.0071,-3.7e+02,-0.0014,-0.0059,6.4e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23190000,0.78,-0.016,-0.0034,-0.62,0.0027,-0.0051,0.024,-0.0051,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0057,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23290000,0.78,-0.016,-0.0033,-0.62,0.0023,-0.0048,0.025,-0.0054,-0.008,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23390000,0.78,-0.016,-0.0034,-0.62,-0.001,-0.0046,0.022,-0.0095,-0.0082,-3.7e+02,-0.0014,-0.0059,7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23490000,0.78,-0.013,-0.0055,-0.62,0.0046,-0.0042,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.4e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00011,-0.043,-0.0094,-0.0059,-3.7e+02,-0.0013,-0.0059,7.7e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23690000,0.78,0.0011,-0.0087,-0.62,0.043,0.014,-0.093,-0.007,-0.0057,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23790000,0.78,-0.0026,-0.0062,-0.62,0.064,0.031,-0.15,-0.007,-0.0037,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.2e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23990000,0.78,-0.014,-0.0035,-0.62,0.072,0.043,-0.25,-0.005,-0.0014,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.002,-3.7e+02,-0.0013,-0.0059,8.8e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +24190000,0.78,-0.01,-0.0055,-0.62,0.07,0.041,-0.35,-0.0058,-0.00021,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.065,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +24290000,0.78,-0.0092,-0.0058,-0.62,0.078,0.046,-0.4,0.00065,0.0042,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.065,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +24390000,0.79,-0.0096,-0.006,-0.62,0.075,0.044,-0.46,-0.012,-0.0022,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 +24490000,0.79,-0.0054,-0.0064,-0.62,0.086,0.051,-0.51,-0.0037,0.0025,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 +24590000,0.79,-0.0019,-0.0065,-0.62,0.09,0.055,-0.56,-0.017,-0.0063,-3.7e+02,-0.0012,-0.0059,6.5e-05,0.068,-0.028,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 +24690000,0.79,-0.00097,-0.0065,-0.62,0.11,0.071,-0.64,-0.0079,-0.0013,-3.7e+02,-0.0012,-0.0059,7.2e-05,0.068,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.09,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +24790000,0.79,-0.0025,-0.0064,-0.62,0.11,0.08,-0.73,-0.027,-0.006,-3.7e+02,-0.0012,-0.0059,6.1e-05,0.07,-0.029,-0.13,-0.11,-0.026,0.5,-0.0026,-0.09,-0.068,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.018,0.018,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +24890000,0.79,-0.00061,-0.0079,-0.62,0.13,0.095,-0.75,-0.016,0.0028,-3.7e+02,-0.0012,-0.0059,6.1e-05,0.07,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.089,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0058,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +24990000,0.79,0.0012,-0.0095,-0.62,0.13,0.1,-0.81,-0.038,-0.0035,-3.7e+02,-0.0011,-0.0059,4.6e-05,0.072,-0.029,-0.13,-0.11,-0.026,0.5,-0.0025,-0.089,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +25090000,0.79,0.00058,-0.0099,-0.62,0.16,0.12,-0.86,-0.024,0.0079,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.072,-0.029,-0.13,-0.11,-0.027,0.5,-0.0026,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 +25190000,0.79,-0.0014,-0.0096,-0.61,0.15,0.11,-0.91,-0.068,-0.014,-3.7e+02,-0.0011,-0.0058,2.5e-05,0.076,-0.029,-0.13,-0.11,-0.027,0.5,-0.0023,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 +25290000,0.79,0.0056,-0.011,-0.62,0.18,0.13,-0.96,-0.051,-0.0029,-3.7e+02,-0.0011,-0.0058,2.7e-05,0.076,-0.029,-0.13,-0.11,-0.027,0.5,-0.0024,-0.087,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.0011,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 +25390000,0.79,0.012,-0.011,-0.61,0.18,0.13,-1,-0.099,-0.027,-3.7e+02,-0.001,-0.0058,8.4e-06,0.079,-0.029,-0.13,-0.12,-0.027,0.5,-0.0022,-0.087,-0.07,0,0,-3.7e+02,8.1e-05,8.5e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.001,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 +25490000,0.79,0.013,-0.011,-0.61,0.22,0.16,-1.1,-0.081,-0.014,-3.7e+02,-0.001,-0.0058,1.7e-05,0.079,-0.029,-0.13,-0.12,-0.027,0.5,-0.0025,-0.086,-0.069,0,0,-3.7e+02,8.2e-05,8.5e-05,0.046,0.022,0.022,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.2e-05,0.0012,0.00057,0.0011,0.0011,1,1,0.01 +25590000,0.79,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.058,0.0026,-3.7e+02,-0.001,-0.0058,2.3e-05,0.08,-0.029,-0.13,-0.12,-0.027,0.5,-0.0028,-0.085,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.1e-05,0.0011,0.00057,0.0011,0.0011,1,1,0.01 +25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,3e-05,0.08,-0.029,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,-3.7e+02,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01 +25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0015,0.042,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0036,-0.083,-0.067,0,0,-3.7e+02,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 +25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.041,0.065,-3.7e+02,-0.00099,-0.0058,5.7e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0042,-0.081,-0.066,0,0,-3.7e+02,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 +25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01 +26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.4e-05,0.08,-0.03,-0.13,-0.12,-0.029,0.5,-0.0047,-0.079,-0.065,0,0,-3.7e+02,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1,0.01 +26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.03,-0.13,-0.13,-0.03,0.5,-0.0055,-0.075,-0.063,0,0,-3.7e+02,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1,0.01 +26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.8e-05,0.081,-0.03,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,-3.7e+02,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1,0.01 +26390000,0.78,0.041,-0.021,-0.62,0.75,0.51,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,8.5e-05,0.081,-0.031,-0.13,-0.13,-0.03,0.49,-0.0064,-0.071,-0.06,0,0,-3.7e+02,8.8e-05,9e-05,0.041,0.042,0.046,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00084,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1,0.01 +26490000,0.78,0.057,-0.028,-0.63,0.84,0.57,-1.3,0.4,0.3,-3.7e+02,-0.00097,-0.0058,9e-05,0.081,-0.031,-0.13,-0.13,-0.031,0.49,-0.0066,-0.069,-0.058,0,0,-3.7e+02,8.9e-05,9.1e-05,0.039,0.045,0.05,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00081,4.9e-05,0.00093,0.00049,0.00084,0.00093,1,1,0.01 +26590000,0.78,0.074,-0.032,-0.62,0.95,0.65,-1.3,0.49,0.36,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.081,-0.031,-0.13,-0.14,-0.032,0.49,-0.0063,-0.066,-0.057,0,0,-3.7e+02,9e-05,9.1e-05,0.038,0.049,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00076,4.6e-05,0.00088,0.00047,0.0008,0.00088,1,1,0.01 +26690000,0.77,0.077,-0.033,-0.63,1.1,0.72,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,0.0001,0.081,-0.031,-0.13,-0.14,-0.033,0.49,-0.0074,-0.061,-0.052,0,0,-3.7e+02,9.1e-05,9.2e-05,0.035,0.053,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00071,4.3e-05,0.00082,0.00045,0.00074,0.00082,1,1,0.01 +26790000,0.77,0.071,-0.032,-0.63,1.2,0.8,-1.3,0.71,0.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.031,-0.13,-0.14,-0.034,0.48,-0.0072,-0.057,-0.049,0,0,-3.7e+02,9.2e-05,9.3e-05,0.032,0.056,0.067,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0057,0.00014,0.00067,4.1e-05,0.00078,0.00042,0.00069,0.00077,1,1,0.01 +26890000,0.77,0.094,-0.039,-0.63,1.3,0.88,-1.3,0.84,0.58,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.031,-0.13,-0.15,-0.035,0.48,-0.0078,-0.053,-0.047,0,0,-3.7e+02,9.2e-05,9.3e-05,0.03,0.059,0.072,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00063,3.9e-05,0.00073,0.00039,0.00065,0.00073,1,1,0.01 +26990000,0.76,0.12,-0.044,-0.63,1.5,0.99,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.031,-0.13,-0.15,-0.036,0.48,-0.008,-0.047,-0.043,0,0,-3.7e+02,9.3e-05,9.4e-05,0.027,0.063,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00013,0.00057,3.5e-05,0.00066,0.00035,0.00059,0.00066,1,1,0.01 +27090000,0.76,0.12,-0.045,-0.63,1.7,1.1,-1.3,1.1,0.77,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.16,-0.037,0.47,-0.0079,-0.043,-0.039,0,0,-3.7e+02,9.3e-05,9.4e-05,0.024,0.067,0.085,0.0061,0.36,0.37,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00052,3.2e-05,0.00059,0.00032,0.00053,0.00059,1,1,0.01 +27190000,0.76,0.11,-0.042,-0.63,1.9,1.2,-1.2,1.3,0.89,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.16,-0.038,0.47,-0.0075,-0.04,-0.035,0,0,-3.7e+02,9.4e-05,9.5e-05,0.021,0.071,0.091,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00048,3e-05,0.00055,0.00029,0.00049,0.00054,1,1,0.01 +27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0076,-0.036,-0.033,0,0,-3.7e+02,9.4e-05,9.5e-05,0.019,0.072,0.094,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00045,2.9e-05,0.00052,0.00026,0.00046,0.00051,1,1,0.01 +27390000,0.77,0.078,-0.033,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0075,-0.035,-0.032,0,0,-3.7e+02,9.5e-05,9.6e-05,0.017,0.073,0.094,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00043,2.8e-05,0.0005,0.00023,0.00044,0.00049,1,1,0.01 +27490000,0.77,0.062,-0.029,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00096,-0.0058,0.00011,0.082,-0.028,-0.13,-0.17,-0.039,0.47,-0.0072,-0.034,-0.032,0,0,-3.7e+02,9.6e-05,9.6e-05,0.015,0.074,0.093,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00042,2.7e-05,0.00049,0.00021,0.00043,0.00048,1,1,0.01 +27590000,0.77,0.05,-0.025,-0.63,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.027,-0.13,-0.17,-0.039,0.47,-0.0067,-0.033,-0.031,0,0,-3.7e+02,9.6e-05,9.7e-05,0.014,0.074,0.092,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00041,2.6e-05,0.00048,0.0002,0.00042,0.00048,1,1,0.01 +27690000,0.77,0.048,-0.025,-0.63,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.026,-0.13,-0.17,-0.04,0.47,-0.0063,-0.032,-0.031,0,0,-3.7e+02,9.7e-05,9.7e-05,0.013,0.074,0.09,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.0004,2.6e-05,0.00048,0.00019,0.00042,0.00047,1,1,0.01 +27790000,0.77,0.05,-0.025,-0.63,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,9.6e-05,0.083,-0.026,-0.13,-0.17,-0.04,0.47,-0.0057,-0.032,-0.031,0,0,-3.7e+02,9.8e-05,9.8e-05,0.012,0.074,0.089,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00039,2.6e-05,0.00047,0.00017,0.00041,0.00047,1,1,0.01 +27890000,0.77,0.048,-0.024,-0.63,2.3,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,9.5e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.0057,-0.031,-0.031,0,0,-3.7e+02,9.9e-05,9.8e-05,0.011,0.075,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00039,2.5e-05,0.00047,0.00016,0.0004,0.00047,1,1,0.01 +27990000,0.77,0.044,-0.023,-0.63,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.47,-0.0056,-0.031,-0.031,0,0,-3.7e+02,0.0001,9.9e-05,0.01,0.075,0.088,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.5e-05,0.00047,0.00016,0.0004,0.00046,1,1,0.01 +28090000,0.78,0.058,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,8.8e-05,0.083,-0.024,-0.13,-0.17,-0.04,0.46,-0.0051,-0.03,-0.03,0,0,-3.7e+02,0.0001,9.9e-05,0.0096,0.076,0.088,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.4e-05,0.00046,0.00015,0.00039,0.00046,1,1,0.01 +28190000,0.77,0.071,-0.031,-0.63,2.4,1.7,-0.93,3.5,2.4,-3.7e+02,-0.00095,-0.0058,8.7e-05,0.084,-0.024,-0.13,-0.17,-0.04,0.46,-0.0051,-0.03,-0.03,0,0,-3.7e+02,0.0001,0.0001,0.0091,0.077,0.088,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00037,2.4e-05,0.00046,0.00014,0.00038,0.00045,1,1,0.01 +28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.3e-05,0.084,-0.023,-0.13,-0.17,-0.04,0.46,-0.0049,-0.029,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1,0.01 +28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,7.9e-05,0.084,-0.022,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 +28490000,0.78,0.0015,-0.006,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 +28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.3e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 +28690000,0.78,-0.0031,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,6.8e-05,0.083,-0.021,-0.12,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 +28790000,0.78,-0.0035,-0.0038,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.4e-05,0.083,-0.02,-0.12,-0.17,-0.041,0.46,-0.0043,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1,0.01 +28890000,0.78,-0.0032,-0.0038,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6e-05,0.082,-0.02,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1,0.01 +28990000,0.78,-0.0028,-0.0039,-0.62,2.1,1.5,0.98,5.4,3.8,-3.7e+02,-0.001,-0.0058,5.3e-05,0.082,-0.019,-0.12,-0.17,-0.041,0.46,-0.0039,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 +29090000,0.78,-0.0024,-0.004,-0.62,2,1.5,0.97,5.6,4,-3.7e+02,-0.001,-0.0058,4.9e-05,0.081,-0.018,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0063,0.081,0.085,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 +29190000,0.78,-0.0021,-0.0041,-0.62,2,1.5,0.97,5.8,4.1,-3.7e+02,-0.001,-0.0058,4.9e-05,0.081,-0.018,-0.12,-0.17,-0.041,0.46,-0.0039,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0061,0.082,0.087,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 +29290000,0.78,-0.0012,-0.0044,-0.62,1.9,1.5,0.99,6,4.2,-3.7e+02,-0.001,-0.0058,4.4e-05,0.081,-0.018,-0.12,-0.17,-0.041,0.46,-0.0037,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.00011,0.00037,0.00043,1,1,0.01 +29390000,0.78,0.00011,-0.0047,-0.62,1.9,1.4,1,6.2,4.4,-3.7e+02,-0.001,-0.0058,3.8e-05,0.081,-0.017,-0.12,-0.17,-0.041,0.46,-0.0034,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 +29490000,0.78,0.0013,-0.0051,-0.62,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.5e-05,0.08,-0.016,-0.12,-0.17,-0.041,0.46,-0.0034,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 +29590000,0.78,0.0023,-0.0053,-0.62,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,3.2e-05,0.08,-0.016,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 +29690000,0.78,0.003,-0.0055,-0.62,1.7,1.4,0.99,6.7,4.8,-3.7e+02,-0.001,-0.0057,2.8e-05,0.08,-0.015,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.9e-05,0.00037,0.00043,1,1,0.01 +29790000,0.78,0.0034,-0.0057,-0.62,1.7,1.4,0.98,6.9,5,-3.7e+02,-0.001,-0.0057,2.4e-05,0.079,-0.014,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.027,0,0,-3.7e+02,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.8e-05,0.00037,0.00042,1,1,0.01 +29890000,0.78,0.0036,-0.0057,-0.62,1.7,1.3,0.97,7.1,5.1,-3.7e+02,-0.001,-0.0057,1.8e-05,0.079,-0.013,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.7e-05,0.00037,0.00042,1,1,0.01 +29990000,0.78,0.0036,-0.0058,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.4e-05,0.079,-0.013,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1,0.01 +30090000,0.78,0.0035,-0.0058,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1e-05,0.079,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1,0.01 +30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.1e-05,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1,0.01 +30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.4e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01 +30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,4.2e-06,0.077,-0.011,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 +30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3.1e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 +30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.9e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01 +30690000,0.78,0.0018,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-2.3e-06,0.077,-0.0087,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 +30790000,0.78,0.0014,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-5.4e-06,0.076,-0.0085,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 +30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.3e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01 +30990000,0.78,0.00035,-0.0051,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1.2e-05,0.075,-0.0069,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1,0.01 +31090000,0.78,-0.00019,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.6e-05,0.075,-0.0062,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 +31190000,0.78,-0.00061,-0.0048,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.9e-05,0.075,-0.0054,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 +31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.075,-0.0047,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 +31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.004,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 +31490000,0.78,-0.0025,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-3e-05,0.074,-0.0033,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 +31590000,0.78,-0.0029,-0.0043,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3.1e-05,0.073,-0.0026,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1,0.01 +31690000,0.78,-0.0037,-0.0041,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.073,-0.0019,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31790000,0.78,-0.0044,-0.0039,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.6e-05,0.072,-0.001,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00016,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00077,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.96,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-4.9e-05,0.071,0.0015,-0.11,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.8,-3.7e+02,-0.0012,-0.0057,-5.8e-05,0.07,0.0024,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.07,0.0034,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.069,0.0041,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 +32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01 +32590000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.9e-05,0.069,0.0052,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 +32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.068,0.0058,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 +32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0062,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.024,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 +32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.067,0.0067,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 +32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.7e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 +33090000,0.79,-0.0091,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 +33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.066,0.0075,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1,0.01 +33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1,0.01 +33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.065,0.0071,-0.11,-0.18,-0.041,0.46,-0.00098,-0.027,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8.1e-05,0.00032,0.00039,1,1,0.01 +33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0072,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01 +33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0072,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01 +33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0072,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01 +33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01 +33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01 +33990000,0.86,-0.015,0.0071,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0069,-0.11,-0.2,-0.046,0.46,0.0005,-0.0039,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1,0.01 +34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01 +34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01 +34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01 +34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.4e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01 +34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01 +34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.3e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01 +34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-4.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01 +34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0051,-0.11,-0.2,-0.047,0.46,0.00012,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1,0.01 +34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01 +34990000,0.64,-0.0062,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00018,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1,0.01 +35090000,0.64,-0.0063,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1,0.01 +35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01 +35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01 +35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01 +35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01 +35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 +35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 +35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 +35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 +35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 +36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 +36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 +36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 +36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 +36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 +36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 +36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 +36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 +36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0052,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 +36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 +37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 +37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 +37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 +37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 +37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 +37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 +37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 +37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 +37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 +37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 +38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 +38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 +38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 +38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 +38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 +38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 +38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 +38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.87,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 +38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index efd262eaf455..f205da08db4c 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -14,338 +14,338 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.6e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.2e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.5e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.095,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.7e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.4e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-2.9e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.6e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.095,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0054,-0.074,-0.0011,-0.0013,-3.6e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.095,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.095,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.5e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.095,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.014,0.00048,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.5e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-2.1e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.095,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.01,-0.013,0.00038,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.01,-0.013,0.00032,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-3.1e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.095,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-3.1e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.01,-0.013,0.00057,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.095,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.5e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.095,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.095,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.0097,-0.013,0.00059,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.095,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.095,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.0095,-0.013,0.00053,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.095,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.8e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.095,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.0094,-0.013,0.00064,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.095,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.095,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.0093,-0.012,0.00077,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-5.2e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.095,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-5.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.095,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.0095,-0.012,0.00075,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.7e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.095,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.7e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.095,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.0094,-0.012,0.00077,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-6.2e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.095,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-6.2e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.095,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.0094,-0.012,0.00077,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.095,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.0093,-0.012,0.00087,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.095,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.0092,-0.012,0.00091,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-7e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.095,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-7e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.0091,-0.011,0.00097,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-7.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0089,-0.011,0.0009,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0088,-0.011,0.00086,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0088,-0.011,0.00089,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0088,-0.012,0.00087,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0088,-0.011,0.00068,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0089,-0.011,0.00069,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0089,-0.011,0.00072,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0089,-0.011,0.00073,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0089,-0.011,0.00063,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.8e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6590000,1,-0.009,-0.011,0.00056,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6690000,1,-0.0089,-0.011,0.00052,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-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.009,-0.011,0.00048,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-9.2e-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,8.1e-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.0088,-0.011,0.0004,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-9.2e-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,8.1e-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.29,0.024,-0.0061,0.96,-0.2,-0.033,-0.037,-0.11,-0.019,-0.055,-0.00071,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.095,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1,1.8 -7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.049,-0.038,-0.15,-0.027,-0.056,-0.00058,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.095,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1,1.8 -7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.00054,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1,1.8 -7290000,-0.29,0.025,-0.0063,0.96,-0.28,-0.066,-0.034,-0.2,-0.04,-0.055,-0.00053,-0.01,-0.00021,-0.00088,-0.00019,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1,1.9 -7390000,-0.29,0.025,-0.0063,0.96,-0.3,-0.072,-0.032,-0.23,-0.048,-0.052,-0.00052,-0.01,-0.00021,-0.0011,-0.00023,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00014,0.0013,0.0013,0.00086,0.0013,1,1,1.9 -7490000,-0.29,0.024,-0.0063,0.96,-0.32,-0.08,-0.026,-0.25,-0.056,-0.046,-0.00051,-0.0099,-0.00021,-0.0015,-0.00027,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 -7590000,-0.29,0.024,-0.0065,0.96,-0.34,-0.087,-0.022,-0.28,-0.065,-0.041,-0.00049,-0.0098,-0.00021,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 -7690000,-0.29,0.024,-0.0065,0.96,-0.35,-0.096,-0.022,-0.31,-0.076,-0.036,-0.00047,-0.0097,-0.00021,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 -7790000,-0.29,0.023,-0.0063,0.96,-0.36,-0.11,-0.024,-0.34,-0.09,-0.041,-0.0004,-0.0096,-0.00021,-0.0017,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 -7890000,-0.29,0.023,-0.0063,0.96,-0.37,-0.11,-0.025,-0.37,-0.1,-0.045,-0.00038,-0.0095,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00086,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.0001,0.0013,0.0013,0.00083,0.0013,1,1,2 -7990000,-0.29,0.023,-0.0064,0.96,-0.39,-0.12,-0.021,-0.4,-0.11,-0.041,-0.00041,-0.0094,-0.0002,-0.0016,-0.00019,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.8e-05,0.0013,0.0012,0.00083,0.0013,1,1,2 -8090000,-0.29,0.023,-0.0062,0.96,-0.41,-0.13,-0.022,-0.43,-0.13,-0.044,-0.00034,-0.0094,-0.0002,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.0008,0.00083,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,9.6e-05,0.0013,0.0012,0.00083,0.0013,1,1,2.1 -8190000,-0.29,0.022,-0.0063,0.96,-0.41,-0.14,-0.017,-0.46,-0.15,-0.038,-0.00028,-0.0092,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00078,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.4e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 -8290000,-0.29,0.022,-0.0064,0.96,-0.44,-0.15,-0.016,-0.51,-0.16,-0.038,-0.00033,-0.0093,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00075,0.00078,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.2e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 -8390000,-0.29,0.022,-0.0065,0.96,-0.45,-0.15,-0.015,-0.55,-0.17,-0.036,-0.00034,-0.0092,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0012,9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 -8490000,-0.29,0.022,-0.0065,0.96,-0.46,-0.15,-0.016,-0.58,-0.18,-0.041,-0.00043,-0.0091,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00071,0.00073,0.053,0.82,0.81,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.2 -8590000,-0.29,0.022,-0.0063,0.96,-0.45,-0.16,-0.012,-0.6,-0.2,-0.036,-0.00037,-0.0089,-0.00019,-0.0016,-0.00011,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00069,0.00071,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.7e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 -8690000,-0.29,0.021,-0.0064,0.96,-0.46,-0.16,-0.014,-0.64,-0.21,-0.037,-0.00042,-0.0088,-0.00019,-0.0016,-7.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00067,0.00069,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,8.6e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 -8790000,-0.29,0.021,-0.0065,0.96,-0.48,-0.16,-0.013,-0.67,-0.23,-0.035,-0.00041,-0.0088,-0.00019,-0.0016,-6.7e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00065,0.00067,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,8.5e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 -8890000,-0.29,0.021,-0.0064,0.96,-0.47,-0.16,-0.0093,-0.68,-0.24,-0.029,-0.00046,-0.0085,-0.00018,-0.0016,4.3e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00063,0.00065,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,8.4e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 -8990000,-0.29,0.02,-0.0063,0.96,-0.45,-0.17,-0.0088,-0.68,-0.25,-0.032,-0.0005,-0.0082,-0.00017,-0.0013,0.00015,-0.13,-0.1,-0.024,0.5,0.08,-0.032,-0.069,0,0,0.095,0.00062,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,8.3e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 -9090000,-0.29,0.02,-0.0064,0.96,-0.46,-0.16,-0.0099,-0.72,-0.23,-0.032,-0.00067,-0.0082,-0.00016,-0.0012,0.00032,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 -9190000,-0.29,0.02,-0.0064,0.96,-0.46,-0.15,-0.0095,-0.74,-0.23,-0.033,-0.00077,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.095,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.3 -9290000,-0.29,0.02,-0.0061,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00077,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9390000,-0.29,0.02,-0.0059,0.96,-0.45,-0.17,-0.007,-0.75,-0.28,-0.031,-0.00069,-0.0077,-0.00015,-0.00085,0.00049,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9490000,-0.29,0.019,-0.006,0.96,-0.46,-0.17,-0.0055,-0.78,-0.28,-0.028,-0.00077,-0.0076,-0.00015,-0.00093,0.00058,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9590000,-0.29,0.019,-0.006,0.96,-0.47,-0.19,-0.0054,-0.82,-0.33,-0.029,-0.00064,-0.0075,-0.00015,-0.00087,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4 -9690000,-0.29,0.019,-0.0059,0.96,-0.47,-0.2,-0.0026,-0.83,-0.36,-0.028,-0.0006,-0.0074,-0.00015,-0.00078,0.00046,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9790000,-0.29,0.019,-0.0059,0.96,-0.48,-0.21,-0.0039,-0.88,-0.4,-0.029,-0.00052,-0.0074,-0.00015,-0.00077,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9890000,-0.29,0.019,-0.0058,0.96,-0.47,-0.21,-0.0027,-0.88,-0.42,-0.03,-0.00055,-0.0072,-0.00014,-0.00053,0.00044,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9990000,-0.29,0.019,-0.0058,0.96,-0.49,-0.22,-0.002,-0.93,-0.46,-0.032,-0.00049,-0.0072,-0.00015,-0.00044,0.00038,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.5 -10090000,-0.29,0.019,-0.0057,0.96,-0.49,-0.24,-0.00079,-0.96,-0.51,-0.03,-0.00039,-0.0071,-0.00015,-0.00045,0.0003,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10190000,-0.29,0.019,-0.0057,0.96,-0.49,-0.26,4.4e-05,-0.97,-0.58,-0.031,-0.00025,-0.007,-0.00015,-0.00028,0.00017,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10290000,-0.29,0.019,-0.0056,0.96,-0.49,-0.26,-0.0011,-0.98,-0.59,-0.03,-0.00032,-0.0069,-0.00014,-0.00016,0.00024,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10390000,-0.29,0.019,-0.0055,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00015,-0.029,-0.00036,-0.0067,-0.00014,-6.4e-06,0.0003,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10490000,-0.29,0.019,-0.0055,0.96,-0.01,-0.0087,0.0071,0.00024,-0.00081,-0.024,-0.00029,-0.0067,-0.00014,-0.00015,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10590000,-0.29,0.019,-0.0054,0.96,-0.021,-0.0074,0.013,-0.0011,-0.00057,-0.022,-0.00039,-0.0066,-0.00013,0.0001,0.0006,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10690000,-0.29,0.019,-0.0053,0.96,-0.034,-0.01,0.016,-0.0038,-0.0015,-0.018,-0.00037,-0.0065,-0.00013,0.00013,0.00058,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10790000,-0.29,0.019,-0.0052,0.96,-0.034,-0.014,0.014,0.00012,-0.0018,-0.016,-0.0004,-0.0064,-0.00013,0.002,5.7e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10890000,-0.29,0.019,-0.0051,0.96,-0.043,-0.019,0.01,-0.0037,-0.0034,-0.019,-0.00052,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.8 -10990000,-0.29,0.019,-0.0051,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00056,-0.0064,-0.00012,0.0058,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 -11090000,-0.29,0.019,-0.0052,0.96,-0.051,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00045,-0.0063,-0.00013,0.006,0.00063,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 -11190000,-0.29,0.018,-0.0053,0.96,-0.041,-0.026,0.027,-0.0021,-0.0027,-0.0011,-0.00045,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 -11290000,-0.29,0.018,-0.0053,0.96,-0.05,-0.027,0.026,-0.0066,-0.0053,-0.00072,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.9 -11390000,-0.29,0.018,-0.0052,0.96,-0.043,-0.024,0.017,-0.0037,-0.0034,-0.0091,-0.00052,-0.0063,-0.00013,0.019,0.0029,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 -11490000,-0.29,0.018,-0.0051,0.96,-0.05,-0.026,0.021,-0.0082,-0.006,-0.003,-0.00053,-0.0062,-0.00012,0.019,0.003,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 -11590000,-0.29,0.018,-0.0052,0.96,-0.045,-0.021,0.019,-0.005,-0.0039,-0.004,-0.00057,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 -11690000,-0.29,0.017,-0.0052,0.96,-0.051,-0.026,0.019,-0.0097,-0.0062,-0.0053,-0.00061,-0.0063,-0.00012,0.025,0.0042,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.087,0.087,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,3 -11790000,-0.29,0.017,-0.0051,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.0007,-0.0063,-0.00012,0.03,0.0046,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 -11890000,-0.29,0.017,-0.0053,0.96,-0.049,-0.028,0.018,-0.01,-0.008,-0.0016,-0.00069,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 -11990000,-0.29,0.017,-0.0053,0.96,-0.039,-0.021,0.015,-0.0064,-0.0053,-0.0052,-0.00072,-0.0063,-0.00012,0.037,0.0066,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 -12090000,-0.29,0.017,-0.0052,0.96,-0.045,-0.022,0.018,-0.011,-0.0076,0.00088,-0.0007,-0.0062,-0.00012,0.037,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3.1 -12190000,-0.29,0.017,-0.0052,0.96,-0.038,-0.013,0.017,-0.0054,-0.0029,0.0028,-0.00066,-0.0062,-0.00012,0.043,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 -12290000,-0.29,0.017,-0.0053,0.96,-0.04,-0.012,0.016,-0.0094,-0.0041,0.0038,-0.00063,-0.0062,-0.00012,0.043,0.0085,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 -12390000,-0.29,0.016,-0.0053,0.96,-0.033,-0.0087,0.014,-0.0051,-0.0027,-0.0022,-0.00063,-0.0062,-0.00012,0.047,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 -12490000,-0.29,0.016,-0.0053,0.96,-0.036,-0.0097,0.018,-0.0087,-0.0037,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 -12590000,-0.29,0.016,-0.0052,0.96,-0.03,-0.0084,0.02,-0.0035,-0.0039,0.0017,-0.00061,-0.0061,-0.00012,0.05,0.0078,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 -12690000,-0.29,0.016,-0.0052,0.96,-0.033,-0.0065,0.019,-0.0066,-0.0047,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 -12790000,-0.29,0.016,-0.005,0.96,-0.023,-0.012,0.02,-0.0016,-0.0077,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0069,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.4e-06,7e-06,2.2e-06,0.0093,0.0096,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.2 -12890000,-0.29,0.016,-0.005,0.96,-0.025,-0.013,0.021,-0.004,-0.009,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0073,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -12990000,-0.29,0.016,-0.005,0.96,-0.021,-0.0099,0.022,-0.0012,-0.0063,0.0096,-0.00075,-0.0061,-0.00012,0.054,0.0079,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0083,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -13090000,-0.29,0.016,-0.0049,0.96,-0.023,-0.011,0.019,-0.0033,-0.0076,0.0084,-0.00079,-0.006,-0.00011,0.054,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -13190000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.018,-0.0017,-0.0086,0.009,-0.00082,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0072,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -13290000,-0.29,0.016,-0.0049,0.96,-0.021,-0.011,0.016,-0.0038,-0.0099,0.0084,-0.00081,-0.006,-0.00011,0.056,0.0086,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13390000,-0.29,0.016,-0.0049,0.96,-0.017,-0.0083,0.015,-0.0014,-0.0068,0.009,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.0001,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13490000,-0.29,0.016,-0.0049,0.96,-0.019,-0.011,0.015,-0.0032,-0.0079,0.0051,-0.00079,-0.006,-0.00011,0.057,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,0.0001,0.0001,0.051,0.053,0.053,0.009,0.067,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13590000,-0.29,0.016,-0.0049,0.96,-0.014,-0.0075,0.016,0.0017,-0.0056,0.0036,-0.00077,-0.006,-0.00011,0.059,0.009,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,9.3e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0059,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13690000,-0.29,0.016,-0.0048,0.96,-0.015,-0.0066,0.016,0.00026,-0.0063,0.0062,-0.00079,-0.0059,-0.00011,0.059,0.0093,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,9.4e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -13790000,-0.29,0.015,-0.0048,0.96,-0.011,-0.0047,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.061,0.0092,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.7e-05,8.7e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -13890000,-0.29,0.015,-0.0047,0.96,-0.012,-0.0058,0.017,0.0044,-0.0039,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0093,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.8e-05,8.8e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -13990000,-0.29,0.015,-0.0047,0.96,-0.014,-0.0096,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0097,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.3e-05,8.3e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0047,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -14090000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0037,0.017,0.0022,-0.0049,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14190000,-0.29,0.015,-0.0048,0.96,-0.01,-0.0025,0.017,0.0035,-0.0039,0.0033,-0.00073,-0.006,-0.00011,0.063,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0046,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14290000,-0.29,0.015,-0.0048,0.96,-0.013,-0.0029,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.063,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.1e-05,8e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14390000,-0.29,0.015,-0.0048,0.96,-0.012,-0.0025,0.017,0.0036,-0.0047,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0043,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14490000,-0.29,0.015,-0.005,0.96,-0.012,-0.0018,0.02,0.0022,-0.0047,0.014,-0.00071,-0.0059,-0.00012,0.064,0.0087,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.8e-05,7.7e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14590000,-0.29,0.015,-0.005,0.96,-0.015,-0.0035,0.018,0.00068,-0.0052,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0088,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.5e-05,7.4e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0038,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14690000,-0.29,0.015,-0.005,0.96,-0.016,-0.0038,0.018,-0.00092,-0.0057,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14790000,-0.29,0.015,-0.0051,0.96,-0.019,-0.0012,0.018,-0.00061,-0.0012,0.013,-0.00072,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.0007,0.022,-0.0027,-0.0016,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -14990000,-0.29,0.015,-0.005,0.96,-0.02,-0.0013,0.025,-0.0022,-0.0028,0.016,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -15090000,-0.29,0.016,-0.0049,0.96,-0.021,-0.0024,0.029,-0.0043,-0.0029,0.018,-0.00074,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00056,0.029,-0.0034,-0.0023,0.02,-0.00073,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -15290000,-0.29,0.016,-0.0051,0.96,-0.024,-0.00067,0.029,-0.0059,-0.0028,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15390000,-0.29,0.016,-0.0052,0.96,-0.023,-0.0026,0.028,-0.0046,-0.0023,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15490000,-0.29,0.016,-0.0052,0.96,-0.025,-0.00012,0.028,-0.007,-0.0025,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0045,0.028,-0.0033,-0.0057,0.017,-0.00078,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15690000,-0.29,0.016,-0.0051,0.96,-0.024,-0.0024,0.028,-0.0049,-0.0061,0.018,-0.00083,-0.0057,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -15790000,-0.29,0.015,-0.0051,0.96,-0.021,-0.0012,0.028,-0.0035,-0.0052,0.019,-0.00087,-0.0058,-0.00011,0.066,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -15890000,-0.29,0.016,-0.0052,0.96,-0.021,-0.0024,0.029,-0.0059,-0.0052,0.019,-0.00084,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0019,0.026,-0.0049,-0.0044,0.018,-0.00083,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00065,0.024,-0.0072,-0.0044,0.018,-0.00082,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00046,0.023,-0.0071,-0.0036,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16290000,-0.29,0.016,-0.0051,0.96,-0.022,0.00049,0.022,-0.0091,-0.0037,0.017,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16390000,-0.29,0.016,-0.005,0.96,-0.023,-6.6e-05,0.023,-0.007,-0.0036,0.017,-0.00082,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16490000,-0.29,0.016,-0.0051,0.96,-0.027,0.0009,0.025,-0.0098,-0.0035,0.021,-0.00081,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16590000,-0.29,0.016,-0.0051,0.96,-0.031,0.0013,0.029,-0.0085,-0.003,0.021,-0.00082,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16690000,-0.29,0.015,-0.0051,0.96,-0.034,0.0049,0.029,-0.011,-0.0028,0.021,-0.00084,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16790000,-0.29,0.015,-0.005,0.96,-0.035,0.0046,0.028,-0.0096,-0.0025,0.021,-0.00086,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0028,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16890000,-0.29,0.015,-0.0049,0.96,-0.035,0.0041,0.029,-0.013,-0.0025,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6.1e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -16990000,-0.29,0.015,-0.005,0.96,-0.032,0.0045,0.029,-0.011,-0.0027,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -17090000,-0.29,0.015,-0.0051,0.96,-0.037,0.0065,0.028,-0.015,-0.0022,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -17190000,-0.29,0.015,-0.0052,0.96,-0.036,0.0083,0.03,-0.014,-0.0038,0.021,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -17290000,-0.29,0.015,-0.0052,0.96,-0.039,0.009,0.03,-0.018,-0.0026,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17390000,-0.29,0.015,-0.0051,0.96,-0.029,0.014,0.029,-0.01,-0.0013,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17490000,-0.29,0.015,-0.0052,0.96,-0.029,0.015,0.029,-0.013,0.00029,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17590000,-0.29,0.015,-0.0052,0.96,-0.029,0.013,0.028,-0.012,-0.00011,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17690000,-0.29,0.015,-0.0052,0.96,-0.03,0.014,0.029,-0.016,0.001,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 -17790000,-0.29,0.015,-0.0053,0.96,-0.031,0.014,0.029,-0.015,0.0018,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0026,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 -17890000,-0.29,0.015,-0.0052,0.96,-0.035,0.015,0.029,-0.017,0.003,0.032,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 -17990000,-0.29,0.015,-0.0052,0.96,-0.034,0.016,0.029,-0.014,0.0053,0.033,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.5 -18090000,-0.29,0.015,-0.0052,0.96,-0.036,0.017,0.028,-0.018,0.0068,0.031,-0.00094,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18190000,-0.29,0.015,-0.0052,0.96,-0.032,0.014,0.028,-0.013,0.0046,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18290000,-0.29,0.015,-0.0052,0.96,-0.036,0.014,0.027,-0.017,0.0057,0.028,-0.00098,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18390000,-0.29,0.015,-0.0051,0.96,-0.032,0.014,0.027,-0.012,0.0048,0.027,-0.00099,-0.0057,-0.00011,0.07,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18490000,-0.29,0.015,-0.0051,0.96,-0.036,0.013,0.026,-0.015,0.0057,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0025,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18590000,-0.29,0.015,-0.005,0.96,-0.034,0.013,0.026,-0.013,0.0051,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18690000,-0.29,0.015,-0.005,0.96,-0.034,0.012,0.025,-0.015,0.006,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18790000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.024,-0.012,0.0052,0.028,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18890000,-0.29,0.015,-0.0049,0.96,-0.031,0.012,0.022,-0.015,0.0065,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -18990000,-0.29,0.015,-0.0049,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -19090000,-0.29,0.015,-0.0049,0.96,-0.028,0.013,0.024,-0.016,0.0064,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -19190000,-0.29,0.015,-0.0049,0.96,-0.026,0.014,0.023,-0.014,0.0063,0.023,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19390000,-0.29,0.015,-0.005,0.96,-0.026,0.012,0.025,-0.015,0.0074,0.021,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19690000,-0.29,0.015,-0.0049,0.96,-0.025,0.013,0.025,-0.018,0.0078,0.021,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -19790000,-0.29,0.015,-0.005,0.96,-0.022,0.013,0.023,-0.018,0.0085,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -19890000,-0.29,0.015,-0.005,0.96,-0.023,0.013,0.023,-0.02,0.0098,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -19990000,-0.29,0.015,-0.005,0.96,-0.02,0.014,0.021,-0.016,0.009,0.012,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -20090000,-0.29,0.015,-0.005,0.96,-0.023,0.016,0.021,-0.018,0.01,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5.1 -20190000,-0.29,0.015,-0.005,0.96,-0.024,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 -20290000,-0.29,0.015,-0.005,0.96,-0.022,0.016,0.022,-0.021,0.012,0.016,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 -20390000,-0.29,0.015,-0.005,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 -20490000,-0.29,0.015,-0.005,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.3e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20590000,-0.29,0.015,-0.0049,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.2e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20690000,-0.29,0.015,-0.0048,0.96,-0.017,0.016,0.023,-0.025,0.014,0.014,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.5e-05,5.1e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20790000,-0.29,0.015,-0.0042,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20890000,-0.29,0.01,0.0044,0.96,-0.0063,0.0016,-0.11,-0.021,0.011,0.0066,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.11,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20990000,-0.29,0.0063,0.0074,0.96,0.0088,-0.015,-0.25,-0.017,0.0081,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.092,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.2e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21090000,-0.29,0.0069,0.0058,0.96,0.023,-0.028,-0.37,-0.015,0.0062,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.061,5.3e-05,4.9e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21190000,-0.29,0.0088,0.0033,0.96,0.029,-0.033,-0.5,-0.013,0.0046,-0.075,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.025,5.1e-05,4.8e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21290000,-0.29,0.01,0.0012,0.96,0.027,-0.036,-0.63,-0.01,0.002,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.034,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21390000,-0.29,0.011,-0.00024,0.96,0.021,-0.029,-0.75,-0.012,0.0052,-0.2,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.099,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21490000,-0.29,0.012,-0.00099,0.96,0.014,-0.028,-0.89,-0.0097,0.0021,-0.28,-0.0011,-0.0058,-0.00013,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.18,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21590000,-0.29,0.012,-0.0015,0.96,0.0028,-0.022,-1,-0.014,0.0068,-0.37,-0.0011,-0.0058,-0.00012,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.27,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.002,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21690000,-0.29,0.012,-0.0018,0.96,-0.0025,-0.019,-1.1,-0.014,0.004,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.39,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21790000,-0.29,0.012,-0.0022,0.96,-0.0083,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.51,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0072,-1.4,-0.016,0.0097,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.65,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.001,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22090000,-0.29,0.013,-0.0039,0.96,-0.023,0.0043,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.93,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22190000,-0.29,0.013,-0.0043,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.1,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22290000,-0.29,0.014,-0.005,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.2,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22390000,-0.29,0.014,-0.0053,0.96,-0.045,0.022,-1.4,-0.038,0.029,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.4,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22490000,-0.29,0.015,-0.0054,0.96,-0.052,0.028,-1.4,-0.043,0.032,-1.6,-0.001,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.5,5e-05,4.6e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22590000,-0.29,0.015,-0.0052,0.96,-0.057,0.034,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.6,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22690000,-0.29,0.015,-0.0052,0.96,-0.062,0.039,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.8,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22790000,-0.29,0.016,-0.0051,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.9,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -22890000,-0.29,0.016,-0.0052,0.96,-0.073,0.048,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.8e-05,0.069,0.011,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.1,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -22990000,-0.29,0.016,-0.005,0.96,-0.076,0.048,-1.4,-0.065,0.045,-2.3,-0.0011,-0.0058,-7e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.2,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23090000,-0.29,0.017,-0.005,0.96,-0.082,0.052,-1.4,-0.072,0.05,-2.5,-0.0011,-0.0058,-6.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.4,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23190000,-0.29,0.017,-0.0049,0.96,-0.084,0.047,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.1e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.5,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23290000,-0.29,0.017,-0.0054,0.96,-0.09,0.051,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.7,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23390000,-0.29,0.017,-0.0053,0.96,-0.09,0.054,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.8e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.8,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23490000,-0.29,0.017,-0.0053,0.96,-0.096,0.054,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.9,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23590000,-0.29,0.017,-0.0055,0.96,-0.095,0.048,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.1,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23690000,-0.29,0.018,-0.006,0.96,-0.094,0.051,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.2e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.2,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23790000,-0.29,0.021,-0.0075,0.96,-0.079,0.048,-0.95,-0.08,0.047,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.3,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23890000,-0.29,0.025,-0.01,0.96,-0.074,0.051,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.4,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23990000,-0.29,0.028,-0.012,0.96,-0.065,0.05,-0.13,-0.074,0.046,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -24090000,-0.29,0.027,-0.012,0.96,-0.072,0.058,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.7e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -24190000,-0.29,0.023,-0.0092,0.96,-0.076,0.055,0.088,-0.066,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24290000,-0.29,0.019,-0.0072,0.96,-0.08,0.057,0.066,-0.074,0.044,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24390000,-0.29,0.018,-0.0064,0.96,-0.064,0.05,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24490000,-0.29,0.018,-0.0066,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24590000,-0.29,0.018,-0.0072,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24690000,-0.29,0.018,-0.0077,0.96,-0.045,0.044,0.075,-0.046,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24790000,-0.29,0.017,-0.0078,0.96,-0.039,0.042,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24890000,-0.29,0.017,-0.0077,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25090000,-0.29,0.016,-0.0078,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25190000,-0.29,0.016,-0.008,0.96,-0.011,0.042,0.047,-0.0079,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25290000,-0.3,0.016,-0.0082,0.96,-0.006,0.045,0.042,-0.0086,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25390000,-0.3,0.015,-0.0083,0.96,0.003,0.043,0.04,0.0014,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25490000,-0.3,0.015,-0.0084,0.96,0.0074,0.044,0.04,0.0011,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25590000,-0.3,0.015,-0.0085,0.96,0.012,0.04,0.041,0.0086,0.0097,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25690000,-0.3,0.014,-0.008,0.96,0.013,0.039,0.03,0.0099,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25790000,-0.3,0.014,-0.0078,0.96,0.024,0.034,0.03,0.017,0.0035,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25890000,-0.3,0.014,-0.0079,0.96,0.03,0.034,0.033,0.02,0.0078,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25990000,-0.3,0.014,-0.0079,0.96,0.032,0.029,0.026,0.017,-0.0034,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26090000,-0.3,0.014,-0.0076,0.96,0.037,0.029,0.025,0.021,-0.0013,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26190000,-0.3,0.014,-0.0074,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26290000,-0.3,0.015,-0.0074,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26390000,-0.3,0.015,-0.0068,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26490000,-0.3,0.015,-0.0066,0.96,0.043,0.0087,0.028,0.023,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26590000,-0.3,0.015,-0.006,0.96,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26690000,-0.3,0.015,-0.0059,0.96,0.044,-0.0049,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26790000,-0.3,0.014,-0.0057,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26990000,-0.3,0.015,-0.0045,0.96,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -27090000,-0.3,0.015,-0.0043,0.96,0.057,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27290000,-0.3,0.016,-0.0044,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27390000,-0.3,0.018,-0.0056,0.96,0.067,-0.026,0.46,0.007,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27490000,-0.3,0.02,-0.0067,0.95,0.072,-0.028,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27590000,-0.3,0.019,-0.0067,0.96,0.063,-0.03,0.87,0.0077,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.3,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27690000,-0.3,0.016,-0.0058,0.96,0.058,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.2,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27790000,-0.3,0.015,-0.0047,0.96,0.054,-0.026,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27890000,-0.3,0.015,-0.0043,0.96,0.061,-0.031,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27990000,-0.3,0.015,-0.0047,0.96,0.061,-0.034,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28090000,-0.3,0.015,-0.005,0.96,0.065,-0.034,0.8,0.026,-0.027,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.9,4.5e-05,4e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28190000,-0.3,0.015,-0.0044,0.96,0.062,-0.033,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28290000,-0.3,0.016,-0.0038,0.96,0.066,-0.036,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28390000,-0.3,0.016,-0.0038,0.96,0.068,-0.038,0.81,0.035,-0.034,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.7,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28490000,-0.3,0.017,-0.004,0.96,0.07,-0.041,0.81,0.043,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.6,4.5e-05,4e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28590000,-0.29,0.017,-0.004,0.96,0.063,-0.042,0.81,0.043,-0.041,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.5,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28690000,-0.29,0.016,-0.0039,0.96,0.062,-0.043,0.81,0.049,-0.045,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.5,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28790000,-0.29,0.016,-0.0032,0.96,0.06,-0.042,0.81,0.05,-0.044,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.4,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28890000,-0.29,0.015,-0.0031,0.96,0.064,-0.044,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.3,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28990000,-0.29,0.016,-0.0028,0.96,0.062,-0.042,0.81,0.058,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29090000,-0.29,0.016,-0.0027,0.96,0.065,-0.043,0.81,0.065,-0.053,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29190000,-0.29,0.016,-0.0026,0.96,0.066,-0.043,0.8,0.067,-0.052,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.1,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29290000,-0.29,0.016,-0.0028,0.96,0.071,-0.048,0.81,0.075,-0.056,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29390000,-0.29,0.015,-0.0033,0.96,0.067,-0.045,0.81,0.074,-0.053,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29490000,-0.29,0.015,-0.0033,0.96,0.07,-0.046,0.81,0.081,-0.059,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29590000,-0.29,0.015,-0.0032,0.96,0.068,-0.045,0.81,0.079,-0.057,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.8,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29690000,-0.29,0.015,-0.0032,0.96,0.072,-0.044,0.81,0.087,-0.062,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.7,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29790000,-0.29,0.015,-0.003,0.96,0.069,-0.038,0.8,0.084,-0.059,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29890000,-0.29,0.015,-0.0024,0.96,0.071,-0.039,0.8,0.092,-0.063,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29990000,-0.29,0.016,-0.0025,0.96,0.066,-0.038,0.8,0.087,-0.062,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.5,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30090000,-0.29,0.016,-0.0027,0.96,0.067,-0.037,0.8,0.094,-0.064,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.4,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30190000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.089,-0.056,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.4,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30290000,-0.29,0.016,-0.0027,0.96,0.062,-0.031,0.8,0.096,-0.059,-1.4,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.3,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30390000,-0.29,0.015,-0.0027,0.96,0.06,-0.026,0.8,0.095,-0.053,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.2,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30490000,-0.29,0.015,-0.0027,0.96,0.063,-0.026,0.8,0.1,-0.056,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30590000,-0.29,0.016,-0.0029,0.96,0.062,-0.024,0.8,0.098,-0.053,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30690000,-0.29,0.016,-0.0033,0.96,0.059,-0.023,0.8,0.1,-0.056,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30790000,-0.29,0.016,-0.0031,0.96,0.053,-0.014,0.79,0.096,-0.044,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.92,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30890000,-0.29,0.015,-0.0025,0.96,0.052,-0.01,0.79,0.1,-0.044,-0.95,-0.0013,-0.0058,-4e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.85,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30990000,-0.29,0.015,-0.0026,0.96,0.047,-0.0087,0.79,0.095,-0.043,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.78,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31090000,-0.29,0.015,-0.0028,0.96,0.046,-0.0074,0.79,0.1,-0.043,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.71,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31190000,-0.29,0.016,-0.0029,0.96,0.043,-0.0043,0.8,0.094,-0.04,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.64,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31290000,-0.29,0.016,-0.0031,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.57,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31390000,-0.29,0.015,-0.0029,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.49,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31490000,-0.29,0.016,-0.0026,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31590000,-0.29,0.016,-0.0024,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.35,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.28,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-6.8e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31890000,-0.29,0.017,-0.0023,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.14,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31990000,-0.29,0.016,-0.0026,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,8.4e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.068,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32090000,-0.29,0.016,-0.003,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,4.1e-07,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32190000,-0.29,0.016,-0.0033,0.96,0.028,0.028,0.8,0.094,-0.0047,-0.028,-0.0012,-0.0058,3.5e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.072,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32290000,-0.29,0.016,-0.0031,0.96,0.027,0.03,0.79,0.098,-0.002,0.042,-0.0012,-0.0058,7.3e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.14,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32390000,-0.29,0.016,-0.0033,0.96,0.024,0.032,0.79,0.094,0.0016,0.12,-0.0012,-0.0058,5.5e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0093,0.12,-0.0012,-0.0058,3.2e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32590000,-0.29,0.015,-0.0064,0.96,-0.014,0.084,-0.081,0.093,0.0024,0.1,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.2,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.19,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32790000,-0.29,0.015,-0.0062,0.96,-0.0057,0.09,-0.083,0.093,0.0036,0.072,-0.0012,-0.0058,-7.2e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32890000,-0.29,0.015,-0.0062,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-2.7e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32990000,-0.29,0.015,-0.0061,0.96,-0.0024,0.091,-0.084,0.092,-0.00064,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33090000,-0.29,0.015,-0.006,0.96,0.0014,0.097,-0.081,0.092,0.0086,0.036,-0.0013,-0.0058,-9.8e-06,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.006,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0027,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33390000,-0.3,0.015,-0.0059,0.96,0.014,0.093,-0.078,0.094,-0.0055,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 -33490000,-0.3,0.015,-0.0059,0.96,0.019,0.097,-0.078,0.097,0.0039,-0.00071,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 -33590000,-0.3,0.015,-0.0057,0.95,0.023,0.095,-0.075,0.096,-0.009,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 -33690000,-0.3,0.015,-0.0057,0.95,0.026,0.098,-0.076,0.097,-3.5e-05,-0.019,-0.0013,-0.0058,-2.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 -33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.071,0.094,-0.013,-0.028,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 -33890000,-0.3,0.015,-0.0056,0.95,0.033,0.098,-0.071,0.097,-0.0041,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 -33990000,-0.3,0.015,-0.0055,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 -34090000,-0.3,0.015,-0.0055,0.95,0.038,0.1,-0.066,0.099,-0.0028,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 -34190000,-0.3,0.015,-0.0054,0.95,0.039,0.098,-0.064,0.094,-0.015,-0.05,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 -34290000,-0.3,0.015,-0.0053,0.95,0.04,0.1,-0.062,0.098,-0.0048,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 -34390000,-0.3,0.015,-0.0052,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 -34490000,-0.3,0.015,-0.0052,0.95,0.045,0.1,-0.055,0.097,-0.0069,-0.061,-0.0013,-0.0057,-3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 -34590000,-0.3,0.014,-0.0051,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 -34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 -34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38 -34890000,-0.3,0.014,-0.0051,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41 +2190000,1,-0.011,-0.014,0.00039,0.033,-0.014,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.7e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.095,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.5e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.095,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,0.0004,0.029,-0.01,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.4e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.095,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.014,0.00047,0.033,-0.0091,-0.14,0.011,-0.0043,-0.079,-0.0017,-0.0023,-1.4e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.01,-0.013,0.00039,0.023,-0.0062,-0.15,0.0066,-0.0024,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.095,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.01,-0.013,0.00043,0.027,-0.0055,-0.15,0.0091,-0.003,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.01,-0.013,0.00037,0.022,-0.0032,-0.14,0.0059,-0.0017,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.01,-0.013,0.0003,0.026,-0.005,-0.14,0.0082,-0.0021,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.01,-0.013,0.00031,0.02,-0.0039,-0.15,0.0054,-0.0013,-0.086,-0.002,-0.0033,-3e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.095,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.01,-0.013,0.00052,0.025,-0.0068,-0.15,0.0077,-0.0019,-0.087,-0.002,-0.0033,-3e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.01,-0.013,0.00056,0.02,-0.0065,-0.15,0.0051,-0.0014,-0.097,-0.0021,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.095,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.01,-0.013,0.00058,0.023,-0.0067,-0.15,0.0073,-0.0021,-0.11,-0.0021,-0.0036,-3.4e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.095,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0036,-0.15,0.0049,-0.0014,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.095,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0023,-0.15,0.0072,-0.0017,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.095,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0018,-0.15,0.0051,-0.001,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.095,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.0095,-0.013,0.00052,0.024,-0.0011,-0.15,0.0074,-0.0012,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.095,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.0094,-0.012,0.00055,0.019,0.0033,-0.15,0.0051,-0.00056,-0.11,-0.0022,-0.0043,-4.7e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.095,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.0094,-0.013,0.00063,0.021,0.0045,-0.14,0.0072,-0.00017,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.095,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.0094,-0.013,0.00069,0.026,0.0042,-0.14,0.0096,0.00021,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.095,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.0093,-0.012,0.00076,0.022,0.0037,-0.12,0.0071,0.00045,-0.098,-0.0022,-0.0044,-5.1e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.095,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.0094,-0.012,0.00072,0.024,0.0034,-0.12,0.0094,0.0008,-0.1,-0.0022,-0.0044,-5.1e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.095,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.0095,-0.012,0.00074,0.021,0.0033,-0.12,0.0068,0.00068,-0.11,-0.0022,-0.0046,-5.6e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.095,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.0094,-0.012,0.00069,0.025,0.0018,-0.11,0.0091,0.00086,-0.094,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.095,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.0094,-0.012,0.00076,0.021,0.0036,-0.11,0.0067,0.00072,-0.095,-0.0022,-0.0048,-6.1e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.095,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.0094,-0.012,0.00082,0.023,0.0024,-0.11,0.0089,0.001,-0.098,-0.0022,-0.0048,-6.1e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.095,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.0094,-0.012,0.00076,0.017,0.0027,-0.1,0.0064,0.00074,-0.09,-0.0021,-0.005,-6.5e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.095,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.0093,-0.012,0.00086,0.015,0.0048,-0.099,0.008,0.0012,-0.092,-0.0021,-0.005,-6.5e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.095,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.0093,-0.012,0.0009,0.01,0.0024,-0.093,0.0053,0.0009,-0.088,-0.0021,-0.0051,-6.9e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.095,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.0092,-0.012,0.00088,0.013,0.0031,-0.085,0.0065,0.0012,-0.083,-0.0021,-0.0051,-6.9e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.0091,-0.011,0.00096,0.01,0.0034,-0.082,0.0045,0.00087,-0.082,-0.0021,-0.0052,-7.2e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.0089,-0.012,0.001,0.0099,0.007,-0.08,0.0055,0.0014,-0.079,-0.0021,-0.0052,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0071,-0.068,0.0038,0.0013,-0.072,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0021,-0.067,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.002,-0.065,-0.002,-0.0054,-7.7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0089,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0033,-0.058,-0.002,-0.0054,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.0029,-0.055,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0046,-0.053,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0037,-0.056,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0088,-0.012,0.00085,0.011,0.017,-0.041,0.0038,0.0053,-0.05,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0071,-0.047,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0089,-0.011,0.00067,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0089,-0.011,0.0007,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0089,-0.011,0.00071,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0018,-0.0056,-8.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.0089,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0088,-0.011,0.0005,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.00047,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,8.1e-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.00039,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,8.1e-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.29,0.024,-0.0061,0.96,-0.2,-0.032,-0.037,-0.11,-0.019,-0.055,-0.00077,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.095,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1,1.8 +7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.048,-0.038,-0.15,-0.027,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.095,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1,1.8 +7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1,1.8 +7290000,-0.29,0.025,-0.0063,0.96,-0.28,-0.066,-0.034,-0.2,-0.04,-0.055,-0.00059,-0.01,-0.00021,-0.00088,-0.00019,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1,1.9 +7390000,-0.29,0.024,-0.0062,0.96,-0.3,-0.072,-0.032,-0.23,-0.047,-0.052,-0.00058,-0.01,-0.00021,-0.0011,-0.00023,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00014,0.0013,0.0013,0.00086,0.0013,1,1,1.9 +7490000,-0.29,0.024,-0.0063,0.96,-0.32,-0.08,-0.026,-0.25,-0.056,-0.046,-0.00057,-0.0099,-0.00021,-0.0015,-0.00027,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 +7590000,-0.29,0.024,-0.0064,0.96,-0.34,-0.088,-0.022,-0.28,-0.065,-0.041,-0.00055,-0.0098,-0.00021,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 +7690000,-0.29,0.024,-0.0064,0.96,-0.35,-0.096,-0.022,-0.31,-0.076,-0.036,-0.00053,-0.0097,-0.00021,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 +7790000,-0.29,0.023,-0.0062,0.96,-0.36,-0.11,-0.024,-0.34,-0.09,-0.041,-0.00046,-0.0096,-0.0002,-0.0017,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 +7890000,-0.29,0.023,-0.0063,0.96,-0.37,-0.11,-0.025,-0.37,-0.1,-0.045,-0.00044,-0.0095,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00086,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.0001,0.0013,0.0013,0.00083,0.0013,1,1,2 +7990000,-0.29,0.023,-0.0063,0.96,-0.39,-0.12,-0.021,-0.4,-0.11,-0.041,-0.00047,-0.0094,-0.0002,-0.0016,-0.0002,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.8e-05,0.0013,0.0012,0.00083,0.0013,1,1,2 +8090000,-0.29,0.023,-0.0062,0.96,-0.4,-0.13,-0.022,-0.43,-0.13,-0.044,-0.0004,-0.0094,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.0008,0.00083,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,9.6e-05,0.0013,0.0012,0.00083,0.0013,1,1,2.1 +8190000,-0.29,0.022,-0.0062,0.96,-0.41,-0.14,-0.017,-0.46,-0.15,-0.038,-0.00033,-0.0092,-0.0002,-0.0016,-0.00026,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00078,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.4e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 +8290000,-0.29,0.022,-0.0064,0.96,-0.44,-0.15,-0.016,-0.51,-0.16,-0.038,-0.00038,-0.0093,-0.0002,-0.0017,-0.00023,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00075,0.00078,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.2e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 +8390000,-0.29,0.022,-0.0064,0.96,-0.45,-0.15,-0.015,-0.55,-0.17,-0.036,-0.00039,-0.0092,-0.0002,-0.0017,-0.00021,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0012,9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 +8490000,-0.29,0.022,-0.0064,0.96,-0.45,-0.15,-0.016,-0.58,-0.18,-0.041,-0.00048,-0.0091,-0.00019,-0.0016,-0.00013,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00071,0.00073,0.053,0.82,0.81,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.2 +8590000,-0.29,0.022,-0.0062,0.96,-0.45,-0.16,-0.012,-0.6,-0.2,-0.036,-0.00042,-0.0089,-0.00019,-0.0016,-0.00013,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00069,0.00071,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.7e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 +8690000,-0.29,0.021,-0.0063,0.96,-0.46,-0.16,-0.014,-0.63,-0.21,-0.037,-0.00048,-0.0088,-0.00019,-0.0016,-9e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00067,0.00069,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,8.6e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 +8790000,-0.29,0.021,-0.0064,0.96,-0.48,-0.17,-0.013,-0.67,-0.23,-0.035,-0.00046,-0.0088,-0.00018,-0.0016,-8.7e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00065,0.00067,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,8.5e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 +8890000,-0.29,0.021,-0.0063,0.96,-0.47,-0.17,-0.0093,-0.68,-0.24,-0.029,-0.00051,-0.0085,-0.00018,-0.0016,1.9e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00063,0.00065,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,8.4e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 +8990000,-0.29,0.02,-0.0061,0.96,-0.45,-0.17,-0.0088,-0.67,-0.25,-0.032,-0.00055,-0.0082,-0.00017,-0.0013,0.00012,-0.13,-0.1,-0.024,0.5,0.08,-0.032,-0.069,0,0,0.095,0.00062,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,8.3e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 +9090000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0099,-0.72,-0.24,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00029,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 +9190000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0095,-0.73,-0.24,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00042,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.095,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.3 +9290000,-0.29,0.02,-0.006,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00048,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 +9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0076,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 +9490000,-0.29,0.019,-0.0059,0.96,-0.46,-0.17,-0.0055,-0.78,-0.29,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00055,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 +9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00086,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4 +9690000,-0.29,0.019,-0.0058,0.96,-0.46,-0.2,-0.0026,-0.83,-0.37,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00041,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00076,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00052,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9990000,-0.29,0.019,-0.0057,0.96,-0.48,-0.23,-0.002,-0.92,-0.47,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.5 +10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00044,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10190000,-0.29,0.019,-0.0055,0.96,-0.49,-0.27,5.1e-05,-0.97,-0.6,-0.031,-0.00028,-0.007,-0.00015,-0.00027,0.00012,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10290000,-0.29,0.019,-0.0055,0.96,-0.48,-0.27,-0.0011,-0.97,-0.61,-0.03,-0.00034,-0.0069,-0.00014,-0.00015,0.00018,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,3.7e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00014,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00011,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10790000,-0.29,0.019,-0.005,0.96,-0.033,-0.015,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,5.9e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10890000,-0.29,0.019,-0.0049,0.96,-0.043,-0.02,0.01,-0.0036,-0.0035,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.8 +10990000,-0.29,0.019,-0.005,0.96,-0.039,-0.022,0.016,-0.0014,-0.0019,-0.012,-0.00058,-0.0064,-0.00012,0.0058,0.00072,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 +11090000,-0.29,0.019,-0.0051,0.96,-0.05,-0.029,0.02,-0.0059,-0.0046,-0.0081,-0.00046,-0.0063,-0.00013,0.006,0.00072,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 +11190000,-0.29,0.018,-0.0051,0.96,-0.041,-0.027,0.027,-0.002,-0.0028,-0.0011,-0.00047,-0.0063,-0.00013,0.013,0.0018,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 +11290000,-0.29,0.018,-0.0052,0.96,-0.05,-0.029,0.026,-0.0065,-0.0056,-0.00072,-0.00048,-0.0063,-0.00013,0.013,0.0017,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.9 +11390000,-0.29,0.018,-0.0051,0.96,-0.043,-0.025,0.017,-0.0037,-0.0035,-0.0091,-0.00053,-0.0063,-0.00013,0.019,0.0032,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 +11490000,-0.29,0.018,-0.005,0.96,-0.05,-0.027,0.021,-0.0082,-0.0063,-0.003,-0.00054,-0.0063,-0.00012,0.019,0.0034,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 +11590000,-0.29,0.018,-0.0051,0.96,-0.044,-0.023,0.019,-0.005,-0.004,-0.004,-0.00058,-0.0063,-0.00012,0.025,0.0047,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 +11690000,-0.29,0.017,-0.0051,0.96,-0.05,-0.027,0.019,-0.0096,-0.0065,-0.0053,-0.00062,-0.0063,-0.00012,0.025,0.0047,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.087,0.087,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,3 +11790000,-0.29,0.017,-0.005,0.96,-0.04,-0.026,0.02,-0.0055,-0.0056,-0.0023,-0.00072,-0.0063,-0.00012,0.03,0.0053,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 +11890000,-0.29,0.017,-0.0052,0.96,-0.048,-0.029,0.018,-0.01,-0.0083,-0.0016,-0.0007,-0.0063,-0.00012,0.03,0.0052,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 +11990000,-0.29,0.017,-0.0052,0.96,-0.039,-0.022,0.015,-0.0063,-0.0055,-0.0052,-0.00073,-0.0063,-0.00012,0.037,0.0074,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 +12090000,-0.29,0.017,-0.0051,0.96,-0.045,-0.024,0.018,-0.011,-0.008,0.00088,-0.00071,-0.0062,-0.00012,0.037,0.0077,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3.1 +12190000,-0.29,0.017,-0.0051,0.96,-0.038,-0.014,0.017,-0.0054,-0.0031,0.0028,-0.00067,-0.0062,-0.00012,0.043,0.0095,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 +12290000,-0.29,0.017,-0.0052,0.96,-0.04,-0.013,0.016,-0.0093,-0.0044,0.0038,-0.00064,-0.0062,-0.00012,0.043,0.0095,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 +12390000,-0.29,0.016,-0.0052,0.96,-0.033,-0.0095,0.014,-0.0051,-0.0028,-0.0022,-0.00063,-0.0062,-0.00012,0.047,0.0098,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 +12490000,-0.29,0.016,-0.0052,0.96,-0.036,-0.011,0.018,-0.0086,-0.0039,-0.00015,-0.00062,-0.0061,-0.00012,0.047,0.0099,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 +12590000,-0.29,0.016,-0.0051,0.96,-0.03,-0.0091,0.019,-0.0035,-0.0041,0.0017,-0.00062,-0.0061,-0.00012,0.05,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 +12690000,-0.29,0.016,-0.0051,0.96,-0.033,-0.0073,0.019,-0.0066,-0.0049,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.009,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 +12790000,-0.29,0.016,-0.0049,0.96,-0.023,-0.013,0.02,-0.0015,-0.0079,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.008,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.4e-06,7e-06,2.2e-06,0.0093,0.0096,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.2 +12890000,-0.29,0.016,-0.0049,0.96,-0.025,-0.013,0.021,-0.0039,-0.0093,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0085,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +12990000,-0.29,0.016,-0.0049,0.96,-0.021,-0.011,0.022,-0.0011,-0.0065,0.0096,-0.00076,-0.0061,-0.00012,0.054,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0083,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +13090000,-0.29,0.016,-0.0049,0.96,-0.023,-0.012,0.019,-0.0032,-0.0078,0.0084,-0.0008,-0.006,-0.00011,0.054,0.0097,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +13190000,-0.29,0.016,-0.0048,0.96,-0.019,-0.012,0.018,-0.0017,-0.0088,0.009,-0.00083,-0.006,-0.00011,0.055,0.0096,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0072,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 +13290000,-0.29,0.016,-0.0048,0.96,-0.02,-0.012,0.016,-0.0037,-0.01,0.0083,-0.00081,-0.006,-0.00011,0.056,0.0099,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13390000,-0.29,0.016,-0.0048,0.96,-0.017,-0.0089,0.015,-0.0013,-0.0069,0.0089,-0.00079,-0.006,-0.00011,0.057,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.0001,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13490000,-0.29,0.016,-0.0048,0.96,-0.019,-0.011,0.015,-0.0032,-0.0081,0.0051,-0.0008,-0.006,-0.00011,0.057,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,0.0001,0.0001,0.051,0.053,0.053,0.009,0.067,0.067,0.045,5.6e-06,5.2e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13590000,-0.29,0.016,-0.0048,0.96,-0.014,-0.0079,0.016,0.0017,-0.0057,0.0036,-0.00078,-0.006,-0.00011,0.059,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,9.3e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0059,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 +13690000,-0.29,0.016,-0.0047,0.96,-0.015,-0.0071,0.016,0.00029,-0.0065,0.0062,-0.0008,-0.0059,-0.00011,0.059,0.011,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,9.4e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +13790000,-0.29,0.015,-0.0047,0.96,-0.011,-0.0051,0.016,0.0054,-0.0035,0.0057,-0.00079,-0.006,-0.00011,0.061,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.7e-05,8.7e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +13890000,-0.29,0.015,-0.0046,0.96,-0.012,-0.0062,0.017,0.0044,-0.0041,0.0078,-0.00083,-0.006,-0.00011,0.06,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.8e-05,8.8e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +13990000,-0.29,0.015,-0.0046,0.96,-0.014,-0.01,0.016,0.0039,-0.0046,0.0067,-0.00086,-0.006,-0.00011,0.061,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.3e-05,8.3e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0047,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 +14090000,-0.29,0.015,-0.0047,0.96,-0.013,-0.0041,0.017,0.0023,-0.0051,0.0031,-0.00078,-0.006,-0.00011,0.061,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14190000,-0.29,0.015,-0.0048,0.96,-0.01,-0.0029,0.017,0.0036,-0.004,0.0033,-0.00074,-0.006,-0.00012,0.063,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0046,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14290000,-0.29,0.015,-0.0047,0.96,-0.013,-0.0032,0.015,0.0025,-0.0043,0.0075,-0.00074,-0.0059,-0.00011,0.063,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.1e-05,8e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14390000,-0.29,0.015,-0.0047,0.96,-0.012,-0.0028,0.017,0.0036,-0.0048,0.012,-0.00075,-0.0059,-0.00011,0.063,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0043,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 +14490000,-0.29,0.015,-0.0049,0.96,-0.012,-0.0021,0.02,0.0023,-0.0049,0.014,-0.00071,-0.0059,-0.00012,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.8e-05,7.7e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14590000,-0.29,0.015,-0.0049,0.96,-0.015,-0.0038,0.018,0.0007,-0.0053,0.01,-0.0007,-0.0059,-0.00012,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.5e-05,7.4e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0038,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14690000,-0.29,0.015,-0.0049,0.96,-0.016,-0.0041,0.018,-0.00088,-0.0058,0.01,-0.0007,-0.0059,-0.00011,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14790000,-0.29,0.015,-0.005,0.96,-0.019,-0.0015,0.018,-0.00058,-0.0013,0.013,-0.00073,-0.0058,-0.00011,0.065,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 +14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.00041,0.022,-0.0027,-0.0017,0.014,-0.00074,-0.0058,-0.00011,0.065,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0015,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +15090000,-0.29,0.015,-0.0048,0.96,-0.021,-0.0027,0.029,-0.0043,-0.0031,0.018,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00079,0.029,-0.0034,-0.0024,0.02,-0.00073,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +15290000,-0.29,0.016,-0.005,0.96,-0.024,-0.00091,0.029,-0.0058,-0.0029,0.017,-0.00075,-0.0057,-0.00011,0.067,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15490000,-0.29,0.016,-0.0051,0.96,-0.025,-0.00034,0.028,-0.007,-0.0026,0.018,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0047,0.028,-0.0032,-0.0058,0.017,-0.00079,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15690000,-0.29,0.016,-0.005,0.96,-0.024,-0.0026,0.028,-0.0048,-0.0062,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +15790000,-0.29,0.015,-0.005,0.96,-0.021,-0.0013,0.028,-0.0035,-0.0053,0.019,-0.00087,-0.0058,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +15890000,-0.29,0.016,-0.0051,0.96,-0.021,-0.0026,0.029,-0.0059,-0.0053,0.019,-0.00084,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0021,0.026,-0.0049,-0.0045,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 +16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00082,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00061,0.023,-0.0071,-0.0037,0.015,-0.0008,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16290000,-0.29,0.015,-0.005,0.96,-0.022,0.00033,0.022,-0.009,-0.0038,0.017,-0.00081,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16390000,-0.29,0.016,-0.0049,0.96,-0.023,-0.00021,0.023,-0.007,-0.0037,0.017,-0.00083,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16490000,-0.29,0.016,-0.005,0.96,-0.027,0.00075,0.025,-0.0098,-0.0036,0.021,-0.00082,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16590000,-0.29,0.016,-0.005,0.96,-0.031,0.0011,0.029,-0.0085,-0.0031,0.021,-0.00082,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16690000,-0.29,0.015,-0.0051,0.96,-0.034,0.0047,0.029,-0.011,-0.0029,0.021,-0.00084,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16790000,-0.29,0.015,-0.0049,0.96,-0.035,0.0045,0.028,-0.0095,-0.0026,0.021,-0.00086,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0028,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 +16890000,-0.29,0.015,-0.0049,0.96,-0.035,0.004,0.029,-0.013,-0.0026,0.02,-0.00089,-0.0057,-0.00011,0.068,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6.1e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +16990000,-0.29,0.015,-0.0049,0.96,-0.032,0.0044,0.029,-0.011,-0.0028,0.019,-0.0009,-0.0057,-0.00011,0.069,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +17090000,-0.29,0.015,-0.005,0.96,-0.037,0.0063,0.028,-0.015,-0.0023,0.018,-0.00089,-0.0057,-0.00011,0.069,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +17190000,-0.29,0.015,-0.0051,0.96,-0.036,0.0082,0.03,-0.014,-0.0039,0.021,-0.00089,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 +17290000,-0.29,0.015,-0.0051,0.96,-0.039,0.0089,0.029,-0.017,-0.0027,0.021,-0.00088,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17390000,-0.29,0.015,-0.005,0.96,-0.029,0.014,0.029,-0.01,-0.0014,0.021,-0.00091,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17490000,-0.29,0.015,-0.0051,0.96,-0.029,0.015,0.029,-0.013,0.00019,0.023,-0.0009,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17590000,-0.29,0.015,-0.0051,0.96,-0.029,0.013,0.028,-0.012,-0.00019,0.02,-0.00091,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 +17690000,-0.29,0.015,-0.0052,0.96,-0.03,0.014,0.029,-0.015,0.00095,0.023,-0.00092,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 +17790000,-0.29,0.015,-0.0052,0.96,-0.031,0.014,0.029,-0.015,0.0017,0.028,-0.00093,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0026,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 +17890000,-0.29,0.015,-0.0051,0.96,-0.035,0.015,0.029,-0.017,0.0029,0.032,-0.00094,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 +17990000,-0.29,0.015,-0.0051,0.96,-0.034,0.016,0.029,-0.014,0.0052,0.033,-0.00094,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 +18090000,-0.29,0.015,-0.0052,0.96,-0.036,0.017,0.028,-0.018,0.0067,0.031,-0.00094,-0.0057,-0.00011,0.07,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18190000,-0.29,0.015,-0.0051,0.96,-0.032,0.014,0.028,-0.013,0.0045,0.029,-0.00098,-0.0057,-0.00011,0.07,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18290000,-0.29,0.015,-0.0051,0.96,-0.036,0.014,0.027,-0.017,0.0056,0.028,-0.00098,-0.0057,-0.00011,0.07,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18390000,-0.29,0.015,-0.005,0.96,-0.032,0.014,0.027,-0.012,0.0047,0.027,-0.00099,-0.0057,-0.00011,0.07,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 +18490000,-0.29,0.015,-0.005,0.96,-0.036,0.013,0.026,-0.015,0.0056,0.029,-0.001,-0.0057,-0.00011,0.07,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0025,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18590000,-0.29,0.015,-0.0049,0.96,-0.034,0.013,0.026,-0.013,0.005,0.031,-0.001,-0.0057,-0.00011,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18690000,-0.29,0.015,-0.0049,0.96,-0.034,0.012,0.025,-0.015,0.0059,0.03,-0.001,-0.0057,-0.00011,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18790000,-0.29,0.015,-0.0049,0.96,-0.031,0.011,0.024,-0.012,0.0051,0.028,-0.001,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 +18890000,-0.29,0.015,-0.0048,0.96,-0.031,0.012,0.022,-0.015,0.0064,0.024,-0.001,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +18990000,-0.29,0.015,-0.0048,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +19090000,-0.29,0.015,-0.0048,0.96,-0.028,0.013,0.024,-0.016,0.0063,0.024,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +19190000,-0.29,0.015,-0.0048,0.96,-0.026,0.014,0.023,-0.014,0.0062,0.023,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 +19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19390000,-0.29,0.015,-0.0049,0.96,-0.026,0.012,0.025,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19690000,-0.29,0.015,-0.0048,0.96,-0.025,0.013,0.025,-0.018,0.0078,0.021,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +19790000,-0.29,0.015,-0.0049,0.96,-0.022,0.013,0.023,-0.018,0.0084,0.017,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +19890000,-0.29,0.015,-0.005,0.96,-0.023,0.013,0.023,-0.02,0.0097,0.015,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +19990000,-0.29,0.015,-0.005,0.96,-0.02,0.014,0.021,-0.016,0.009,0.012,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 +20090000,-0.29,0.015,-0.005,0.96,-0.023,0.016,0.021,-0.018,0.01,0.016,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5.1 +20190000,-0.29,0.015,-0.005,0.96,-0.024,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 +20290000,-0.29,0.015,-0.005,0.96,-0.022,0.016,0.022,-0.021,0.012,0.016,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 +20390000,-0.29,0.015,-0.0049,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 +20490000,-0.29,0.015,-0.0049,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 +20590000,-0.29,0.015,-0.0048,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.2e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20690000,-0.29,0.015,-0.0047,0.96,-0.017,0.016,0.023,-0.025,0.014,0.014,-0.0011,-0.0058,-0.00013,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.5e-05,5.1e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20790000,-0.29,0.015,-0.0041,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20890000,-0.29,0.01,0.0045,0.96,-0.0062,0.0015,-0.11,-0.021,0.01,0.0066,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.3e-05,5e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 +20990000,-0.29,0.0063,0.0075,0.96,0.0089,-0.015,-0.25,-0.017,0.008,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.092,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.2e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21090000,-0.29,0.0069,0.0059,0.96,0.023,-0.028,-0.37,-0.015,0.0061,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.061,5.3e-05,4.9e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21190000,-0.29,0.0088,0.0033,0.96,0.029,-0.033,-0.5,-0.013,0.0046,-0.075,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.025,5.1e-05,4.8e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21290000,-0.29,0.01,0.0013,0.96,0.027,-0.036,-0.63,-0.01,0.002,-0.13,-0.0011,-0.0058,-0.00014,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.034,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21390000,-0.29,0.011,-0.00017,0.96,0.021,-0.029,-0.75,-0.012,0.0052,-0.2,-0.0011,-0.0058,-0.00013,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.099,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21490000,-0.29,0.012,-0.00092,0.96,0.014,-0.028,-0.89,-0.0096,0.0021,-0.28,-0.0011,-0.0058,-0.00013,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.18,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21590000,-0.29,0.012,-0.0014,0.96,0.0029,-0.022,-1,-0.014,0.0067,-0.37,-0.0011,-0.0058,-0.00012,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.27,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.002,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21690000,-0.29,0.012,-0.0018,0.96,-0.0024,-0.019,-1.1,-0.014,0.0039,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.39,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21790000,-0.29,0.012,-0.0021,0.96,-0.0082,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.51,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0073,-1.4,-0.016,0.0096,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.65,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00089,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22090000,-0.29,0.013,-0.0038,0.96,-0.023,0.0041,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.93,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22190000,-0.29,0.013,-0.0042,0.96,-0.03,0.011,-1.4,-0.027,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.1,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22290000,-0.29,0.014,-0.0049,0.96,-0.038,0.015,-1.4,-0.031,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.2,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22390000,-0.29,0.014,-0.0052,0.96,-0.045,0.022,-1.4,-0.038,0.029,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.4,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22490000,-0.29,0.014,-0.0054,0.96,-0.052,0.028,-1.4,-0.043,0.032,-1.6,-0.001,-0.0058,-7.2e-05,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.5,5e-05,4.6e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22590000,-0.29,0.015,-0.0052,0.96,-0.057,0.034,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.8e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.6,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22690000,-0.29,0.015,-0.0051,0.96,-0.062,0.039,-1.4,-0.05,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.8,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +22790000,-0.29,0.016,-0.005,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.2e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.9,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +22890000,-0.29,0.016,-0.0051,0.96,-0.073,0.048,-1.4,-0.062,0.046,-2.2,-0.0011,-0.0058,-6.8e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.1,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +22990000,-0.29,0.016,-0.0049,0.96,-0.076,0.048,-1.4,-0.065,0.045,-2.3,-0.0011,-0.0058,-7e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.2,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23090000,-0.29,0.017,-0.0049,0.96,-0.082,0.052,-1.4,-0.072,0.05,-2.5,-0.0011,-0.0058,-6.9e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.4,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23190000,-0.29,0.017,-0.0048,0.96,-0.084,0.047,-1.4,-0.072,0.046,-2.6,-0.0011,-0.0058,-8.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.5,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23290000,-0.29,0.017,-0.0053,0.96,-0.09,0.051,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.7,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23390000,-0.29,0.017,-0.0052,0.96,-0.09,0.054,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.8e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.8,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23490000,-0.29,0.017,-0.0053,0.96,-0.096,0.054,-1.4,-0.085,0.057,-3,-0.0011,-0.0058,-8.3e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.9,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23590000,-0.29,0.017,-0.0054,0.96,-0.095,0.048,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.6e-05,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.1,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23690000,-0.29,0.018,-0.006,0.96,-0.094,0.051,-1.3,-0.09,0.051,-3.3,-0.0011,-0.0058,-9.2e-05,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.2,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23790000,-0.29,0.021,-0.0074,0.96,-0.079,0.048,-0.95,-0.08,0.047,-3.4,-0.0012,-0.0058,-9.7e-05,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.3,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23890000,-0.29,0.025,-0.01,0.96,-0.074,0.051,-0.52,-0.087,0.051,-3.5,-0.0012,-0.0058,-9.4e-05,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.4,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +23990000,-0.29,0.028,-0.012,0.96,-0.065,0.05,-0.13,-0.074,0.046,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +24090000,-0.29,0.027,-0.012,0.96,-0.072,0.058,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.7e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 +24190000,-0.29,0.022,-0.0092,0.96,-0.076,0.055,0.088,-0.066,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24290000,-0.29,0.019,-0.0071,0.96,-0.081,0.057,0.066,-0.074,0.044,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24390000,-0.29,0.018,-0.0063,0.96,-0.064,0.05,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24490000,-0.29,0.018,-0.0065,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24590000,-0.29,0.018,-0.0071,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24690000,-0.29,0.018,-0.0076,0.96,-0.045,0.044,0.075,-0.046,0.036,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24890000,-0.29,0.017,-0.0076,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25090000,-0.29,0.016,-0.0077,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25190000,-0.29,0.016,-0.0079,0.96,-0.011,0.042,0.047,-0.0078,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25290000,-0.3,0.015,-0.0081,0.96,-0.006,0.045,0.042,-0.0086,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25390000,-0.3,0.015,-0.0082,0.96,0.003,0.043,0.04,0.0015,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25490000,-0.3,0.015,-0.0083,0.96,0.0074,0.044,0.04,0.0012,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25590000,-0.3,0.015,-0.0085,0.96,0.012,0.04,0.041,0.0087,0.0095,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25690000,-0.3,0.014,-0.0079,0.96,0.013,0.039,0.03,0.01,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25790000,-0.3,0.014,-0.0078,0.96,0.024,0.034,0.03,0.018,0.0034,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25890000,-0.3,0.014,-0.0078,0.96,0.03,0.034,0.033,0.02,0.0076,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +25990000,-0.3,0.014,-0.0078,0.96,0.032,0.029,0.026,0.017,-0.0036,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26090000,-0.3,0.014,-0.0075,0.96,0.037,0.029,0.025,0.021,-0.0015,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26190000,-0.3,0.014,-0.0073,0.96,0.042,0.02,0.02,0.024,-0.018,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26290000,-0.3,0.015,-0.0073,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26390000,-0.3,0.015,-0.0067,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26490000,-0.3,0.015,-0.0065,0.96,0.043,0.0088,0.028,0.024,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26690000,-0.3,0.015,-0.0058,0.95,0.044,-0.0048,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26790000,-0.3,0.014,-0.0056,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +27090000,-0.3,0.015,-0.0042,0.95,0.056,-0.026,0.025,0.028,-0.066,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.019,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27290000,-0.3,0.016,-0.0043,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27390000,-0.3,0.018,-0.0055,0.96,0.067,-0.025,0.46,0.0071,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27490000,-0.3,0.02,-0.0066,0.95,0.072,-0.028,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27590000,-0.3,0.019,-0.0067,0.96,0.063,-0.03,0.87,0.0077,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.3,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27690000,-0.3,0.016,-0.0058,0.96,0.058,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.2,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27790000,-0.3,0.015,-0.0046,0.96,0.054,-0.026,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27890000,-0.3,0.015,-0.0043,0.96,0.061,-0.031,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +27990000,-0.3,0.015,-0.0047,0.96,0.061,-0.034,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28090000,-0.3,0.015,-0.0049,0.96,0.065,-0.034,0.8,0.026,-0.027,-3,-0.0013,-0.0058,-0.00022,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.9,4.5e-05,4e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28190000,-0.3,0.015,-0.0043,0.96,0.062,-0.033,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28290000,-0.3,0.016,-0.0037,0.96,0.066,-0.036,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28390000,-0.3,0.016,-0.0037,0.96,0.068,-0.038,0.81,0.035,-0.034,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.7,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28490000,-0.3,0.017,-0.0039,0.96,0.07,-0.041,0.81,0.043,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.6,4.5e-05,4e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28590000,-0.29,0.017,-0.0039,0.96,0.063,-0.042,0.81,0.043,-0.041,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.5,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28690000,-0.29,0.016,-0.0038,0.96,0.062,-0.043,0.81,0.049,-0.045,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.5,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28790000,-0.29,0.016,-0.0032,0.96,0.06,-0.042,0.81,0.05,-0.044,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.4,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28890000,-0.29,0.015,-0.003,0.96,0.064,-0.044,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.3,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +28990000,-0.29,0.016,-0.0027,0.96,0.062,-0.042,0.81,0.058,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29090000,-0.29,0.016,-0.0026,0.96,0.065,-0.043,0.81,0.065,-0.053,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29190000,-0.29,0.016,-0.0025,0.96,0.066,-0.043,0.8,0.067,-0.052,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.1,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29290000,-0.29,0.016,-0.0027,0.96,0.071,-0.048,0.81,0.075,-0.056,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29390000,-0.29,0.015,-0.0033,0.96,0.067,-0.045,0.81,0.074,-0.053,-2,-0.0013,-0.0058,-0.00014,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29490000,-0.29,0.015,-0.0032,0.96,0.07,-0.046,0.81,0.081,-0.059,-2,-0.0013,-0.0058,-0.00014,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29590000,-0.29,0.015,-0.0031,0.96,0.068,-0.045,0.81,0.079,-0.057,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.8,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29690000,-0.29,0.015,-0.0032,0.96,0.072,-0.044,0.81,0.087,-0.062,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.7,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29790000,-0.29,0.015,-0.0029,0.96,0.069,-0.038,0.8,0.084,-0.059,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29890000,-0.29,0.015,-0.0023,0.96,0.071,-0.039,0.8,0.092,-0.063,-1.7,-0.0013,-0.0058,-9.4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +29990000,-0.29,0.016,-0.0025,0.96,0.066,-0.038,0.8,0.087,-0.062,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.5,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30090000,-0.29,0.016,-0.0026,0.96,0.067,-0.037,0.8,0.094,-0.064,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.4,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30190000,-0.29,0.016,-0.0026,0.96,0.062,-0.031,0.8,0.089,-0.056,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.4,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30290000,-0.29,0.016,-0.0026,0.96,0.062,-0.031,0.8,0.096,-0.059,-1.4,-0.0013,-0.0058,-8.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.3,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30390000,-0.29,0.015,-0.0026,0.96,0.06,-0.026,0.8,0.095,-0.053,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.2,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30490000,-0.29,0.015,-0.0026,0.96,0.063,-0.025,0.8,0.1,-0.056,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30590000,-0.29,0.016,-0.0029,0.96,0.062,-0.024,0.8,0.098,-0.053,-1.2,-0.0013,-0.0058,-5e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30690000,-0.29,0.016,-0.0032,0.96,0.059,-0.023,0.8,0.1,-0.055,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30790000,-0.29,0.016,-0.003,0.96,0.053,-0.014,0.79,0.096,-0.044,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.92,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30890000,-0.29,0.015,-0.0024,0.96,0.051,-0.01,0.79,0.1,-0.044,-0.95,-0.0013,-0.0058,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.85,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +30990000,-0.29,0.015,-0.0025,0.96,0.047,-0.0086,0.79,0.095,-0.043,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.78,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31090000,-0.29,0.015,-0.0027,0.96,0.046,-0.0074,0.79,0.099,-0.043,-0.81,-0.0012,-0.0058,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.71,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31190000,-0.29,0.016,-0.0028,0.96,0.043,-0.0042,0.8,0.094,-0.039,-0.74,-0.0012,-0.0058,-2.7e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.64,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31290000,-0.29,0.016,-0.003,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.57,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31390000,-0.29,0.015,-0.0028,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.49,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31490000,-0.29,0.016,-0.0025,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31590000,-0.29,0.016,-0.0023,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.35,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.28,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-9.9e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31890000,-0.29,0.017,-0.0022,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.4e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.14,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31990000,-0.29,0.016,-0.0025,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,5.2e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.068,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,9.3e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32190000,-0.29,0.016,-0.0032,0.96,0.028,0.028,0.8,0.094,-0.0046,-0.028,-0.0012,-0.0058,3.2e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.072,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32290000,-0.29,0.016,-0.003,0.96,0.027,0.03,0.79,0.098,-0.0019,0.042,-0.0012,-0.0058,7e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.14,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32390000,-0.29,0.016,-0.0032,0.96,0.024,0.032,0.79,0.094,0.0018,0.12,-0.0012,-0.0058,5.2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0094,0.12,-0.0012,-0.0058,2.9e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32590000,-0.29,0.015,-0.0063,0.96,-0.014,0.084,-0.081,0.093,0.0025,0.1,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.2,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.19,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.0059,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 +33490000,-0.3,0.015,-0.0058,0.96,0.02,0.097,-0.078,0.097,0.004,-0.00072,-0.0013,-0.0058,-2.1e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 +33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 +33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.9e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 +33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.071,0.094,-0.013,-0.028,-0.0013,-0.0058,-3.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 +33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 +33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 +34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 +34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.8e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 +34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 +34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 +34490000,-0.3,0.015,-0.0051,0.95,0.045,0.1,-0.055,0.097,-0.0068,-0.061,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 +34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4.1e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 +34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 +34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38 +34890000,-0.3,0.014,-0.005,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41 diff --git a/src/modules/ekf2/test/test_EKF_gps.cpp b/src/modules/ekf2/test/test_EKF_gps.cpp index 57e277240faf..0e243176a2af 100644 --- a/src/modules/ekf2/test/test_EKF_gps.cpp +++ b/src/modules/ekf2/test/test_EKF_gps.cpp @@ -136,7 +136,7 @@ TEST_F(EkfGpsTest, resetToGpsVelocity) _ekf->set_in_air_status(true); _ekf->set_vehicle_at_rest(false); - _sensor_simulator.runSeconds(5.2); // required to pass the checks + _sensor_simulator.runSeconds(1.2); // required to pass the checks _sensor_simulator.runMicroseconds(dt_us); // THEN: a reset to GPS velocity should be done diff --git a/src/modules/ekf2/test/test_EKF_mag.cpp b/src/modules/ekf2/test/test_EKF_mag.cpp index 6641b4fe6dc1..ca4f440c624d 100644 --- a/src/modules/ekf2/test/test_EKF_mag.cpp +++ b/src/modules/ekf2/test/test_EKF_mag.cpp @@ -68,6 +68,7 @@ class EkfMagTest : public ::testing::Test TEST_F(EkfMagTest, fusionStartWithReset) { + _ekf->set_min_required_gps_health_time(5e6); // GIVEN: some meaningful mag data const float mag_heading = M_PI_F / 3.f; const float incl = 63.1f; @@ -84,11 +85,10 @@ TEST_F(EkfMagTest, fusionStartWithReset) EXPECT_FALSE(_ekf_wrapper.isIntendingMag3DFusion()); EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 1); - // AND WHEN: GNSS fusion starts _ekf_wrapper.enableGpsFusion(); _sensor_simulator.startGps(); - _sensor_simulator.runSeconds(11); + _sensor_simulator.runSeconds(6); // THEN: the earth mag field is reset to the WMM EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 2); From 6d549811bcd2ea5240a7ec945da9fdca5515a10e Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 2 Jul 2024 09:06:56 +0200 Subject: [PATCH 415/652] fmu v3: disable GYRO_FFT to save flash Signed-off-by: Silvan Fuhrer --- boards/px4/fmu-v3/default.px4board | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index 96b71c0cf653..dd4b5f9621be 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -55,7 +55,7 @@ CONFIG_MODULES_FW_POS_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y -CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_GYRO_FFT=n CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y From 71029689e750c3c5fd5974e52e8e09d3b4435cec Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 11 Jun 2024 13:25:48 +0200 Subject: [PATCH 416/652] battery: add replay file for internal resistance estimation --- src/lib/battery/int_res_est_replay.py | 181 ++++++++++++++++++++++++++ 1 file changed, 181 insertions(+) create mode 100644 src/lib/battery/int_res_est_replay.py diff --git a/src/lib/battery/int_res_est_replay.py b/src/lib/battery/int_res_est_replay.py new file mode 100644 index 000000000000..483e687bd571 --- /dev/null +++ b/src/lib/battery/int_res_est_replay.py @@ -0,0 +1,181 @@ +# Test internal resistance estimator on flight logs +# run with: +# python3 int_res_est_replay.py -f -c <#batteryCells> +# -u <(optional)fullCellVoltage> -e <(optional)emptyCellVoltage> -l <(optional)forgettingFactor> -d <(optional)filterMeasurements> +# Note: Can lead to slightly different results than the online estimation due to the fact that +# the log frequency of the voltage and current are not the same as the online frequency. + +from pyulog import ULog +import matplotlib.pyplot as plt +import numpy as np +import argparse + +def getData(log, topic_name, variable_name, instance=0): + for elem in log.data_list: + if elem.name == topic_name and instance == elem.multi_id: + return elem.data[variable_name] + return np.array([]) + +def us2s(time_us): + return time_us * 1e-6 + +def rls_update(theta, P, x, V, I, lam): + gamma = P @ x / (lam + x.T @ P @ x) + error = V - x.T @ theta + data_cov = x.T @ P @ x + theta_temp = theta + gamma * error + P_temp = (P - gamma @ x.T @ P) / lam + if (abs(np.linalg.norm(P)) < abs(np.linalg.norm(P_temp))): + theta_corr = np.array([V + theta[1] * I, theta[1]]) # Correct OCV estimation + P_corr = P + return theta_corr, P_corr, error, data_cov, 0, 0 + return theta_temp, P_temp, error, data_cov, gamma[0], gamma[1] + +def main(log_name, n_cells, full_cell, empty_cell, lam, filtered): + log = ULog(log_name) + timestamps = us2s(getData(log, 'battery_status', 'timestamp')) + if (filtered): + I = getData(log, 'battery_status', 'current_filtered_a') + V = getData(log, 'battery_status', 'voltage_filtered_v') + else: + I = getData(log, 'battery_status', 'current_a') + V = getData(log, 'battery_status', 'voltage_v') + remaining = getData(log, 'battery_status', 'remaining') + + if not timestamps.size or not I.size or not V.size or not remaining.size: + print("Error: Incomplete data.") + return + + # Initializations + theta = np.array([[V[0] + 0.005 * n_cells * I[0]], [0.005 * n_cells]]) # Initial VOC and R + P = np.diag([1.2 * n_cells, 0.1 * n_cells]) # Initial covariance + error = 0 + + # For plotting + VOC_est = np.zeros_like(I) + R_est = np.zeros_like(I) + error_hist = np.zeros_like(I) + v_est = np.zeros_like(I) + internal_resistance_stable = np.zeros_like(I) + internal_resistance_stable[-1] = 0.005 + cov_norm = np.zeros_like(I) + r_cov = np.zeros_like(I) + ocv_cov = np.zeros_like(I) + mixed_cov = np.zeros_like(I) + data_cov_hist = np.zeros_like(I) + gamma_voc_hist = np.zeros_like(I) + gamma_r_hist = np.zeros_like(I) + + for index in range(len(I)): + # RLS algorithm + x = np.array([[1.0], [-I[index]]]) # Input vector + theta, P, error, data_cov, gamma_voc_hist[index], gamma_r_hist[index] = rls_update(theta, P, x, V[index], I[index], lam) # Run RLS + + # For plotting + VOC_est[index] = theta[0][0] + R_est[index] = theta[1][0] + error_hist[index] = error + v_est[index] = x.T @ theta + cov_norm[index] = abs(np.linalg.norm(P)) + ocv_cov[index] = P[0][0] + r_cov[index] = P[1][1] + mixed_cov[index] = P[0][1] + data_cov_hist[index] = data_cov + internal_resistance_stable[index] = max(R_est[index]/n_cells, 0.001) + + ## Plot data + print("Internal Resistance mean (per cell): ", np.mean(R_est) / n_cells) + + # Summary plot + sumFig = plt.figure("Battery Estimation with RLS") + + volt = plt.subplot(2, 3, 1) + volt.plot(timestamps, V, label='Measured voltage') + volt.plot(timestamps, v_est, label='Estimated voltage') + volt.plot(timestamps, np.array(V) + np.array(internal_resistance_stable) * np.array(I) * n_cells, label='OCV estimate') + ocv_smoothed = np.convolve(np.array(V) + np.array(internal_resistance_stable) * np.array(I) * n_cells, np.ones(30)/30, mode='full')[0:np.size(timestamps)] + ocv_smoothed[0:30] = ocv_smoothed[31] + volt.plot(timestamps, ocv_smoothed, label='OCV estimate smoothed') + volt.plot(timestamps, np.full_like(I, full_cell * n_cells), label='100% SOC') + volt.set_title("Measured Voltage vs Estimated voltage vs Estimated Open circuit voltage [V]") + volt.legend() + + intR = plt.subplot(2, 3, 2) + intR.plot(timestamps, np.array(R_est) * 1000 / n_cells, label='Internal resistance estimate') + intR.set_title("Internal resistance estimate (per cell) [mOhm]") + intR.legend() + + soc = plt.subplot(2, 3, 3) + soc.plot(timestamps, remaining, label='SoC logged') + soc.plot(timestamps, np.interp((np.array(V) + np.array(internal_resistance_stable) * n_cells * np.array(I)) / n_cells, [empty_cell, full_cell], [0, 1]), label='SoC with estimator') + soc.plot(timestamps, np.interp(ocv_smoothed / n_cells, [empty_cell, full_cell], [0, 1]), label='SoC with estimator smoothed') + soc.set_title("State of charge") + soc.legend() + + curr = plt.subplot(2, 3, 4) + curr.plot(timestamps, I, label='Measured current') + curr.set_title("Measured Current [A]") + curr.legend() + + err = plt.subplot(2, 3, 5) + err.plot(timestamps, error_hist, label='$Error$') + err.set_title("Voltage estimation error [V]") + err.legend() + + cov = plt.subplot(2, 3, 6) + cov.plot(timestamps, cov_norm, label = 'Covariance norm') + cov.set_title("Covariance norm") + cov.legend() + + # # SoC estimation plots + # socFig = plt.figure("SoC estimation") + # plt.plot(timestamps, np.interp((np.array(V) + np.array(I) * 0.005 * n_cells) / n_cells, [empty_cell, full_cell], [0, 1]), label='SoC with default $R_{int}$') + # plt.plot(timestamps, remaining, label='SoC logged') + # plt.plot(timestamps, np.interp((np.array(V) + np.array(internal_resistance_stable) * n_cells * np.array(I)) / n_cells, [empty_cell, full_cell], [0, 1]), label='SoC with estimator') + # # plt.plot(timestamps, np.convolve(np.interp((np.array(V) + np.array(internal_resistance_stable) * n_cells * np.array(I)) / n_cells, [empty_cell, full_cell], [0, 1]), np.ones(500)/500, mode='full')[0:np.size(timestamps)], label='SoC with estimator smoothed') + # # plt.plot(timestamps, np.interp((np.array(V) + np.array(I) * 0.0009 * n_cells) / n_cells, [empty_cell, full_cell], [0, 1]), label='SoC with $R_{int}$ measured beforehand') + # # plt.plot(timestamps, np.interp(VOC_est/n_cells, [empty_cell, full_cell], [0, 1]), label='SoC with VOC estimate') + # plt.legend() + + # # Covariance plots + # covFig = plt.figure("Covariance plots") + # covR = plt.subplot(2, 2, 1) + # covR.plot(timestamps, r_cov, label = 'r_cov') + # covR.set_title("Internal resistance covariance") + # covR.legend() + # covVOC = plt.subplot(2, 2, 2) + # covVOC.plot(timestamps, ocv_cov, label = 'ocv_cov') + # covVOC.set_title("Open circuit covariance") + # covVOC.legend() + # covM = plt.subplot(2, 2, 3) + # covM.plot(timestamps, mixed_cov, label = 'mixed_cov') + # covM.set_title("Mixed covariance") + # covM.legend() + # covM = plt.subplot(2, 2, 4) + # covM.plot(timestamps, cov_norm, label = 'cov_norm') + # covM.set_title("Covariance norm") + # covM.legend() + + # # Gain plots + # gainFig = plt.figure("Gain plots") + # gainVoc = plt.subplot(1, 2, 1) + # gainVoc.plot(timestamps, gamma_voc_hist, label = 'gain_voc') + # gainVoc.set_title("Gain VOC") + # gainVoc.legend() + # gainR = plt.subplot(1, 2, 2) + # gainR.plot(timestamps, gamma_r_hist, label = 'gain_r') + # gainR.set_title("Gain R") + # gainR.legend() + + plt.show() + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Estimate battery parameters from ulog file.') + parser.add_argument('-f', type = str, required = True, help = 'Full path to ulog file') + parser.add_argument('-c', type = float, required = True, help = 'Number of cells in battery') + parser.add_argument('-u', type = float, required = False, default = 4.05, help = 'Full cell voltage') + parser.add_argument('-e', type = float, required = False, default = 3.6, help = 'Empty cell voltage') + parser.add_argument('-l', type = float, required = False, default = 0.99, help = 'Forgetting factor') + parser.add_argument('-d', type = bool, required = False, default = False, help = 'Filter measurements') + args = parser.parse_args() + main(args.f, args.c, args.u, args.e, args.l, args.d) From f65653a3911c0a87db68da1e41b60163815d96c2 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Thu, 27 Jun 2024 09:41:56 +0200 Subject: [PATCH 417/652] battery: add internal resistance estimation --- .../init.d/airframes/4601_droneblocks_dexi_5 | 1 - msg/BatteryStatus.msg | 8 ++ src/lib/battery/battery.cpp | 111 +++++++++++++----- src/lib/battery/battery.h | 24 ++-- src/lib/battery/module.yaml | 26 +--- src/lib/matrix/matrix/SquareMatrix.hpp | 1 + src/modules/ekf2/EKF/ekf.h | 1 - 7 files changed, 109 insertions(+), 63 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 index c1484d0b417c..d7f985d1d03e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 @@ -25,7 +25,6 @@ param set-default BAT1_CAPACITY 4000 param set-default BAT1_N_CELLS 6 param set-default BAT1_V_EMPTY 3.3 -param set-default BAT1_V_LOAD_DROP 0.5 param set-default BAT_AVRG_CURRENT 13 # Square quadrotor X PX4 numbering diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index 66fcffa0e68f..b13f721a5aa1 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -76,3 +76,11 @@ float32 design_capacity # The design capacity of the battery uint16 average_time_to_full # The predicted remaining time until the battery reaches full charge, in minutes uint16 over_discharge_count # Number of battery overdischarge float32 nominal_voltage # Nominal voltage of the battery pack + +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate +float32 ocv_estimate # [V] Open circuit voltage estimate +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate +float32 volt_based_soc_estimate # [0, 1] Normalized volt based state of charge estimate +float32 voltage_prediction # [V] Predicted voltage +float32 prediction_error # [V] Prediction error +float32 estimation_covariance_norm # Norm of the covariance matrix diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index 21c4b906f367..213d8fc017e1 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -46,6 +46,7 @@ #include using namespace time_literals; +using namespace matrix; Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us, const uint8_t source) : ModuleParams(parent), @@ -53,10 +54,9 @@ Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us, _source(source) { const float expected_filter_dt = static_cast(sample_interval_us) / 1_s; - _voltage_filter_v.setParameters(expected_filter_dt, 1.f); - _current_filter_a.setParameters(expected_filter_dt, .5f); _current_average_filter_a.setParameters(expected_filter_dt, 50.f); - _throttle_filter.setParameters(expected_filter_dt, 1.f); + _ocv_filter_v.setParameters(expected_filter_dt, 1.f); + _cell_voltage_filter_v.setParameters(expected_filter_dt, 1.f); if (index > 9 || index < 1) { PX4_ERR("Battery index must be between 1 and 9 (inclusive). Received %d. Defaulting to 1.", index); @@ -81,9 +81,6 @@ Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us, snprintf(param_name, sizeof(param_name), "BAT%d_CAPACITY", _index); _param_handles.capacity = param_find(param_name); - snprintf(param_name, sizeof(param_name), "BAT%d_V_LOAD_DROP", _index); - _param_handles.v_load_drop = param_find(param_name); - snprintf(param_name, sizeof(param_name), "BAT%d_R_INTERNAL", _index); _param_handles.r_internal = param_find(param_name); @@ -97,29 +94,36 @@ Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us, _param_handles.bat_avrg_current = param_find("BAT_AVRG_CURRENT"); updateParams(); + + // Internal resistance estimation initializations + _RLS_est(0) = OCV_DEFAULT * _params.n_cells; + _RLS_est(1) = R_DEFAULT * _params.n_cells; + _estimation_covariance(0, 0) = OCV_COVARIANCE * _params.n_cells; + _estimation_covariance(0, 1) = 0.f; + _estimation_covariance(1, 0) = 0.f; + _estimation_covariance(1, 1) = R_COVARIANCE * _params.n_cells; + _estimation_covariance_norm = sqrtf(powf(_estimation_covariance(0, 0), 2.f) + 2.f * powf(_estimation_covariance(1, 0), + 2.f) + powf(_estimation_covariance(1, 1), 2.f)); } void Battery::updateVoltage(const float voltage_v) { _voltage_v = voltage_v; - _voltage_filter_v.update(voltage_v); } void Battery::updateCurrent(const float current_a) { _current_a = current_a; - _current_filter_a.update(current_a); } void Battery::updateBatteryStatus(const hrt_abstime ×tamp) { if (!_battery_initialized) { - _voltage_filter_v.reset(_voltage_v); - _current_filter_a.reset(_current_a); + resetInternalResistanceEstimation(_voltage_v, _current_a); } // Require minimum voltage otherwise override connected status - if (_voltage_filter_v.getState() < LITHIUM_BATTERY_RECOGNITION_VOLTAGE) { + if (_voltage_v < LITHIUM_BATTERY_RECOGNITION_VOLTAGE) { _connected = false; } @@ -132,7 +136,7 @@ void Battery::updateBatteryStatus(const hrt_abstime ×tamp) sumDischarged(timestamp, _current_a); _state_of_charge_volt_based = - calculateStateOfChargeVoltageBased(_voltage_filter_v.getState(), _current_filter_a.getState()); + calculateStateOfChargeVoltageBased(_voltage_v, _current_a); if (!_external_state_of_charge) { estimateStateOfCharge(); @@ -149,9 +153,7 @@ battery_status_s Battery::getBatteryStatus() { battery_status_s battery_status{}; battery_status.voltage_v = _voltage_v; - battery_status.voltage_filtered_v = _voltage_filter_v.getState(); battery_status.current_a = _current_a; - battery_status.current_filtered_a = _current_filter_a.getState(); battery_status.current_average_a = _current_average_filter_a.getState(); battery_status.discharged_mah = _discharged_mah; battery_status.remaining = _state_of_charge; @@ -167,6 +169,14 @@ battery_status_s Battery::getBatteryStatus() battery_status.warning = _warning; battery_status.timestamp = hrt_absolute_time(); battery_status.faults = determineFaults(); + battery_status.internal_resistance_estimate = _internal_resistance_estimate; + battery_status.ocv_estimate = _voltage_v + _internal_resistance_estimate * _params.n_cells * _current_a; + battery_status.ocv_estimate_filtered = _ocv_filter_v.getState(); + battery_status.volt_based_soc_estimate = math::interpolate(_ocv_filter_v.getState() / _params.n_cells, + _params.v_empty, _params.v_charged, 0.f, 1.f); + battery_status.voltage_prediction = _voltage_prediction; + battery_status.prediction_error = _prediction_error; + battery_status.estimation_covariance_norm = _estimation_covariance_norm; return battery_status; } @@ -213,27 +223,69 @@ float Battery::calculateStateOfChargeVoltageBased(const float voltage_v, const f // remaining battery capacity based on voltage float cell_voltage = voltage_v / _params.n_cells; - // correct battery voltage locally for load drop to avoid estimation fluctuations - if (_params.r_internal >= 0.f && current_a > FLT_EPSILON) { - cell_voltage += _params.r_internal * current_a; - - } else { - vehicle_thrust_setpoint_s vehicle_thrust_setpoint{}; - _vehicle_thrust_setpoint_0_sub.copy(&vehicle_thrust_setpoint); - const matrix::Vector3f thrust_setpoint = matrix::Vector3f(vehicle_thrust_setpoint.xyz); - const float throttle = thrust_setpoint.length(); + // correct battery voltage locally for load drop according to internal resistance and current + if (current_a > FLT_EPSILON) { + updateInternalResistanceEstimation(voltage_v, current_a); - _throttle_filter.update(throttle); + if (_params.r_internal >= 0.f) { // Use user specified internal resistance value + cell_voltage += _params.r_internal * current_a; - if (!_battery_initialized) { - _throttle_filter.reset(throttle); + } else { // Use estimated internal resistance value + cell_voltage += _internal_resistance_estimate * current_a; } - // assume linear relation between throttle and voltage drop - cell_voltage += throttle * _params.v_load_drop; } - return math::interpolate(cell_voltage, _params.v_empty, _params.v_charged, 0.f, 1.f); + _cell_voltage_filter_v.update(cell_voltage); + return math::interpolate(_cell_voltage_filter_v.getState(), _params.v_empty, _params.v_charged, 0.f, 1.f); +} + +void Battery::updateInternalResistanceEstimation(const float voltage_v, const float current_a) +{ + Vector2f x{1, -current_a}; + _voltage_prediction = (x.transpose() * _RLS_est)(0, 0); + _prediction_error = voltage_v - _voltage_prediction; + const Vector2f gamma = _estimation_covariance * x / (LAMBDA + (x.transpose() * _estimation_covariance * x)(0, 0)); + const Vector2f RSL_est_temp = _RLS_est + gamma * _prediction_error; + const Matrix2f estimation_covariance_temp = (_estimation_covariance + - Matrix(gamma) * (x.transpose() * _estimation_covariance)) / LAMBDA; + const float estimation_covariance_temp_norm = + sqrtf(powf(estimation_covariance_temp(0, 0), 2.f) + + 2.f * powf(estimation_covariance_temp(1, 0), 2.f) + + powf(estimation_covariance_temp(1, 1), 2.f)); + + if (estimation_covariance_temp_norm < _estimation_covariance_norm) { // Only update if estimation improves + _RLS_est = RSL_est_temp; + _estimation_covariance = estimation_covariance_temp; + _estimation_covariance_norm = estimation_covariance_temp_norm; + _internal_resistance_estimate = + math::max(_RLS_est(1) / _params.n_cells, 0.f); // Only use positive values + + } else { // Update OCV estimate with IR estimate + _RLS_est(0) = voltage_v + _RLS_est(1) * current_a; + } + + _ocv_filter_v.update(voltage_v + _internal_resistance_estimate * _params.n_cells * current_a); +} + +void Battery::resetInternalResistanceEstimation(const float voltage_v, const float current_a) +{ + _RLS_est(0) = voltage_v; + _RLS_est(1) = R_DEFAULT * _params.n_cells; + _estimation_covariance.setZero(); + _estimation_covariance(0, 0) = OCV_COVARIANCE * _params.n_cells; + _estimation_covariance(1, 1) = R_COVARIANCE * _params.n_cells; + _estimation_covariance_norm = sqrtf(powf(_estimation_covariance(0, 0), 2.f) + 2.f * powf(_estimation_covariance(1, 0), + 2.f) + powf(_estimation_covariance(1, 1), 2.f)); + _internal_resistance_estimate = R_DEFAULT; + _ocv_filter_v.reset(voltage_v + _internal_resistance_estimate * _params.n_cells * current_a); + + if (_params.r_internal >= 0.f) { // Use user specified internal resistance value + _cell_voltage_filter_v.reset(voltage_v / _params.n_cells + _params.r_internal * current_a); + + } else { // Use estimated internal resistance value + _cell_voltage_filter_v.reset(voltage_v / _params.n_cells + _internal_resistance_estimate * current_a); + } } void Battery::estimateStateOfCharge() @@ -354,7 +406,6 @@ void Battery::updateParams() param_get(_param_handles.v_charged, &_params.v_charged); param_get(_param_handles.n_cells, &_params.n_cells); param_get(_param_handles.capacity, &_params.capacity); - param_get(_param_handles.v_load_drop, &_params.v_load_drop); param_get(_param_handles.r_internal, &_params.r_internal); param_get(_param_handles.source, &_params.source); param_get(_param_handles.low_thr, &_params.low_thr); diff --git a/src/lib/battery/battery.h b/src/lib/battery/battery.h index 91edbe058053..9d24b7bd4448 100644 --- a/src/lib/battery/battery.h +++ b/src/lib/battery/battery.h @@ -58,7 +58,6 @@ #include #include #include -#include /** * BatteryBase is a base class for any type of battery. @@ -118,7 +117,6 @@ class Battery : public ModuleParams param_t v_charged; param_t n_cells; param_t capacity; - param_t v_load_drop; param_t r_internal; param_t low_thr; param_t crit_thr; @@ -132,7 +130,6 @@ class Battery : public ModuleParams float v_charged; int32_t n_cells; float capacity; - float v_load_drop; float r_internal; float low_thr; float crit_thr; @@ -155,7 +152,6 @@ class Battery : public ModuleParams void computeScale(); float computeRemainingTime(float current_a); - uORB::Subscription _vehicle_thrust_setpoint_0_sub{ORB_ID(vehicle_thrust_setpoint)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; uORB::SubscriptionData _flight_phase_estimation_sub{ORB_ID(flight_phase_estimation)}; uORB::PublicationMulti _battery_status_pub{ORB_ID(battery_status)}; @@ -167,12 +163,11 @@ class Battery : public ModuleParams uint8_t _priority{0}; bool _battery_initialized{false}; float _voltage_v{0.f}; - AlphaFilter _voltage_filter_v; + AlphaFilter _ocv_filter_v; + AlphaFilter _cell_voltage_filter_v; float _current_a{-1}; - AlphaFilter _current_filter_a; AlphaFilter _current_average_filter_a; ///< averaging filter for current. For FW, it is the current in level flight. - AlphaFilter _throttle_filter; float _discharged_mah{0.f}; float _discharged_mah_loop{0.f}; float _state_of_charge_volt_based{-1.f}; // [0,1] @@ -183,4 +178,19 @@ class Battery : public ModuleParams bool _armed{false}; bool _vehicle_status_is_fw{false}; hrt_abstime _last_unconnected_timestamp{0}; + + // Internal Resistance estimation + void updateInternalResistanceEstimation(const float voltage_v, const float current_a); + void resetInternalResistanceEstimation(const float voltage_v, const float current_a); + matrix::Vector2f _RLS_est; // [Open circuit voltage estimate [V], Total internal resistance estimate [Ohm]]^T + matrix::Matrix2f _estimation_covariance; + float _estimation_covariance_norm{0.f}; + float _internal_resistance_estimate{0.005f}; // [Ohm] Per cell estimate of the internal resistance + float _voltage_prediction{0.f}; // [V] Predicted voltage of the estimator + float _prediction_error{0.f}; // [V] Error between the predicted and measured voltage + static constexpr float LAMBDA = 0.95f; // [0, 1] Forgetting factor (Tuning parameter for the RLS algorithm) + static constexpr float R_DEFAULT = 0.005f; // [Ohm] Initial per cell estimate of the internal resistance + static constexpr float OCV_DEFAULT = 4.2f; // [V] Initial per cell estimate of the open circuit voltage + static constexpr float R_COVARIANCE = 0.1f; // Initial per cell covariance of the internal resistance + static constexpr float OCV_COVARIANCE = 1.5f; // Initial per cell covariance of the open circuit voltage }; diff --git a/src/lib/battery/module.yaml b/src/lib/battery/module.yaml index 27723a7a4b63..1b6ee5802fb4 100644 --- a/src/lib/battery/module.yaml +++ b/src/lib/battery/module.yaml @@ -39,33 +39,11 @@ parameters: instance_start: 1 default: [4.05, 4.05, 4.05] - BAT${i}_V_LOAD_DROP: - description: - short: Voltage drop per cell on full throttle - long: | - This implicitly defines the internal resistance - to maximum current ratio for the battery and assumes linearity. - A good value to use is the difference between the - 5C and 20-25C load. Not used if BAT${i}_R_INTERNAL is - set. - - type: float - unit: V - min: 0.07 - max: 0.5 - decimal: 2 - increment: 0.01 - reboot_required: true - num_instances: *max_num_config_instances - instance_start: 1 - default: [0.1, 0.1, 0.1] - BAT${i}_R_INTERNAL: description: short: Explicitly defines the per cell internal resistance for battery ${i} long: | - If non-negative, then this will be used in place of - BAT${i}_V_LOAD_DROP for all calculations. + If non-negative, then this will be used instead of the online estimated internal resistance. type: float unit: Ohm @@ -76,7 +54,7 @@ parameters: reboot_required: true num_instances: *max_num_config_instances instance_start: 1 - default: [0.005, 0.005, 0.005] + default: [-1.0, -1.0, -1.0] BAT${i}_N_CELLS: description: diff --git a/src/lib/matrix/matrix/SquareMatrix.hpp b/src/lib/matrix/matrix/SquareMatrix.hpp index 76cb9a3ebc47..0cd20bc5bc4e 100644 --- a/src/lib/matrix/matrix/SquareMatrix.hpp +++ b/src/lib/matrix/matrix/SquareMatrix.hpp @@ -618,6 +618,7 @@ SquareMatrix choleskyInv(const SquareMatrix &A) return L_inv.T() * L_inv; } +using Matrix2f = SquareMatrix; using Matrix3f = SquareMatrix; using Matrix3d = SquareMatrix; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 45917b6348f9..2a23d1d283b4 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -73,7 +73,6 @@ class Ekf final : public EstimatorInterface public: typedef matrix::Vector VectorState; typedef matrix::SquareMatrix SquareMatrixState; - typedef matrix::SquareMatrix Matrix2f; Ekf() { From e03e0261a1a0c82f545e66a1e3795956c886db71 Mon Sep 17 00:00:00 2001 From: zhangteng0526 <49060609+zhangteng0526@users.noreply.github.com> Date: Wed, 3 Jul 2024 10:58:40 +0800 Subject: [PATCH 418/652] Fix buffer overflow in mavlink_receive.cpp --- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 35e2879c6db7..f8e12d51cc6d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1818,7 +1818,7 @@ MavlinkReceiver::handle_message_serial_control(mavlink_message_t *msg) if (shell) { // we ignore the timeout, EXCLUSIVE & BLOCKING flags of the SERIAL_CONTROL message - if (serial_control_mavlink.count > 0) { + if (serial_control_mavlink.count > 0 && serial_control_mavlink.count <= sizeof(serial_control_mavlink.data)) { shell->setTargetID(msg->sysid, msg->compid); shell->write(serial_control_mavlink.data, serial_control_mavlink.count); } From c2ae6a7e24c70e5d3989343127a7b14839f71a01 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 3 Jul 2024 14:47:16 +0200 Subject: [PATCH 419/652] BatteryStatus: remove current_filtered_a Signed-off-by: Silvan Fuhrer --- msg/BatteryStatus.msg | 1 - src/drivers/batt_smbus/batt_smbus.cpp | 1 - .../cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp | 1 - src/drivers/rc/crsf_rc/CrsfRc.cpp | 2 +- src/drivers/rc_input/crsf_telemetry.cpp | 2 +- src/drivers/rc_input/ghst_telemetry.cpp | 2 +- src/drivers/smart_battery/batmon/batmon.cpp | 1 - src/drivers/tattu_can/TattuCan.cpp | 1 - src/drivers/uavcan/sensors/battery.cpp | 1 - src/lib/battery/int_res_est_replay.py | 13 ++++--------- src/lib/drivers/smbus_sbs/SBS.hpp | 1 - src/modules/mavlink/mavlink_receiver.cpp | 1 - src/modules/mavlink/streams/BATTERY_STATUS.hpp | 2 +- src/modules/mavlink/streams/SYS_STATUS.hpp | 2 +- 14 files changed, 9 insertions(+), 22 deletions(-) diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index b13f721a5aa1..8b22326d38d8 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -3,7 +3,6 @@ bool connected # Whether or not a battery is connected, based on a voltage th float32 voltage_v # Battery voltage in volts, 0 if unknown float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown float32 current_a # Battery current in amperes, -1 if unknown -float32 current_filtered_a # Battery current in amperes, filtered, 0 if unknown float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown float32 discharged_mah # Discharged amount in mAh, -1 if unknown float32 remaining # From 1 to 0, -1 if unknown diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index 913bbbe7b82a..7be94866d064 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -122,7 +122,6 @@ void BATT_SMBUS::RunImpl() ret |= _interface->read_word(BATT_SMBUS_CURRENT, result); new_report.current_a = (-1.0f * ((float)(*(int16_t *)&result)) / 1000.0f) * _c_mult; - new_report.current_filtered_a = new_report.current_a; // Read average current. ret |= _interface->read_word(BATT_SMBUS_AVERAGE_CURRENT, result); diff --git a/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp b/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp index 4a4d316ee09c..09c306848eb5 100644 --- a/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp +++ b/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp @@ -77,7 +77,6 @@ class UavcanLegacyBatteryInfoSubscriber : public UavcanDynamicPortSubscriber battery_status_s bat_status {0}; bat_status.timestamp = hrt_absolute_time(); bat_status.voltage_filtered_v = bat_info.voltage; - bat_status.current_filtered_a = bat_info.current; bat_status.current_average_a = bat_info.average_power_10sec; bat_status.remaining = bat_info.state_of_charge_pct / 100.0f; bat_status.scale = -1; diff --git a/src/drivers/rc/crsf_rc/CrsfRc.cpp b/src/drivers/rc/crsf_rc/CrsfRc.cpp index 119e24b07ca4..930b7f138414 100644 --- a/src/drivers/rc/crsf_rc/CrsfRc.cpp +++ b/src/drivers/rc/crsf_rc/CrsfRc.cpp @@ -225,7 +225,7 @@ void CrsfRc::Run() if (_battery_status_sub.update(&battery_status)) { uint16_t voltage = battery_status.voltage_filtered_v * 10; - uint16_t current = battery_status.current_filtered_a * 10; + uint16_t current = battery_status.current_a * 10; int fuel = battery_status.discharged_mah; uint8_t remaining = battery_status.remaining * 100; this->SendTelemetryBattery(voltage, current, fuel, remaining); diff --git a/src/drivers/rc_input/crsf_telemetry.cpp b/src/drivers/rc_input/crsf_telemetry.cpp index 720437c82301..aa4c5ef85d0b 100644 --- a/src/drivers/rc_input/crsf_telemetry.cpp +++ b/src/drivers/rc_input/crsf_telemetry.cpp @@ -82,7 +82,7 @@ bool CRSFTelemetry::send_battery() } uint16_t voltage = battery_status.voltage_filtered_v * 10; - uint16_t current = battery_status.current_filtered_a * 10; + uint16_t current = battery_status.current_a * 10; int fuel = battery_status.discharged_mah; uint8_t remaining = battery_status.remaining * 100; return crsf_send_telemetry_battery(_uart_fd, voltage, current, fuel, remaining); diff --git a/src/drivers/rc_input/ghst_telemetry.cpp b/src/drivers/rc_input/ghst_telemetry.cpp index 6edd0de598e6..910a519a502f 100644 --- a/src/drivers/rc_input/ghst_telemetry.cpp +++ b/src/drivers/rc_input/ghst_telemetry.cpp @@ -91,7 +91,7 @@ bool GHSTTelemetry::send_battery_status() if (_battery_status_sub.update(&battery_status)) { voltage_in_10mV = battery_status.voltage_filtered_v * FACTOR_VOLTS_TO_10MV; - current_in_10mA = battery_status.current_filtered_a * FACTOR_AMPS_TO_10MA; + current_in_10mA = battery_status.current_a * FACTOR_AMPS_TO_10MA; fuel_in_10mAh = battery_status.discharged_mah * FACTOR_MAH_TO_10MAH; success = ghst_send_telemetry_battery_status(_uart_fd, static_cast(voltage_in_10mV), diff --git a/src/drivers/smart_battery/batmon/batmon.cpp b/src/drivers/smart_battery/batmon/batmon.cpp index 8cfe3031ca43..6c6c484948d8 100644 --- a/src/drivers/smart_battery/batmon/batmon.cpp +++ b/src/drivers/smart_battery/batmon/batmon.cpp @@ -152,7 +152,6 @@ void Batmon::RunImpl() ret |= _interface->read_word(BATT_SMBUS_CURRENT, result); new_report.current_a = (-1.0f * ((float)(*(int16_t *)&result)) / 1000.0f); - new_report.current_filtered_a = new_report.current_a; // Read average current. ret |= _interface->read_word(BATT_SMBUS_AVERAGE_CURRENT, result); diff --git a/src/drivers/tattu_can/TattuCan.cpp b/src/drivers/tattu_can/TattuCan.cpp index 746a24137225..ed1603c86921 100644 --- a/src/drivers/tattu_can/TattuCan.cpp +++ b/src/drivers/tattu_can/TattuCan.cpp @@ -117,7 +117,6 @@ void TattuCan::Run() battery_status.voltage_v = static_cast(tattu_message.voltage) / 1000.0f; battery_status.voltage_filtered_v = static_cast(tattu_message.voltage) / 1000.0f; battery_status.current_a = static_cast(tattu_message.current) / 1000.0f; - battery_status.current_filtered_a = static_cast(tattu_message.current) / 1000.0f; battery_status.remaining = static_cast(tattu_message.remaining_percent) / 100.0f; battery_status.temperature = static_cast(tattu_message.temperature); battery_status.capacity = tattu_message.standard_capacity; diff --git a/src/drivers/uavcan/sensors/battery.cpp b/src/drivers/uavcan/sensors/battery.cpp index ab09c327407c..eecaec889667 100644 --- a/src/drivers/uavcan/sensors/battery.cpp +++ b/src/drivers/uavcan/sensors/battery.cpp @@ -106,7 +106,6 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure::populate_smbus_data(battery_status_s &data) ret |= _interface->read_word(BATT_SMBUS_CURRENT, result); data.current_a = (-1.0f * ((float)(*(int16_t *)&result)) * 0.001f); - data.current_filtered_a = data.current_a; // Read remaining capacity. ret |= _interface->read_word(BATT_SMBUS_RELATIVE_SOC, result); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index f8e12d51cc6d..cdd73df693cb 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1772,7 +1772,6 @@ MavlinkReceiver::handle_message_battery_status(mavlink_message_t *msg) battery_status.voltage_v = voltage_sum; battery_status.voltage_filtered_v = voltage_sum; battery_status.current_a = (float)(battery_mavlink.current_battery) / 100.0f; - battery_status.current_filtered_a = battery_status.current_a; battery_status.remaining = (float)battery_mavlink.battery_remaining / 100.0f; battery_status.discharged_mah = (float)battery_mavlink.current_consumed; battery_status.cell_count = cell_count; diff --git a/src/modules/mavlink/streams/BATTERY_STATUS.hpp b/src/modules/mavlink/streams/BATTERY_STATUS.hpp index 73068f0de360..0ab03d6d950d 100644 --- a/src/modules/mavlink/streams/BATTERY_STATUS.hpp +++ b/src/modules/mavlink/streams/BATTERY_STATUS.hpp @@ -74,7 +74,7 @@ class MavlinkStreamBatteryStatus : public MavlinkStream bat_msg.type = MAV_BATTERY_TYPE_LIPO; bat_msg.current_consumed = (battery_status.connected) ? battery_status.discharged_mah : -1; bat_msg.energy_consumed = -1; - bat_msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100 : -1; + bat_msg.current_battery = (battery_status.connected) ? battery_status.current_a * 100 : -1; bat_msg.battery_remaining = (battery_status.connected) ? roundf(battery_status.remaining * 100.f) : -1; // MAVLink extension: 0 is unsupported, in uORB it's NAN bat_msg.time_remaining = (battery_status.connected && (PX4_ISFINITE(battery_status.time_remaining_s))) ? diff --git a/src/modules/mavlink/streams/SYS_STATUS.hpp b/src/modules/mavlink/streams/SYS_STATUS.hpp index 9a2b2cb691ec..fc775a34d65b 100644 --- a/src/modules/mavlink/streams/SYS_STATUS.hpp +++ b/src/modules/mavlink/streams/SYS_STATUS.hpp @@ -167,7 +167,7 @@ class MavlinkStreamSysStatus : public MavlinkStream if (lowest_battery.connected) { msg.voltage_battery = lowest_battery.voltage_filtered_v * 1000.0f; - msg.current_battery = lowest_battery.current_filtered_a * 100.0f; + msg.current_battery = lowest_battery.current_a * 100.0f; msg.battery_remaining = ceilf(lowest_battery.remaining * 100.0f); } else { From 33701aa3d593283182dee92fa989aabedc9cdda2 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 3 Jul 2024 15:00:02 +0200 Subject: [PATCH 420/652] BatteryStatus: remove voltage_filtered_a Signed-off-by: Silvan Fuhrer --- boards/modalai/voxl2-slpi/src/drivers/dsp_hitl/dsp_hitl.cpp | 1 - msg/BatteryStatus.msg | 1 - src/drivers/batt_smbus/batt_smbus.cpp | 1 - src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp | 1 - src/drivers/osd/atxxxx/atxxxx.cpp | 4 ++-- src/drivers/osd/atxxxx/atxxxx.h | 2 +- src/drivers/rc/crsf_rc/CrsfRc.cpp | 2 +- src/drivers/rc_input/crsf_telemetry.cpp | 2 +- src/drivers/rc_input/ghst_telemetry.cpp | 2 +- src/drivers/smart_battery/batmon/batmon.cpp | 1 - src/drivers/tattu_can/TattuCan.cpp | 1 - src/drivers/uavcan/sensors/battery.cpp | 1 - src/lib/drivers/smbus_sbs/SBS.hpp | 1 - src/modules/mavlink/mavlink_receiver.cpp | 3 --- src/modules/mavlink/streams/BATTERY_STATUS.hpp | 4 ++-- src/modules/mavlink/streams/SYS_STATUS.hpp | 2 +- 16 files changed, 9 insertions(+), 20 deletions(-) diff --git a/boards/modalai/voxl2-slpi/src/drivers/dsp_hitl/dsp_hitl.cpp b/boards/modalai/voxl2-slpi/src/drivers/dsp_hitl/dsp_hitl.cpp index b26f56508216..380ebc04d004 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/dsp_hitl/dsp_hitl.cpp +++ b/boards/modalai/voxl2-slpi/src/drivers/dsp_hitl/dsp_hitl.cpp @@ -1148,7 +1148,6 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg) hil_battery_status.timestamp = gyro_accel_time; hil_battery_status.voltage_v = 16.0f; - hil_battery_status.voltage_filtered_v = 16.0f; hil_battery_status.current_a = 10.0f; hil_battery_status.discharged_mah = -1.0f; hil_battery_status.connected = true; diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index 8b22326d38d8..d0beda6dbc9d 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -1,7 +1,6 @@ uint64 timestamp # time since system start (microseconds) bool connected # Whether or not a battery is connected, based on a voltage threshold float32 voltage_v # Battery voltage in volts, 0 if unknown -float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown float32 current_a # Battery current in amperes, -1 if unknown float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown float32 discharged_mah # Discharged amount in mAh, -1 if unknown diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index 7be94866d064..194b88fa94c0 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -116,7 +116,6 @@ void BATT_SMBUS::RunImpl() // Convert millivolts to volts. new_report.voltage_v = ((float)result) / 1000.0f; - new_report.voltage_filtered_v = new_report.voltage_v; // Read current. ret |= _interface->read_word(BATT_SMBUS_CURRENT, result); diff --git a/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp b/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp index 09c306848eb5..718a70844fda 100644 --- a/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp +++ b/src/drivers/cyphal/Subscribers/legacy/LegacyBatteryInfo.hpp @@ -76,7 +76,6 @@ class UavcanLegacyBatteryInfoSubscriber : public UavcanDynamicPortSubscriber battery_status_s bat_status {0}; bat_status.timestamp = hrt_absolute_time(); - bat_status.voltage_filtered_v = bat_info.voltage; bat_status.current_average_a = bat_info.average_power_10sec; bat_status.remaining = bat_info.state_of_charge_pct / 100.0f; bat_status.scale = -1; diff --git a/src/drivers/osd/atxxxx/atxxxx.cpp b/src/drivers/osd/atxxxx/atxxxx.cpp index b504b943c79a..a5acabd3919d 100644 --- a/src/drivers/osd/atxxxx/atxxxx.cpp +++ b/src/drivers/osd/atxxxx/atxxxx.cpp @@ -241,7 +241,7 @@ OSDatxxxx::add_battery_info(uint8_t pos_x, uint8_t pos_y) int ret = PX4_OK; // TODO: show battery symbol based on battery fill level - snprintf(buf, sizeof(buf), "%c%5.2f", OSD_SYMBOL_BATT_3, (double)_battery_voltage_filtered_v); + snprintf(buf, sizeof(buf), "%c%5.2f", OSD_SYMBOL_BATT_3, (double)_battery_voltage_v); buf[sizeof(buf) - 1] = '\0'; for (int i = 0; buf[i] != '\0'; i++) { @@ -330,7 +330,7 @@ OSDatxxxx::update_topics() _battery_sub.copy(&battery); if (battery.connected) { - _battery_voltage_filtered_v = battery.voltage_filtered_v; + _battery_voltage_v = battery.voltage_v; _battery_discharge_mah = battery.discharged_mah; _battery_valid = true; diff --git a/src/drivers/osd/atxxxx/atxxxx.h b/src/drivers/osd/atxxxx/atxxxx.h index e821e65deb32..10685eec9b98 100644 --- a/src/drivers/osd/atxxxx/atxxxx.h +++ b/src/drivers/osd/atxxxx/atxxxx.h @@ -111,7 +111,7 @@ class OSDatxxxx : public device::SPI, public ModuleParams, public I2CSPIDriverread_word(BATT_SMBUS_CURRENT, result); diff --git a/src/drivers/tattu_can/TattuCan.cpp b/src/drivers/tattu_can/TattuCan.cpp index ed1603c86921..1f414c090796 100644 --- a/src/drivers/tattu_can/TattuCan.cpp +++ b/src/drivers/tattu_can/TattuCan.cpp @@ -115,7 +115,6 @@ void TattuCan::Run() battery_status.state_of_health = static_cast(tattu_message.health_status); battery_status.voltage_v = static_cast(tattu_message.voltage) / 1000.0f; - battery_status.voltage_filtered_v = static_cast(tattu_message.voltage) / 1000.0f; battery_status.current_a = static_cast(tattu_message.current) / 1000.0f; battery_status.remaining = static_cast(tattu_message.remaining_percent) / 100.0f; battery_status.temperature = static_cast(tattu_message.temperature); diff --git a/src/drivers/uavcan/sensors/battery.cpp b/src/drivers/uavcan/sensors/battery.cpp index eecaec889667..77698cff16d1 100644 --- a/src/drivers/uavcan/sensors/battery.cpp +++ b/src/drivers/uavcan/sensors/battery.cpp @@ -104,7 +104,6 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure::populate_smbus_data(battery_status_s &data) // Convert millivolts to volts. data.voltage_v = ((float)result) * 0.001f; - data.voltage_filtered_v = data.voltage_v; // Read current. ret |= _interface->read_word(BATT_SMBUS_CURRENT, result); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index cdd73df693cb..06fb97c8a65f 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1770,7 +1770,6 @@ MavlinkReceiver::handle_message_battery_status(mavlink_message_t *msg) } battery_status.voltage_v = voltage_sum; - battery_status.voltage_filtered_v = voltage_sum; battery_status.current_a = (float)(battery_mavlink.current_battery) / 100.0f; battery_status.remaining = (float)battery_mavlink.battery_remaining / 100.0f; battery_status.discharged_mah = (float)battery_mavlink.current_consumed; @@ -2372,7 +2371,6 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) hil_battery_status.timestamp = timestamp; hil_battery_status.voltage_v = 16.0f; - hil_battery_status.voltage_filtered_v = 16.0f; hil_battery_status.current_a = 10.0f; hil_battery_status.discharged_mah = -1.0f; hil_battery_status.connected = true; @@ -2726,7 +2724,6 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) { battery_status_s hil_battery_status{}; hil_battery_status.voltage_v = 11.1f; - hil_battery_status.voltage_filtered_v = 11.1f; hil_battery_status.current_a = 10.0f; hil_battery_status.discharged_mah = -1.0f; hil_battery_status.timestamp = hrt_absolute_time(); diff --git a/src/modules/mavlink/streams/BATTERY_STATUS.hpp b/src/modules/mavlink/streams/BATTERY_STATUS.hpp index 0ab03d6d950d..c3d15054ac2f 100644 --- a/src/modules/mavlink/streams/BATTERY_STATUS.hpp +++ b/src/modules/mavlink/streams/BATTERY_STATUS.hpp @@ -161,10 +161,10 @@ class MavlinkStreamBatteryStatus : public MavlinkStream // If it doesn't fit, we have to split it into UINT16-1 chunks and the remaining // voltage for the subsequent field. // This won't work for voltages of more than 655 volts. - const int num_fields_required = static_cast(battery_status.voltage_filtered_v * 1000.f) / (UINT16_MAX - 1) + 1; + const int num_fields_required = static_cast(battery_status.voltage_v * 1000.f) / (UINT16_MAX - 1) + 1; if (num_fields_required <= mavlink_cell_slots) { - float remaining_voltage = battery_status.voltage_filtered_v * 1000.f; + float remaining_voltage = battery_status.voltage_v * 1000.f; for (int i = 0; i < num_fields_required - 1; ++i) { bat_msg.voltages[i] = UINT16_MAX - 1; diff --git a/src/modules/mavlink/streams/SYS_STATUS.hpp b/src/modules/mavlink/streams/SYS_STATUS.hpp index fc775a34d65b..272947b1ad77 100644 --- a/src/modules/mavlink/streams/SYS_STATUS.hpp +++ b/src/modules/mavlink/streams/SYS_STATUS.hpp @@ -166,7 +166,7 @@ class MavlinkStreamSysStatus : public MavlinkStream const battery_status_s &lowest_battery = battery_status[lowest_battery_index]; if (lowest_battery.connected) { - msg.voltage_battery = lowest_battery.voltage_filtered_v * 1000.0f; + msg.voltage_battery = lowest_battery.voltage_v * 1000.0f; msg.current_battery = lowest_battery.current_a * 100.0f; msg.battery_remaining = ceilf(lowest_battery.remaining * 100.0f); From 522a25a410c47f38a4493f8a0ed6534437e51e71 Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Wed, 12 Jun 2024 14:41:08 +0200 Subject: [PATCH 421/652] gnss(septentrio): first batch of bugfixes after internal testing Internal testing revealed usability issues. Those and some other problems are fixed. --- src/drivers/gnss/septentrio/module.h | 2 +- src/drivers/gnss/septentrio/sbf/messages.h | 4 +- src/drivers/gnss/septentrio/septentrio.cpp | 493 ++++++++++++--------- src/drivers/gnss/septentrio/septentrio.h | 66 ++- 4 files changed, 332 insertions(+), 233 deletions(-) diff --git a/src/drivers/gnss/septentrio/module.h b/src/drivers/gnss/septentrio/module.h index 28b52240b643..c935c1263e44 100644 --- a/src/drivers/gnss/septentrio/module.h +++ b/src/drivers/gnss/septentrio/module.h @@ -56,7 +56,7 @@ #endif #ifdef SEP_LOG_ERROR -#define SEP_ERR(...) {PX4_WARN(__VA_ARGS__);} +#define SEP_ERR(...) {PX4_ERR(__VA_ARGS__);} #else #define SEP_ERR(...) {} #endif diff --git a/src/drivers/gnss/septentrio/sbf/messages.h b/src/drivers/gnss/septentrio/sbf/messages.h index e51a6f469b31..487a40054c64 100644 --- a/src/drivers/gnss/septentrio/sbf/messages.h +++ b/src/drivers/gnss/septentrio/sbf/messages.h @@ -60,8 +60,8 @@ constexpr uint32_t k_dnu_u4_value {4294967295}; constexpr uint32_t k_dnu_u4_bitfield {0}; constexpr uint16_t k_dnu_u2_value {65535}; constexpr uint16_t k_dnu_u2_bitfield {0}; -constexpr float k_dnu_f4_value {-2 * 10000000000}; -constexpr double k_dnu_f8_value {-2 * 10000000000}; +constexpr float k_dnu_f4_value {-2.0f * 10000000000.0f}; +constexpr double k_dnu_f8_value {-2.0 * 10000000000.0}; /// Maximum size of all expected messages. /// This needs to be bigger than the maximum size of all declared SBF blocks so that `memcpy()` can safely copy from the decoding buffer using this value into messages. diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index ad99ed6342c8..838caea2947c 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -55,6 +55,7 @@ #include #include #include +#include #include #include @@ -86,6 +87,11 @@ constexpr int k_max_receiver_read_timeout = 50; */ constexpr size_t k_min_receiver_read_bytes = 32; +/** + * The baud rate of Septentrio receivers with factory default configuration. +*/ +constexpr uint32_t k_septentrio_receiver_default_baud_rate = 115200; + constexpr uint8_t k_max_command_size = 120; constexpr uint16_t k_timeout_5hz = 500; constexpr uint32_t k_read_buffer_size = 150; @@ -134,11 +140,14 @@ constexpr const char *k_frequency_25_0hz = "msec40"; constexpr const char *k_frequency_50_0hz = "msec20"; px4::atomic SeptentrioDriver::_secondary_instance {nullptr}; +uint32_t SeptentrioDriver::k_supported_baud_rates[] {0, 38400, 57600, 115200, 230400, 460800, 500000, 576000, 921600, 1000000, 1500000}; +uint32_t SeptentrioDriver::k_default_baud_rate {230400}; +orb_advert_t SeptentrioDriver::k_mavlink_log_pub {nullptr}; SeptentrioDriver::SeptentrioDriver(const char *device_path, Instance instance, uint32_t baud_rate) : Device(MODULE_NAME), _instance(instance), - _baud_rate(baud_rate) + _chosen_baud_rate(baud_rate) { strncpy(_port, device_path, sizeof(_port) - 1); // Enforce null termination. @@ -171,6 +180,10 @@ SeptentrioDriver::SeptentrioDriver(const char *device_path, Instance instance, u get_parameter("SEP_STREAM_LOG", &receiver_stream_log); _receiver_stream_log = receiver_stream_log; + if (_receiver_stream_log == _receiver_stream_main) { + mavlink_log_warning(&k_mavlink_log_pub, "Septentrio: Logging stream should be different from main stream"); + } + int32_t automatic_configuration {true}; get_parameter("SEP_AUTO_CONFIG", &automatic_configuration); _automatic_configuration = static_cast(automatic_configuration); @@ -240,15 +253,13 @@ int SeptentrioDriver::print_status() break; } - PX4_INFO("health: %s, port: %s, baud rate: %lu", is_healthy() ? "OK" : "NOT OK", _port, _baud_rate); + PX4_INFO("health: %s, port: %s, baud rate: %lu", is_healthy() ? "OK" : "NOT OK", _port, _uart.getBaudrate()); PX4_INFO("controller -> receiver data rate: %lu B/s", output_data_rate()); PX4_INFO("receiver -> controller data rate: %lu B/s", input_data_rate()); PX4_INFO("sat info: %s", (_message_satellite_info != nullptr) ? "enabled" : "disabled"); - if (_message_gps_state.timestamp != 0) { - + if (first_gps_uorb_message_created() && _state == State::ReceivingData) { PX4_INFO("rate RTCM injection: %6.2f Hz", static_cast(rtcm_injection_frequency())); - print_message(ORB_ID(sensor_gps), _message_gps_state); } @@ -267,7 +278,7 @@ void SeptentrioDriver::run() _uart.setPort(_port); if (_uart.open()) { - _state = State::ConfiguringDevice; + _state = State::DetectingBaudRate; } else { // Failed to open port, so wait a bit before trying again. @@ -277,14 +288,42 @@ void SeptentrioDriver::run() break; } + case State::DetectingBaudRate: { + static uint32_t expected_baud_rates[] = {k_septentrio_receiver_default_baud_rate, 115200, 230400, 57600, 460800, 500000, 576000, 38400, 921600, 1000000, 1500000}; + expected_baud_rates[0] = _chosen_baud_rate != 0 ? _chosen_baud_rate : k_septentrio_receiver_default_baud_rate; + + if (detect_receiver_baud_rate(expected_baud_rates[_current_baud_rate_index], true)) { + if (set_baudrate(expected_baud_rates[_current_baud_rate_index]) == PX4_OK) { + _state = State::ConfiguringDevice; + + } else { + SEP_ERR("Setting local baud rate failed"); + } + + } else { + _current_baud_rate_index++; + + if (_current_baud_rate_index == sizeof(expected_baud_rates) / sizeof(expected_baud_rates[0])) { + _current_baud_rate_index = 0; + } + } + + break; + } + case State::ConfiguringDevice: { - if (configure() == PX4_OK) { - SEP_INFO("Automatic configuration successful"); + ConfigureResult result = configure(); + + if (!(static_cast(result) & static_cast(ConfigureResult::FailedCompletely))) { + if (static_cast(result) & static_cast(ConfigureResult::NoLogging)) { + mavlink_log_warning(&k_mavlink_log_pub, "Septentrio: Failed to configure receiver internal logging"); + } + + SEP_INFO("Automatic configuration finished"); _state = State::ReceivingData; } else { - // Failed to configure device, so wait a bit before trying again. - px4_usleep(200000); + _state = State::DetectingBaudRate; } break; @@ -296,7 +335,7 @@ void SeptentrioDriver::run() receive_result = receive(k_timeout_5hz); if (receive_result == -1) { - _state = State::ConfiguringDevice; + _state = State::DetectingBaudRate; } if (_message_satellite_info && (receive_result & 2)) { @@ -385,19 +424,51 @@ SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[]) SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[], Instance instance) { - ModuleArguments arguments{}; - SeptentrioDriver *gps{nullptr}; + ModuleArguments arguments {}; + SeptentrioDriver *gps {nullptr}; if (parse_cli_arguments(argc, argv, arguments) == PX4_ERROR) { return nullptr; } + if (arguments.device_path_main && arguments.device_path_secondary + && arguments.device_path_main == arguments.device_path_secondary) { + mavlink_log_critical(&k_mavlink_log_pub, "Septentrio: Device paths must be different"); + return nullptr; + } + + bool valid_chosen_baud_rate {false}; + + for (uint8_t i = 0; i < sizeof(k_supported_baud_rates) / sizeof(k_supported_baud_rates[0]); i++) { + switch (instance) { + case Instance::Main: + if (arguments.baud_rate_main == static_cast(k_supported_baud_rates[i])) { + valid_chosen_baud_rate = true; + } + + break; + + case Instance::Secondary: + if (arguments.baud_rate_secondary == static_cast(k_supported_baud_rates[i])) { + valid_chosen_baud_rate = true; + } + + break; + } + } + + if (!valid_chosen_baud_rate) { + mavlink_log_critical(&k_mavlink_log_pub, "Septentrio: Baud rate %d is unsupported, falling back to default %lu", + instance == Instance::Main ? arguments.baud_rate_main : arguments.baud_rate_secondary, k_default_baud_rate); + } + if (instance == Instance::Main) { if (Serial::validatePort(arguments.device_path_main)) { - gps = new SeptentrioDriver(arguments.device_path_main, instance, arguments.baud_rate_main); + gps = new SeptentrioDriver(arguments.device_path_main, instance, + valid_chosen_baud_rate ? arguments.baud_rate_main : k_default_baud_rate); } else { - PX4_ERR("invalid device (-d) %s", arguments.device_path_main ? arguments.device_path_main : ""); + PX4_ERR("Invalid device (-d) %s", arguments.device_path_main ? arguments.device_path_main : ""); } if (gps && arguments.device_path_secondary) { @@ -410,7 +481,8 @@ SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[], Instance } else { if (Serial::validatePort(arguments.device_path_secondary)) { - gps = new SeptentrioDriver(arguments.device_path_secondary, instance, arguments.baud_rate_secondary); + gps = new SeptentrioDriver(arguments.device_path_secondary, instance, + valid_chosen_baud_rate ? arguments.baud_rate_secondary : k_default_baud_rate); } else { PX4_ERR("Invalid secondary device (-e) %s", arguments.device_path_secondary ? arguments.device_path_secondary : ""); @@ -425,6 +497,7 @@ SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[], Instance int SeptentrioDriver::custom_command(int argc, char *argv[]) { bool handled = false; + const char *failure_reason {"unknown command"}; SeptentrioDriver *driver_instance; if (!is_running()) { @@ -448,7 +521,7 @@ int SeptentrioDriver::custom_command(int argc, char *argv[]) type = ReceiverResetType::Cold; } else { - print_usage("incorrect reset type"); + failure_reason = "unknown reset type"; } if (type != ReceiverResetType::None) { @@ -457,11 +530,11 @@ int SeptentrioDriver::custom_command(int argc, char *argv[]) } } else { - print_usage("incorrect usage of reset command"); + failure_reason = "incorrect usage of reset command"; } } - return (handled) ? 0 : print_usage("unknown command"); + return handled ? 0 : print_usage(failure_reason); } int SeptentrioDriver::print_usage(const char *reason) @@ -473,25 +546,28 @@ int SeptentrioDriver::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description -GPS driver module that handles the communication with Septentrio devices and publishes the position via uORB. - -The module supports a secondary GPS device, specified via `-e` parameter. The position will be published on -the second uORB topic instance. It can be used for logging and heading computation. +Driver for Septentrio GNSS receivers. It can automatically configure them and make their output available for the rest of the system. +A secondary receiver is supported for redundancy, logging and dual-receiver heading. +Septentrio receiver baud rates from 57600 to 1500000 are supported. If others are used, the driver will use 230400 and give a warning. ### Examples -Starting 2 GPS devices (main one on /dev/ttyS3, secondary on /dev/ttyS4) +Use one receiver on port `/dev/ttyS0` and automatically configure it to use baud rate 230400: +$ septentrio start -d /dev/ttyS0 -b 230400 + +Use two receivers, the primary on port `/dev/ttyS3` and the secondary on `/dev/ttyS4`, +detect baud rate automatically and preserve them: $ septentrio start -d /dev/ttyS3 -e /dev/ttyS4 -Initiate warm restart of GPS device +Perform warm reset of the receivers: $ gps reset warm )DESCR_STR"); PRINT_MODULE_USAGE_NAME("septentrio", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "Primary Septentrio receiver", false); - PRINT_MODULE_USAGE_PARAM_INT('b', 0, 57600, 1500000, "Primary baud rate", true); - PRINT_MODULE_USAGE_PARAM_STRING('e', nullptr, "", "Secondary Septentrio receiver", true); - PRINT_MODULE_USAGE_PARAM_INT('g', 0, 57600, 1500000, "Secondary baud rate", true); + PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "Primary receiver port", false); + PRINT_MODULE_USAGE_PARAM_INT('b', 0, 57600, 1500000, "Primary receiver baud rate", true); + PRINT_MODULE_USAGE_PARAM_STRING('e', nullptr, "", "Secondary receiver port", true); + PRINT_MODULE_USAGE_PARAM_INT('g', 0, 57600, 1500000, "Secondary receiver baud rate", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reset connected receiver"); @@ -508,15 +584,15 @@ int SeptentrioDriver::reset(ReceiverResetType type) switch (type) { case ReceiverResetType::Hot: - res = send_message_and_wait_for_ack(k_command_reset_hot, k_receiver_ack_timeout); + res = send_message_and_wait_for_ack(k_command_reset_hot, k_receiver_ack_timeout_fast); break; case ReceiverResetType::Warm: - res = send_message_and_wait_for_ack(k_command_reset_warm, k_receiver_ack_timeout); + res = send_message_and_wait_for_ack(k_command_reset_warm, k_receiver_ack_timeout_fast); break; case ReceiverResetType::Cold: - res = send_message_and_wait_for_ack(k_command_reset_cold, k_receiver_ack_timeout); + res = send_message_and_wait_for_ack(k_command_reset_cold, k_receiver_ack_timeout_fast); break; default: @@ -553,13 +629,13 @@ int SeptentrioDriver::parse_cli_arguments(int argc, char *argv[], ModuleArgument switch (ch) { case 'b': if (px4_get_parameter_value(myoptarg, arguments.baud_rate_main) != 0) { - PX4_ERR("baud rate parsing failed"); + PX4_ERR("Baud rate parsing failed"); return PX4_ERROR; } break; case 'g': if (px4_get_parameter_value(myoptarg, arguments.baud_rate_secondary) != 0) { - PX4_ERR("baud rate parsing failed"); + PX4_ERR("Baud rate parsing failed"); return PX4_ERROR; } break; @@ -637,42 +713,31 @@ void SeptentrioDriver::schedule_reset(ReceiverResetType reset_type) } } -uint32_t SeptentrioDriver::detect_receiver_baud_rate(bool forced_input) { - // So we can restore the port to its original state. - const uint32_t original_baud_rate = _uart.getBaudrate(); - - // Baud rates we expect the receiver to be running at. - uint32_t expected_baud_rates[] = {115200, 115200, 230400, 57600, 460800, 500000, 576000, 38400, 921600, 1000000, 1500000}; - if (_baud_rate != 0) { - expected_baud_rates[0] = _baud_rate; +bool SeptentrioDriver::detect_receiver_baud_rate(const uint32_t &baud_rate, bool forced_input) { + if (set_baudrate(baud_rate) != PX4_OK) { + return false; } - for (uint i = 0; i < sizeof(expected_baud_rates)/sizeof(expected_baud_rates[0]); i++) { - if (set_baudrate(expected_baud_rates[i]) != PX4_OK) { - set_baudrate(original_baud_rate); - return 0; - } + if (forced_input) { + force_input(); + } - if (forced_input) { - force_input(); - } + // Make sure that any weird data is "flushed" in the receiver. + (void)send_message("\n"); - if (send_message_and_wait_for_ack(k_command_ping, k_receiver_ack_timeout)) { - SEP_INFO("Detected baud rate: %lu", expected_baud_rates[i]); - set_baudrate(original_baud_rate); - return expected_baud_rates[i]; - } + if (send_message_and_wait_for_ack(k_command_ping, k_receiver_ack_timeout_fast)) { + SEP_INFO("Detected baud rate: %lu", baud_rate); + return true; } - set_baudrate(original_baud_rate); - return 0; + return false; } int SeptentrioDriver::detect_serial_port(char* const port_name) { // Read buffer to get the COM port char buf[k_read_buffer_size]; size_t buffer_offset = 0; // The offset into the string where the next data should be read to. - hrt_abstime timeout_time = hrt_absolute_time() + 5 * 1000 * k_receiver_ack_timeout; + hrt_abstime timeout_time = hrt_absolute_time() + 5 * 1000 * k_receiver_ack_timeout_fast; bool response_detected = false; // Receiver prints prompt after a message. @@ -682,7 +747,7 @@ int SeptentrioDriver::detect_serial_port(char* const port_name) { do { // Read at most the amount of available bytes in the buffer after the current offset, -1 because we need '\0' at the end for a valid string. - int read_result = read(reinterpret_cast(buf) + buffer_offset, sizeof(buf) - buffer_offset - 1, k_receiver_ack_timeout); + int read_result = read(reinterpret_cast(buf) + buffer_offset, sizeof(buf) - buffer_offset - 1, k_receiver_ack_timeout_fast); if (read_result < 0) { SEP_WARN("SBF read error"); @@ -734,132 +799,81 @@ int SeptentrioDriver::detect_serial_port(char* const port_name) { } } -int SeptentrioDriver::configure() +SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() { char msg[k_max_command_size] {}; - - // Passively detect receiver baud rate. - uint32_t detected_receiver_baud_rate = detect_receiver_baud_rate(true); - - if (detected_receiver_baud_rate == 0) { - SEP_INFO("CONFIG: failed baud detection"); - return PX4_ERROR; - } - - // Set same baud rate on our end. - if (set_baudrate(detected_receiver_baud_rate) != PX4_OK) { - SEP_INFO("CONFIG: failed local baud rate setting"); - return PX4_ERROR; - } - char com_port[5] {}; + ConfigureResult result {ConfigureResult::OK}; // Passively detect receiver port. if (detect_serial_port(com_port) != PX4_OK) { - SEP_INFO("CONFIG: failed port detection"); - return PX4_ERROR; + SEP_WARN("CONFIG: failed port detection"); + return ConfigureResult::FailedCompletely; } // We should definitely match baud rates and detect used port, but don't do other configuration if not requested. // This will force input on the receiver. That shouldn't be a problem as it's on our own connection. if (!_automatic_configuration) { - return PX4_OK; + return ConfigureResult::OK; } // If user requested specific baud rate, set it now. Otherwise keep detected baud rate. - if (strstr(com_port, "COM") != nullptr && _baud_rate != 0) { - snprintf(msg, sizeof(msg), k_command_set_baud_rate, com_port, _baud_rate); + if (strstr(com_port, "COM") != nullptr && _chosen_baud_rate != 0) { + snprintf(msg, sizeof(msg), k_command_set_baud_rate, com_port, _chosen_baud_rate); if (!send_message(msg)) { - SEP_INFO("CONFIG: baud rate command write error"); - return PX4_ERROR; + SEP_WARN("CONFIG: baud rate command write error"); + return ConfigureResult::FailedCompletely; } // When sending a command and setting the baud rate right after, the controller could send the command at the new baud rate. // From testing this could take some time. - px4_usleep(1000000); + px4_usleep(2000000); - if (set_baudrate(_baud_rate) != PX4_OK) { - SEP_INFO("CONFIG: failed local baud rate setting"); - return PX4_ERROR; + if (set_baudrate(_chosen_baud_rate) != PX4_OK) { + SEP_WARN("CONFIG: failed local baud rate setting"); + return ConfigureResult::FailedCompletely; } - if (!send_message_and_wait_for_ack(k_command_ping, k_receiver_ack_timeout)) { - SEP_INFO("CONFIG: failed remote baud rate setting"); - return PX4_ERROR; + if (!send_message_and_wait_for_ack(k_command_ping, k_receiver_ack_timeout_fast)) { + SEP_WARN("CONFIG: failed remote baud rate setting"); + return ConfigureResult::FailedCompletely; } - } else { - _baud_rate = detected_receiver_baud_rate; } // Delete all sbf outputs on current COM port to remove clutter data snprintf(msg, sizeof(msg), k_command_clear_sbf, _receiver_stream_main, com_port); - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - SEP_INFO("CONFIG: failed delete output"); - return PX4_ERROR; // connection and/or baudrate detection failed - } - - // Define/inquire the type of data that the receiver should accept/send on a given connection descriptor - snprintf(msg, sizeof(msg), k_command_set_data_io, com_port, "SBF"); - - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - return PX4_ERROR; - } - - // Specify the offsets that the receiver applies to the computed attitude angles. - snprintf(msg, sizeof(msg), k_command_set_attitude_offset, (double)(_heading_offset * 180 / M_PI_F), (double)_pitch_offset); - - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - return PX4_ERROR; - } - - snprintf(msg, sizeof(msg), k_command_set_dynamics, "high"); - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - return PX4_ERROR; + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + SEP_WARN("CONFIG: failed delete output"); + return ConfigureResult::FailedCompletely; // connection and/or baudrate detection failed } - const char *sbf_frequency {k_frequency_10_0hz}; - switch (_sbf_output_frequency) { - case SBFOutputFrequency::Hz5_0: - sbf_frequency = k_frequency_5_0hz; - break; - case SBFOutputFrequency::Hz10_0: - sbf_frequency = k_frequency_10_0hz; - break; - case SBFOutputFrequency::Hz20_0: - sbf_frequency = k_frequency_20_0hz; - break; - case SBFOutputFrequency::Hz25_0: - sbf_frequency = k_frequency_25_0hz; - break; - } - - // Output a set of SBF blocks on a given connection at a regular interval. - snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, _receiver_stream_main, com_port, sbf_frequency); - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - SEP_INFO("Failed to configure SBF"); - return PX4_ERROR; - } - - if (_receiver_setup == ReceiverSetup::MovingBase) { - if (_instance == Instance::Secondary) { - snprintf(msg, sizeof(msg), k_command_set_data_io, com_port, "+RTCMv3"); - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - SEP_INFO("Failed to configure RTCM output"); - } - } else { - snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_moving_base); - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - SEP_INFO("Failed to configure attitude source"); - } + // Set up the satellites used in PVT computation. + if (_receiver_constellation_usage != static_cast(SatelliteUsage::Default)) { + char requested_satellites[40] {}; + if (_receiver_constellation_usage & static_cast(SatelliteUsage::GPS)) { + strcat(requested_satellites, "GPS+"); } - } else { - snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_multi_antenna); - // This fails on single-antenna receivers, which is fine. Therefore don't check for acknowledgement. - if (!send_message(msg)) { - SEP_INFO("Failed to configure attitude source"); - return PX4_ERROR; + if (_receiver_constellation_usage & static_cast(SatelliteUsage::GLONASS)) { + strcat(requested_satellites, "GLONASS+"); + } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::Galileo)) { + strcat(requested_satellites, "GALILEO+"); + } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::SBAS)) { + strcat(requested_satellites, "SBAS+"); + } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::BeiDou)) { + strcat(requested_satellites, "BEIDOU+"); + } + // Make sure to remove the trailing '+' if any. + requested_satellites[math::max(static_cast(strlen(requested_satellites)) - 1, 0)] = '\0'; + snprintf(msg, sizeof(msg), k_command_set_satellite_usage, requested_satellites); + // Use a longer timeout as the `setSatelliteUsage` command acknowledges a bit slower on mosaic-H-based receivers. + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_slow)) { + SEP_WARN("CONFIG: Failed to configure constellation usage"); + return ConfigureResult::FailedCompletely; } } @@ -919,42 +933,77 @@ int SeptentrioDriver::configure() } snprintf(msg, sizeof(msg), k_command_set_sbf_output, _receiver_stream_log, "DSK1", _receiver_logging_overwrite ? "" : "+", level, frequency); - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - SEP_ERR("Failed to configure logging"); - return PX4_ERROR; + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + result = static_cast(static_cast(result) | static_cast(ConfigureResult::NoLogging)); } } else if (_receiver_stream_log == _receiver_stream_main) { - SEP_WARN("Skipping logging setup: logging stream can't equal main stream"); + result = static_cast(static_cast(result) | static_cast(ConfigureResult::NoLogging)); } - // Set up the satellites used in PVT computation. - if (_receiver_constellation_usage != static_cast(SatelliteUsage::Default)) { - char requested_satellites[40] {}; - if (_receiver_constellation_usage & static_cast(SatelliteUsage::GPS)) { - strcat(requested_satellites, "GPS+"); - } - if (_receiver_constellation_usage & static_cast(SatelliteUsage::GLONASS)) { - strcat(requested_satellites, "GLONASS+"); - } - if (_receiver_constellation_usage & static_cast(SatelliteUsage::Galileo)) { - strcat(requested_satellites, "GALILEO+"); - } - if (_receiver_constellation_usage & static_cast(SatelliteUsage::SBAS)) { - strcat(requested_satellites, "SBAS+"); - } - if (_receiver_constellation_usage & static_cast(SatelliteUsage::BeiDou)) { - strcat(requested_satellites, "BEIDOU+"); + // Define/inquire the type of data that the receiver should accept/send on a given connection descriptor + snprintf(msg, sizeof(msg), k_command_set_data_io, com_port, "SBF"); + + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + return ConfigureResult::FailedCompletely; + } + + // Specify the offsets that the receiver applies to the computed attitude angles. + snprintf(msg, sizeof(msg), k_command_set_attitude_offset, (double)(_heading_offset * 180 / M_PI_F), (double)_pitch_offset); + + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + return ConfigureResult::FailedCompletely; + } + + snprintf(msg, sizeof(msg), k_command_set_dynamics, "high"); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + return ConfigureResult::FailedCompletely; + } + + const char *sbf_frequency {k_frequency_10_0hz}; + switch (_sbf_output_frequency) { + case SBFOutputFrequency::Hz5_0: + sbf_frequency = k_frequency_5_0hz; + break; + case SBFOutputFrequency::Hz10_0: + sbf_frequency = k_frequency_10_0hz; + break; + case SBFOutputFrequency::Hz20_0: + sbf_frequency = k_frequency_20_0hz; + break; + case SBFOutputFrequency::Hz25_0: + sbf_frequency = k_frequency_25_0hz; + break; + } + + // Output a set of SBF blocks on a given connection at a regular interval. + snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, _receiver_stream_main, com_port, sbf_frequency); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + SEP_WARN("CONFIG: Failed to configure SBF"); + return ConfigureResult::FailedCompletely; + } + + if (_receiver_setup == ReceiverSetup::MovingBase) { + if (_instance == Instance::Secondary) { + snprintf(msg, sizeof(msg), k_command_set_data_io, com_port, "+RTCMv3"); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + SEP_WARN("CONFIG: Failed to configure RTCM output"); + } + } else { + snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_moving_base); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { + SEP_WARN("CONFIG: Failed to configure attitude source"); + } } - // Make sure to remove the trailing '+' if any. - requested_satellites[math::max(static_cast(strlen(requested_satellites)) - 1, 0)] = '\0'; - snprintf(msg, sizeof(msg), k_command_set_satellite_usage, requested_satellites); - if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout)) { - SEP_ERR("Failed to configure constellation usage"); - return PX4_ERROR; + } else { + snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_multi_antenna); + // This fails on single-antenna receivers, which is fine. Therefore don't check for acknowledgement. + if (!send_message(msg)) { + SEP_WARN("CONFIG: Failed to configure attitude source"); + return ConfigureResult::FailedCompletely; } } - return PX4_OK; + return result; } int SeptentrioDriver::parse_char(const uint8_t byte) @@ -1035,36 +1084,37 @@ int SeptentrioDriver::process_message() PVTGeodetic pvt_geodetic; if (_sbf_decoder.parse(&header) == PX4_OK && _sbf_decoder.parse(&pvt_geodetic) == PX4_OK) { - if (pvt_geodetic.mode_type < ModeType::StandAlonePVT) { + switch (pvt_geodetic.mode_type) { + case ModeType::NoPVT: _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; - - } else if (pvt_geodetic.mode_type == ModeType::PVTWithSBAS) { + break; + case ModeType::PVTWithSBAS: _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTCM_CODE_DIFFERENTIAL; - - } else if (pvt_geodetic.mode_type == ModeType::RTKFloat || pvt_geodetic.mode_type == ModeType::MovingBaseRTKFloat) { + break; + case ModeType::RTKFloat: + case ModeType::MovingBaseRTKFloat: _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FLOAT; - - } else if (pvt_geodetic.mode_type == ModeType::RTKFixed || pvt_geodetic.mode_type == ModeType::MovingBaseRTKFixed) { + break; + case ModeType::RTKFixed: + case ModeType::MovingBaseRTKFixed: _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FIXED; - - } else { + break; + default: _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_3D; + break; } - // Check fix and error code - _message_gps_state.vel_ned_valid = _message_gps_state.fix_type > sensor_gps_s::FIX_TYPE_NONE && pvt_geodetic.error == Error::None; - // Check boundaries and invalidate GPS velocities if (pvt_geodetic.vn <= k_dnu_f4_value || pvt_geodetic.ve <= k_dnu_f4_value || pvt_geodetic.vu <= k_dnu_f4_value) { _message_gps_state.vel_ned_valid = false; } - // Check boundaries and invalidate position - // We're not just checking for the do-not-use value but for any value beyond the specified max values - if (pvt_geodetic.latitude <= k_dnu_f8_value || - pvt_geodetic.longitude <= k_dnu_f8_value || - pvt_geodetic.height <= k_dnu_f8_value || - pvt_geodetic.undulation <= k_dnu_f4_value) { + if (pvt_geodetic.latitude > k_dnu_f8_value && pvt_geodetic.longitude > k_dnu_f8_value && pvt_geodetic.height > k_dnu_f8_value && pvt_geodetic.undulation > k_dnu_f4_value) { + _message_gps_state.latitude_deg = pvt_geodetic.latitude * M_RAD_TO_DEG; + _message_gps_state.longitude_deg = pvt_geodetic.longitude * M_RAD_TO_DEG; + _message_gps_state.altitude_msl_m = pvt_geodetic.height - static_cast(pvt_geodetic.undulation); + _message_gps_state.altitude_ellipsoid_m = pvt_geodetic.height; + } else { _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; } @@ -1082,23 +1132,22 @@ int SeptentrioDriver::process_message() _message_gps_state.satellites_used = 0; } - _message_gps_state.latitude_deg = pvt_geodetic.latitude * M_RAD_TO_DEG; - _message_gps_state.longitude_deg = pvt_geodetic.longitude * M_RAD_TO_DEG; - _message_gps_state.altitude_msl_m = pvt_geodetic.height - static_cast(pvt_geodetic.undulation); - _message_gps_state.altitude_ellipsoid_m = pvt_geodetic.height; - /* H and V accuracy are reported in 2DRMS, but based off the u-blox reporting we expect RMS. * Divide by 100 from cm to m and in addition divide by 2 to get RMS. */ _message_gps_state.eph = static_cast(pvt_geodetic.h_accuracy) / 200.0f; _message_gps_state.epv = static_cast(pvt_geodetic.v_accuracy) / 200.0f; + // Check fix and error code + _message_gps_state.vel_ned_valid = _message_gps_state.fix_type > sensor_gps_s::FIX_TYPE_NONE && pvt_geodetic.error == Error::None; _message_gps_state.vel_n_m_s = pvt_geodetic.vn; _message_gps_state.vel_e_m_s = pvt_geodetic.ve; _message_gps_state.vel_d_m_s = -1.0f * pvt_geodetic.vu; _message_gps_state.vel_m_s = sqrtf(_message_gps_state.vel_n_m_s * _message_gps_state.vel_n_m_s + _message_gps_state.vel_e_m_s * _message_gps_state.vel_e_m_s); - _message_gps_state.cog_rad = pvt_geodetic.cog * M_DEG_TO_RAD_F; + if (pvt_geodetic.cog > k_dnu_f4_value) { + _message_gps_state.cog_rad = pvt_geodetic.cog * M_DEG_TO_RAD_F; + } _message_gps_state.c_variance_rad = M_DEG_TO_RAD_F; _message_gps_state.time_utc_usec = 0; @@ -1178,14 +1227,8 @@ int SeptentrioDriver::process_message() VelCovGeodetic vel_cov_geodetic; if (_sbf_decoder.parse(&vel_cov_geodetic) == PX4_OK) { - _message_gps_state.s_variance_m_s = vel_cov_geodetic.cov_ve_ve; - - if (_message_gps_state.s_variance_m_s < vel_cov_geodetic.cov_vn_vn) { - _message_gps_state.s_variance_m_s = vel_cov_geodetic.cov_vn_vn; - } - - if (_message_gps_state.s_variance_m_s < vel_cov_geodetic.cov_vu_vu) { - _message_gps_state.s_variance_m_s = vel_cov_geodetic.cov_vu_vu; + if (vel_cov_geodetic.cov_ve_ve > k_dnu_f4_value && vel_cov_geodetic.cov_vn_vn > k_dnu_f4_value && vel_cov_geodetic.cov_vu_vu > k_dnu_f4_value) { + _message_gps_state.s_variance_m_s = math::max(math::max(vel_cov_geodetic.cov_ve_ve, vel_cov_geodetic.cov_vn_vn), vel_cov_geodetic.cov_vu_vu); } } @@ -1206,7 +1249,8 @@ int SeptentrioDriver::process_message() if (_sbf_decoder.parse(&att_euler) && !att_euler.error_not_requested && att_euler.error_aux1 == Error::None && - att_euler.error_aux2 == Error::None) { + att_euler.error_aux2 == Error::None && + att_euler.heading > k_dnu_f4_value) { float heading = att_euler.heading * M_PI_F / 180.0f; // Range of degrees to range of radians in [0, 2PI]. // Ensure range is in [-PI, PI]. @@ -1230,7 +1274,8 @@ int SeptentrioDriver::process_message() if (_sbf_decoder.parse(&att_cov_euler) == PX4_OK && !att_cov_euler.error_not_requested && att_cov_euler.error_aux1 == Error::None && - att_cov_euler.error_aux2 == Error::None) { + att_cov_euler.error_aux2 == Error::None && + att_cov_euler.cov_headhead > k_dnu_f4_value) { _message_gps_state.heading_accuracy = att_cov_euler.cov_headhead * M_PI_F / 180.0f; // Convert range of degrees to range of radians in [0, 2PI] } @@ -1289,13 +1334,16 @@ bool SeptentrioDriver::send_message_and_wait_for_ack(const char *msg, const int return true; } else if (expected_response[response_check_character] == buf[i]) { ++response_check_character; + } else if (buf[i] == '$') { + // Special case makes sure we don't miss start of new response if that happened to be the character we weren't expecting next (e.g., `$R: ge$R: gecm`) + response_check_character = 1; } else { response_check_character = 0; } } } while (timeout_time > hrt_absolute_time()); - PX4_DEBUG("Response: timeout"); + SEP_WARN("Response: timeout"); return false; } @@ -1523,6 +1571,11 @@ void SeptentrioDriver::publish_satellite_info() } } +bool SeptentrioDriver::first_gps_uorb_message_created() const +{ + return _message_gps_state.timestamp != 0; +} + void SeptentrioDriver::publish_rtcm_corrections(uint8_t *data, size_t len) { gps_inject_data_s gps_inject_data{}; @@ -1668,13 +1721,11 @@ void SeptentrioDriver::set_clock(timespec rtc_gps_time) bool SeptentrioDriver::is_healthy() const { - if (_state == State::ReceivingData) { - if (!receiver_configuration_healthy()) { - return false; - } + if (_state == State::ReceivingData && receiver_configuration_healthy()) { + return true; } - return true; + return false; } void SeptentrioDriver::reset_gps_state_message() diff --git a/src/drivers/gnss/septentrio/septentrio.h b/src/drivers/gnss/septentrio/septentrio.h index 371c0f2d98cc..ec203cd86186 100644 --- a/src/drivers/gnss/septentrio/septentrio.h +++ b/src/drivers/gnss/septentrio/septentrio.h @@ -47,6 +47,7 @@ #include #include #include +#include #include #include #include @@ -271,9 +272,20 @@ class SeptentrioDriver : public ModuleBase, public device::Dev * @return `PX4_OK` on success, `PX4_ERROR` otherwise */ int force_input(); + + /** + * Standard baud rates the driver can be started with. `0` means the driver matches baud rates but does not change them. + */ + static uint32_t k_supported_baud_rates[]; + + /** + * Default baud rate, used when the user requested an invalid baud rate. + */ + static uint32_t k_default_baud_rate; private: enum class State { OpeningSerialPort, + DetectingBaudRate, ConfiguringDevice, ReceivingData, }; @@ -295,9 +307,24 @@ class SeptentrioDriver : public ModuleBase, public device::Dev }; /** - * Maximum timeout to wait for command acknowledgement by the receiver. + * The result of trying to configure the receiver. + */ + enum class ConfigureResult : int32_t { + OK = 0, + FailedCompletely = 1 << 0, + NoLogging = 1 << 1, + }; + + /** + * Maximum timeout to wait for fast command acknowledgement by the receiver. */ - static constexpr uint16_t k_receiver_ack_timeout = 200; + static constexpr uint16_t k_receiver_ack_timeout_fast = 200; + + /** + * Maximum timeout to wait for slow command acknowledgement by the receiver. + * Might be the case for commands that send more output back as reply. + */ + static constexpr uint16_t k_receiver_ack_timeout_slow = 400; /** * Duration of one update monitoring interval in us. @@ -306,6 +333,11 @@ class SeptentrioDriver : public ModuleBase, public device::Dev */ static constexpr hrt_abstime k_update_monitoring_interval_duration = 5_s; + /** + * uORB type to send messages to ground control stations. + */ + static orb_advert_t k_mavlink_log_pub; + /** * The default stream for output of PVT data. */ @@ -347,13 +379,15 @@ class SeptentrioDriver : public ModuleBase, public device::Dev void schedule_reset(ReceiverResetType type); /** - * @brief Detect the current baud rate used by the receiver on the connected port. + * @brief Detect whether the receiver is running at the given baud rate. + * Does not preserve local baud rate! * - * @param force_input Choose whether the receiver forces input on the port + * @param baud_rate The baud rate to check. + * @param force_input Choose whether the receiver forces input on the port. * - * @return The detected baud rate on success, or `0` on error + * @return `true` if running at the baud rate, or `false` on error. */ - uint32_t detect_receiver_baud_rate(bool forced_input); + bool detect_receiver_baud_rate(const uint32_t &baud_rate, bool forced_input); /** * @brief Try to detect the serial port used on the receiver side. @@ -369,9 +403,9 @@ class SeptentrioDriver : public ModuleBase, public device::Dev * * If the user has disabled automatic configuration, only execute the steps that do not touch the receiver (e.g., baud rate detection, port detection...). * - * @return `PX4_OK` on success, `PX4_ERROR` otherwise. + * @return `ConfigureResult::OK` if configured, or error. */ - int configure(); + ConfigureResult configure(); /** * @brief Parse the next byte of a received message from the receiver. @@ -505,6 +539,13 @@ class SeptentrioDriver : public ModuleBase, public device::Dev */ void publish_satellite_info(); + /** + * @brief Check whether the driver has created its first complete `SensorGPS` uORB message. + * + * @return `true` if the driver has created its first complete `SensorGPS` uORB message, `false` if still waiting. + */ + bool first_gps_uorb_message_created() const; + /** * @brief Publish RTCM corrections. * @@ -579,6 +620,9 @@ class SeptentrioDriver : public ModuleBase, public device::Dev /** * @brief Check whether the current receiver configuration is likely healthy. * + * This is checked by passively monitoring output from the receiver and validating whether it is what is + * expected. + * * @return `true` if the receiver is operating correctly, `false` if it needs to be reconfigured. */ bool receiver_configuration_healthy() const; @@ -611,6 +655,9 @@ class SeptentrioDriver : public ModuleBase, public device::Dev /** * @brief Check whether the driver is operating correctly. * + * The driver is operating correctly when it has fully configured the receiver and is actively receiving all the + * expected data. + * * @return `true` if the driver is working as expected, `false` otherwise. */ bool is_healthy() const; @@ -666,7 +713,7 @@ class SeptentrioDriver : public ModuleBase, public device::Dev uint8_t _spoofing_state {0}; ///< Receiver spoofing state uint8_t _jamming_state {0}; ///< Receiver jamming state const Instance _instance {Instance::Main}; ///< The receiver that this instance of the driver controls - uint32_t _baud_rate {0}; + uint32_t _chosen_baud_rate {0}; ///< The baud rate requested by the user static px4::atomic _secondary_instance; hrt_abstime _sleep_end {0}; ///< End time for sleeping State _resume_state {State::OpeningSerialPort}; ///< Resume state after sleep @@ -683,6 +730,7 @@ class SeptentrioDriver : public ModuleBase, public device::Dev bool _automatic_configuration {true}; ///< Automatic configuration of the receiver given by the `SEP_AUTO_CONFIG` parameter ReceiverSetup _receiver_setup {ReceiverSetup::Default}; ///< Purpose of the receivers, given by the `SEP_HARDW_SETUP` parameter int32_t _receiver_constellation_usage {0}; ///< Constellation usage in PVT computation given by the `SEP_CONST_USAGE` parameter + uint8_t _current_baud_rate_index {0}; ///< Index of the current baud rate to check // Decoding and parsing DecodingStatus _active_decoder {DecodingStatus::Searching}; ///< Currently active decoder that new data has to be fed into From 7bb239637e08014568e5f43871c443e5032cfc5e Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Mon, 17 Jun 2024 11:01:08 +0200 Subject: [PATCH 422/652] gnss(septentrio): fix error on driver start with same device paths This fixes an incorrect check of the device paths during instantiation of the Septentrio driver that caused the driver to start and not print an error message. --- src/drivers/gnss/septentrio/septentrio.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index 838caea2947c..cc6f5b828342 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -432,7 +432,7 @@ SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[], Instance } if (arguments.device_path_main && arguments.device_path_secondary - && arguments.device_path_main == arguments.device_path_secondary) { + && strcmp(arguments.device_path_main, arguments.device_path_secondary) == 0) { mavlink_log_critical(&k_mavlink_log_pub, "Septentrio: Device paths must be different"); return nullptr; } From bfbbf2ff6f51ec5e9b71110d8e74c61922ae4f4b Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Mon, 17 Jun 2024 11:15:47 +0200 Subject: [PATCH 423/652] gnss(septentrio): improve `SEP_DUMP_COMM` parameter documentation The documentation for `SEP_DUMP_COMM` was quite unclear and users had to use the user guide to find out what exactly it did. The new documentation tries to make the purpose clearer. --- src/drivers/gnss/septentrio/module.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/gnss/septentrio/module.yaml b/src/drivers/gnss/septentrio/module.yaml index 49788b7f9759..fd06252469a1 100644 --- a/src/drivers/gnss/septentrio/module.yaml +++ b/src/drivers/gnss/septentrio/module.yaml @@ -104,7 +104,8 @@ parameters: description: short: Log GPS communication data long: | - Dump raw communication data from and to the connected receiver to the log file. + Log raw communication between the driver and connected receivers. + For example, "To receiver" will log all commands and corrections sent by the driver to the receiver. type: enum default: 0 min: 0 From 49dc896d205864d58203cfd3927dcdb9e2897cda Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Tue, 18 Jun 2024 10:11:54 +0200 Subject: [PATCH 424/652] gnss(septentrio): fix broken heading Heading wasn't working because of an incorrect check during parsing. --- src/drivers/gnss/septentrio/septentrio.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index cc6f5b828342..5b8839101732 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -1246,7 +1246,7 @@ int SeptentrioDriver::process_message() AttEuler att_euler; - if (_sbf_decoder.parse(&att_euler) && + if (_sbf_decoder.parse(&att_euler) == PX4_OK && !att_euler.error_not_requested && att_euler.error_aux1 == Error::None && att_euler.error_aux2 == Error::None && @@ -1540,10 +1540,6 @@ void SeptentrioDriver::publish() _sensor_gps_pub.publish(_message_gps_state); - // Heading/yaw data can be updated at a lower rate than the other navigation data. - // The uORB message definition requires this data to be set to a NAN if no new valid data is available. - _message_gps_state.heading = NAN; - if (_message_gps_state.spoofing_state != _spoofing_state) { if (_message_gps_state.spoofing_state > sensor_gps_s::SPOOFING_STATE_NONE) { From e27b252433e52c52773ebeffdb39b571a7044c5a Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Tue, 18 Jun 2024 11:28:29 +0200 Subject: [PATCH 425/652] gnss(septentrio): fix incorrect heading offset configuration Heading offset was configured as radians but should be configured as degrees on Septentrio receivers. The parameter was already in degrees but the configuration logic was changing it into radians. Also allow the entire allowed range of heading offset values for Septentrio receivers. --- src/drivers/gnss/septentrio/module.yaml | 2 +- src/drivers/gnss/septentrio/septentrio.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/gnss/septentrio/module.yaml b/src/drivers/gnss/septentrio/module.yaml index fd06252469a1..1b151f3618ba 100644 --- a/src/drivers/gnss/septentrio/module.yaml +++ b/src/drivers/gnss/septentrio/module.yaml @@ -71,7 +71,7 @@ parameters: type: float decimal: 3 default: 0 - min: 0 + min: -360 max: 360 unit: deg reboot_required: true diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index 5b8839101732..095e60d5c329 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -153,8 +153,6 @@ SeptentrioDriver::SeptentrioDriver(const char *device_path, Instance instance, u // Enforce null termination. _port[sizeof(_port) - 1] = '\0'; - reset_gps_state_message(); - int32_t enable_sat_info {0}; get_parameter("SEP_SAT_INFO", &enable_sat_info); @@ -211,6 +209,8 @@ SeptentrioDriver::SeptentrioDriver(const char *device_path, Instance instance, u } set_device_type(DRV_GPS_DEVTYPE_SBF); + + reset_gps_state_message(); } SeptentrioDriver::~SeptentrioDriver() @@ -948,7 +948,7 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() } // Specify the offsets that the receiver applies to the computed attitude angles. - snprintf(msg, sizeof(msg), k_command_set_attitude_offset, (double)(_heading_offset * 180 / M_PI_F), (double)_pitch_offset); + snprintf(msg, sizeof(msg), k_command_set_attitude_offset, static_cast(_heading_offset), static_cast(_pitch_offset)); if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { return ConfigureResult::FailedCompletely; From c0663ee85c8b52065d75fb9e024e8ec5a013eba3 Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Fri, 21 Jun 2024 11:06:45 +0200 Subject: [PATCH 426/652] gnss(septentrio): fix line lenghth of module documentation --- src/drivers/gnss/septentrio/septentrio.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index 095e60d5c329..5c53db6098d5 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -546,9 +546,11 @@ int SeptentrioDriver::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description -Driver for Septentrio GNSS receivers. It can automatically configure them and make their output available for the rest of the system. +Driver for Septentrio GNSS receivers. +It can automatically configure them and make their output available for the rest of the system. A secondary receiver is supported for redundancy, logging and dual-receiver heading. -Septentrio receiver baud rates from 57600 to 1500000 are supported. If others are used, the driver will use 230400 and give a warning. +Septentrio receiver baud rates from 57600 to 1500000 are supported. +If others are used, the driver will use 230400 and give a warning. ### Examples From c8c46788ed079216e38a3d4d421b96f28d949ab3 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 27 Jun 2024 14:17:57 +0200 Subject: [PATCH 427/652] Autostart: load airframes with priority ROMFS -> SD card --- ROMFS/px4fmu_common/init.d/rcS | 26 ++++++++++++++++---------- Tools/px4airframes/rcout.py | 6 ------ 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 9986a3a75374..0849dbd6cd6a 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -217,25 +217,31 @@ else fi unset BOARD_RC_DEFAULTS - # - # Set parameters and env variables for selected SYS_AUTOSTART. - # - set AUTOSTART_PATH etc/init.d/rc.autostart + # Load airframe configuration based on SYS_AUTOSTART parameter if ! param compare SYS_AUTOSTART 0 then - if param greater SYS_AUTOSTART 1000000 + # rc.autostart directly run the right airframe script which sets the VEHICLE_TYPE + # Look for airframe in ROMFS + . ${R}etc/init.d/rc.autostart + + if [ ${VEHICLE_TYPE} == none ] then - # Use external startup file + # Look for airframe on SD card if [ $SDCARD_AVAILABLE = yes ] then - set AUTOSTART_PATH etc/init.d/rc.autostart_ext + . ${R}etc/init.d/rc.autostart_ext else - echo "ERROR [init] SD card not mounted - trying to load airframe from ROMFS" + echo "ERROR [init] SD card not mounted - can't load external airframe" fi fi - . ${R}$AUTOSTART_PATH + + if [ ${VEHICLE_TYPE} == none ] + then + echo "ERROR [init] No airframe file found for SYS_AUTOSTART value" + param set SYS_AUTOSTART 0 + tune_control play error + fi fi - unset AUTOSTART_PATH # Check parameter version and reset upon airframe configuration version mismatch. # Reboot required because "param reset_all" would reset all "param set" lines from airframe. diff --git a/Tools/px4airframes/rcout.py b/Tools/px4airframes/rcout.py index 9bc8747185a2..a6bdc9e94410 100644 --- a/Tools/px4airframes/rcout.py +++ b/Tools/px4airframes/rcout.py @@ -79,12 +79,6 @@ def __init__(self, groups, board, post_start=False): result += "then\n" result += "\techo \"Loading airframe: /etc/init.d/airframes/${AIRFRAME}\"\n" result += "\t. /etc/init.d/airframes/${AIRFRAME}\n" - if not post_start: - result += "else\n" - result += "\techo \"ERROR [init] No file matches SYS_AUTOSTART value found in : /etc/init.d/airframes\"\n" - # Reset the configuration - result += "\tparam set SYS_AUTOSTART 0\n" - result += "\ttone_alarm ${TUNE_ERR}\n" result += "fi\n" result += "unset AIRFRAME" self.output = result From d3480d13026a6243daebdb8ee19a2107bcae38dd Mon Sep 17 00:00:00 2001 From: Dmitry Ponomarev Date: Mon, 6 Feb 2023 00:55:52 +0300 Subject: [PATCH 428/652] Cyphal: add port.List --- src/drivers/cyphal/Cyphal.cpp | 43 +++++++++++++++++++++- src/drivers/cyphal/Cyphal.hpp | 3 ++ src/drivers/cyphal/PublicationManager.cpp | 9 +++++ src/drivers/cyphal/PublicationManager.hpp | 2 + src/drivers/cyphal/SubscriptionManager.cpp | 21 +++++++++++ src/drivers/cyphal/SubscriptionManager.hpp | 2 + 6 files changed, 79 insertions(+), 1 deletion(-) diff --git a/src/drivers/cyphal/Cyphal.cpp b/src/drivers/cyphal/Cyphal.cpp index 73de1992ff51..5ce3a0b77a01 100644 --- a/src/drivers/cyphal/Cyphal.cpp +++ b/src/drivers/cyphal/Cyphal.cpp @@ -125,7 +125,7 @@ int CyphalNode::start(uint32_t node_id, uint32_t bitrate) _instance = new CyphalNode(node_id, 8, CANARD_MTU_CAN_FD); } else { - _instance = new CyphalNode(node_id, 64, CANARD_MTU_CAN_CLASSIC); + _instance = new CyphalNode(node_id, 512, CANARD_MTU_CAN_CLASSIC); } if (_instance == nullptr) { @@ -188,6 +188,8 @@ void CyphalNode::Run() // send uavcan::node::Heartbeat_1_0 @ 1 Hz sendHeartbeat(); + sendPortList(); + // Check all publishers _pub_manager.update(); @@ -392,6 +394,45 @@ void CyphalNode::sendHeartbeat() } } +void CyphalNode::sendPortList() +{ + static hrt_abstime _uavcan_node_port_List_last{0}; + + if (hrt_elapsed_time(&_uavcan_node_port_List_last) < 3_s) { + return; + } + + static uavcan_node_port_List_0_1 msg{}; + static uint8_t uavcan_node_port_List_0_1_buffer[uavcan_node_port_List_0_1_EXTENT_BYTES_]; + static CanardTransferID _uavcan_node_port_List_transfer_id{0}; + size_t payload_size = uavcan_node_port_List_0_1_EXTENT_BYTES_; + const hrt_abstime now = hrt_absolute_time(); + + const CanardTransferMetadata transfer_metadata = { + .priority = CanardPriorityNominal, + .transfer_kind = CanardTransferKindMessage, + .port_id = uavcan_node_port_List_0_1_FIXED_PORT_ID_, + .remote_node_id = CANARD_NODE_ID_UNSET, + .transfer_id = _uavcan_node_port_List_transfer_id++ + }; + + // memset(uavcan_node_port_List_0_1_buffer, 0x00, uavcan_node_port_List_0_1_EXTENT_BYTES_); + uavcan_node_port_List_0_1_initialize_(&msg); + + _pub_manager.fillSubjectIdList(msg.publishers); + _sub_manager.fillSubjectIdList(msg.subscribers); + + uavcan_node_port_List_0_1_serialize_(&msg, uavcan_node_port_List_0_1_buffer, &payload_size); + + _canard_handle.TxPush(now + PUBLISHER_DEFAULT_TIMEOUT_USEC, + &transfer_metadata, + payload_size, + &uavcan_node_port_List_0_1_buffer + ); + + _uavcan_node_port_List_last = now; +} + bool UavcanMixingInterface::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs, unsigned num_control_groups_updated) { diff --git a/src/drivers/cyphal/Cyphal.hpp b/src/drivers/cyphal/Cyphal.hpp index 004a509f4039..0132830fb6c9 100644 --- a/src/drivers/cyphal/Cyphal.hpp +++ b/src/drivers/cyphal/Cyphal.hpp @@ -137,6 +137,9 @@ class CyphalNode : public ModuleParams, public px4::ScheduledWorkItem // Sends a heartbeat at 1s intervals void sendHeartbeat(); + // Sends a port.List at 3s intervals + void sendPortList(); + px4::atomic_bool _task_should_exit{false}; ///< flag to indicate to tear down the CAN driver bool _initialized{false}; ///< number of actuators currently available diff --git a/src/drivers/cyphal/PublicationManager.cpp b/src/drivers/cyphal/PublicationManager.cpp index 74ef3699c4d7..84133e037240 100644 --- a/src/drivers/cyphal/PublicationManager.cpp +++ b/src/drivers/cyphal/PublicationManager.cpp @@ -125,6 +125,15 @@ UavcanPublisher *PublicationManager::getPublisher(const char *subject_name) return NULL; } +void PublicationManager::fillSubjectIdList(uavcan_node_port_SubjectIDList_0_1 &publishers_list) +{ + uavcan_node_port_SubjectIDList_0_1_select_sparse_list_(&publishers_list); + + for (auto &dynpub : _dynpublishers) { + publishers_list.sparse_list.elements[publishers_list.sparse_list.count].value = dynpub->id(); + publishers_list.sparse_list.count++; + } +} void PublicationManager::update() { diff --git a/src/drivers/cyphal/PublicationManager.hpp b/src/drivers/cyphal/PublicationManager.hpp index 2c3da87d9d58..c996e797e9aa 100644 --- a/src/drivers/cyphal/PublicationManager.hpp +++ b/src/drivers/cyphal/PublicationManager.hpp @@ -79,6 +79,7 @@ #include #include +#include #include "Actuators/EscClient.hpp" #include "Publishers/udral/Readiness.hpp" @@ -103,6 +104,7 @@ class PublicationManager UavcanPublisher *getPublisher(const char *subject_name); + void fillSubjectIdList(uavcan_node_port_SubjectIDList_0_1 &publishers_list); private: void updateDynamicPublications(); diff --git a/src/drivers/cyphal/SubscriptionManager.cpp b/src/drivers/cyphal/SubscriptionManager.cpp index e489357fc2f5..ef4ae73f2bd9 100644 --- a/src/drivers/cyphal/SubscriptionManager.cpp +++ b/src/drivers/cyphal/SubscriptionManager.cpp @@ -158,3 +158,24 @@ void SubscriptionManager::updateParams() // Check for any newly-enabled subscriptions updateDynamicSubscriptions(); } + +void SubscriptionManager::fillSubjectIdList(uavcan_node_port_SubjectIDList_0_1 &subscribers_list) +{ + uavcan_node_port_SubjectIDList_0_1_select_sparse_list_(&subscribers_list); + + UavcanDynamicPortSubscriber *dynsub = _dynsubscribers; + + auto &sparse_list = subscribers_list.sparse_list; + + while (dynsub != nullptr) { + int32_t instance_idx = 0; + + while (dynsub->isValidPortId(dynsub->id(instance_idx))) { + sparse_list.elements[sparse_list.count].value = dynsub->id(instance_idx); + sparse_list.count++; + instance_idx++; + } + + dynsub = dynsub->next(); + } +} diff --git a/src/drivers/cyphal/SubscriptionManager.hpp b/src/drivers/cyphal/SubscriptionManager.hpp index bb56e1e05776..ce5b12a54d57 100644 --- a/src/drivers/cyphal/SubscriptionManager.hpp +++ b/src/drivers/cyphal/SubscriptionManager.hpp @@ -71,6 +71,7 @@ #include #include +#include #include "Subscribers/DynamicPortSubscriber.hpp" #include "CanardInterface.hpp" @@ -100,6 +101,7 @@ class SubscriptionManager void subscribe(); void printInfo(); void updateParams(); + void fillSubjectIdList(uavcan_node_port_SubjectIDList_0_1 &subscribers_list); private: void updateDynamicSubscriptions(); From b063202b456a346e56b7ff45ba8a12a9f1a6ae61 Mon Sep 17 00:00:00 2001 From: Dmitry Ponomarev Date: Tue, 13 Dec 2022 14:46:41 +0300 Subject: [PATCH 429/652] Cyphal: remove setpoint scaling to 8192 --- src/drivers/cyphal/Actuators/EscClient.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/cyphal/Actuators/EscClient.hpp b/src/drivers/cyphal/Actuators/EscClient.hpp index 8d3f75fba632..c546c5b8b475 100644 --- a/src/drivers/cyphal/Actuators/EscClient.hpp +++ b/src/drivers/cyphal/Actuators/EscClient.hpp @@ -105,7 +105,7 @@ class UavcanEscController : public UavcanPublisher for (uint8_t i = 0; i < MAX_ACTUATORS; i++) { if (i < num_outputs) { - msg_sp.value[i] = static_cast(outputs[i]); + msg_sp.value[i] = static_cast(outputs[i] / 8192.0); } else { // "unset" values published as NaN From 52476633a86693551da7f81b6cfa6b0b82e2fd69 Mon Sep 17 00:00:00 2001 From: Dmitry Ponomarev Date: Fri, 14 Apr 2023 17:47:10 +0300 Subject: [PATCH 430/652] Cyphal: use actual time instead of transfer id in uptime field of heartbeat --- src/drivers/cyphal/Cyphal.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/cyphal/Cyphal.cpp b/src/drivers/cyphal/Cyphal.cpp index 5ce3a0b77a01..94030971b54e 100644 --- a/src/drivers/cyphal/Cyphal.cpp +++ b/src/drivers/cyphal/Cyphal.cpp @@ -361,10 +361,10 @@ void CyphalNode::sendHeartbeat() if (hrt_elapsed_time(&_uavcan_node_heartbeat_last) >= 1_s) { uavcan_node_Heartbeat_1_0 heartbeat{}; - heartbeat.uptime = _uavcan_node_heartbeat_transfer_id; // TODO: use real uptime + const hrt_abstime now = hrt_absolute_time(); + heartbeat.uptime = now / 1000000; heartbeat.health.value = uavcan_node_Health_1_0_NOMINAL; heartbeat.mode.value = uavcan_node_Mode_1_0_OPERATIONAL; - const hrt_abstime now = hrt_absolute_time(); size_t payload_size = uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_; const CanardTransferMetadata transfer_metadata = { From 515543b1c5a3c1d11053c57f7f9eca803c94de78 Mon Sep 17 00:00:00 2001 From: PonomarevDA Date: Mon, 24 Apr 2023 00:11:39 +0300 Subject: [PATCH 431/652] Cyphal: divide EscClient into 2 publishers, so setpoint and readiness are 2 different ports now --- src/drivers/cyphal/Actuators/EscClient.hpp | 142 +++++++++++---------- src/drivers/cyphal/ParamManager.hpp | 3 +- src/drivers/cyphal/PublicationManager.hpp | 10 +- src/drivers/cyphal/parameters.c | 9 ++ 4 files changed, 98 insertions(+), 66 deletions(-) diff --git a/src/drivers/cyphal/Actuators/EscClient.hpp b/src/drivers/cyphal/Actuators/EscClient.hpp index c546c5b8b475..27cb715caed2 100644 --- a/src/drivers/cyphal/Actuators/EscClient.hpp +++ b/src/drivers/cyphal/Actuators/EscClient.hpp @@ -63,16 +63,14 @@ using std::isfinite; #include #include -/// TODO: Allow derived class of Subscription at same time, to handle ESC Feedback/Status -class UavcanEscController : public UavcanPublisher +class ReadinessPublisher : public UavcanPublisher { public: - static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS; - UavcanEscController(CanardHandle &handle, UavcanParamManager &pmgr) : - UavcanPublisher(handle, pmgr, "udral.", "esc") { }; + ReadinessPublisher(CanardHandle &handle, UavcanParamManager &pmgr) : + UavcanPublisher(handle, pmgr, "udral.", "readiness") { }; - ~UavcanEscController() {}; + ~ReadinessPublisher() {}; void update() override { @@ -95,58 +93,18 @@ class UavcanEscController : public UavcanPublisher if (hrt_absolute_time() > _previous_pub_time + READINESS_PUBLISH_PERIOD) { publish_readiness(); } - }; + } - void update_outputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs) - { - if (_port_id > 0) { - reg_udral_service_actuator_common_sp_Vector31_0_1 msg_sp {0}; - size_t payload_size = reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_; - - for (uint8_t i = 0; i < MAX_ACTUATORS; i++) { - if (i < num_outputs) { - msg_sp.value[i] = static_cast(outputs[i] / 8192.0); - - } else { - // "unset" values published as NaN - msg_sp.value[i] = NAN; - } - } - - uint8_t esc_sp_payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_]; - - const CanardTransferMetadata transfer_metadata = { - .priority = CanardPriorityNominal, - .transfer_kind = CanardTransferKindMessage, - .port_id = _port_id, // This is the subject-ID. - .remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET. - .transfer_id = _transfer_id, - }; - - int result = reg_udral_service_actuator_common_sp_Vector31_0_1_serialize_(&msg_sp, esc_sp_payload_buffer, - &payload_size); + static constexpr hrt_abstime READINESS_PUBLISH_PERIOD = 100000; + hrt_abstime _previous_pub_time = 0; - if (result == 0) { - // set the data ready in the buffer and chop if needed - ++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject. - result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, - &transfer_metadata, - payload_size, - &esc_sp_payload_buffer); - } - } - }; + uORB::Subscription _armed_sub{ORB_ID(actuator_armed)}; + actuator_armed_s _armed {}; - /** - * Sets the number of rotors - */ - void set_rotor_count(uint8_t count) { _rotor_count = count; } + uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)}; + uint64_t _actuator_test_timestamp{0}; -private: - /** - * ESC status message reception will be reported via this callback. - */ - void esc_status_sub_cb(const CanardRxTransfer &msg); + CanardTransferID _arming_transfer_id; void publish_readiness() { @@ -156,7 +114,7 @@ class UavcanEscController : public UavcanPublisher size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_; // Only publish if we have a valid publication ID set - if (_port_id == 0) { + if (_port_id == 0 || _port_id == CANARD_PORT_ID_UNSET) { return; } @@ -174,7 +132,7 @@ class UavcanEscController : public UavcanPublisher uint8_t arming_payload_buffer[reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_]; - CanardPortID arming_pid = static_cast(static_cast(_port_id) + 1); + CanardPortID arming_pid = static_cast(static_cast(_port_id)); const CanardTransferMetadata transfer_metadata = { .priority = CanardPriorityNominal, .transfer_kind = CanardTransferKindMessage, @@ -195,17 +153,73 @@ class UavcanEscController : public UavcanPublisher &arming_payload_buffer); } }; +}; - uint8_t _rotor_count {0}; +/// TODO: Allow derived class of Subscription at same time, to handle ESC Feedback/Status +class UavcanEscController : public UavcanPublisher +{ +public: + static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS; - static constexpr hrt_abstime READINESS_PUBLISH_PERIOD = 100000; - hrt_abstime _previous_pub_time = 0; + UavcanEscController(CanardHandle &handle, UavcanParamManager &pmgr) : + UavcanPublisher(handle, pmgr, "udral.", "esc") { }; - uORB::Subscription _armed_sub{ORB_ID(actuator_armed)}; - actuator_armed_s _armed {}; + ~UavcanEscController() {}; - uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)}; - uint64_t _actuator_test_timestamp{0}; + void update() override + { + }; - CanardTransferID _arming_transfer_id; + void update_outputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs) + { + if (_port_id > 0 && _port_id != CANARD_PORT_ID_UNSET) { + reg_udral_service_actuator_common_sp_Vector31_0_1 msg_sp {0}; + size_t payload_size = reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_; + + for (uint8_t i = 0; i < MAX_ACTUATORS; i++) { + if (i < num_outputs) { + msg_sp.value[i] = static_cast(outputs[i] / 8192.0); + + } else { + // "unset" values published as NaN + msg_sp.value[i] = NAN; + } + } + + uint8_t esc_sp_payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_]; + + const CanardTransferMetadata transfer_metadata = { + .priority = CanardPriorityNominal, + .transfer_kind = CanardTransferKindMessage, + .port_id = _port_id, // This is the subject-ID. + .remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET. + .transfer_id = _transfer_id, + }; + + int result = reg_udral_service_actuator_common_sp_Vector31_0_1_serialize_(&msg_sp, esc_sp_payload_buffer, + &payload_size); + + if (result == 0) { + // set the data ready in the buffer and chop if needed + ++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject. + result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, + &transfer_metadata, + payload_size, + &esc_sp_payload_buffer); + } + } + }; + + /** + * Sets the number of rotors + */ + void set_rotor_count(uint8_t count) { _rotor_count = count; } + +private: + /** + * ESC status message reception will be reported via this callback. + */ + void esc_status_sub_cb(const CanardRxTransfer &msg); + + uint8_t _rotor_count {0}; }; diff --git a/src/drivers/cyphal/ParamManager.hpp b/src/drivers/cyphal/ParamManager.hpp index 67c5dbc20bf6..ef7c6ba50425 100644 --- a/src/drivers/cyphal/ParamManager.hpp +++ b/src/drivers/cyphal/ParamManager.hpp @@ -116,8 +116,9 @@ class UavcanParamManager private: - const UavcanParamBinder _uavcan_params[13] { + const UavcanParamBinder _uavcan_params[14] { {"uavcan.pub.udral.esc.0.id", "UCAN1_ESC_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.pub.udral.readiness.0.id", "UCAN1_READ_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.udral.servo.0.id", "UCAN1_SERVO_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.udral.gps.0.id", "UCAN1_GPS_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.udral.actuator_outputs.0.id", "UCAN1_ACTR_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, diff --git a/src/drivers/cyphal/PublicationManager.hpp b/src/drivers/cyphal/PublicationManager.hpp index c996e797e9aa..8defb8d8f479 100644 --- a/src/drivers/cyphal/PublicationManager.hpp +++ b/src/drivers/cyphal/PublicationManager.hpp @@ -67,7 +67,7 @@ /* Preprocessor calculation of publisher count */ #define UAVCAN_PUB_COUNT CONFIG_CYPHAL_GNSS_PUBLISHER + \ - CONFIG_CYPHAL_ESC_CONTROLLER + \ + 2 * CONFIG_CYPHAL_ESC_CONTROLLER + \ CONFIG_CYPHAL_READINESS_PUBLISHER + \ CONFIG_CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER + \ CONFIG_CYPHAL_UORB_SENSOR_GPS_PUBLISHER @@ -133,6 +133,14 @@ class PublicationManager "udral.esc", 0 }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanPublisher * + { + return new ReadinessPublisher(handle, pmgr); + }, + "udral.readiness", + 0 + }, #endif #if CONFIG_CYPHAL_READINESS_PUBLISHER { diff --git a/src/drivers/cyphal/parameters.c b/src/drivers/cyphal/parameters.c index becd33fc426a..2cb06ddc2e60 100644 --- a/src/drivers/cyphal/parameters.c +++ b/src/drivers/cyphal/parameters.c @@ -162,6 +162,15 @@ PARAM_DEFINE_INT32(UCAN1_UORB_GPS_P, -1); */ PARAM_DEFINE_INT32(UCAN1_ESC_PUB, -1); +/** + * Cyphal ESC readiness port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_READ_PUB, -1); + /** * Cyphal GPS publication port ID. * From 41bd6c92e24bc2c58c55d9c85cd5a6a4121a44be Mon Sep 17 00:00:00 2001 From: PonomarevDA Date: Mon, 24 Apr 2023 01:14:28 +0300 Subject: [PATCH 432/652] Cyphal: add zubax.telega.CompactFeedback --- src/drivers/cyphal/Actuators/EscClient.hpp | 65 ++++++++++++++++++++++ src/drivers/cyphal/ParamManager.hpp | 3 +- src/drivers/cyphal/SubscriptionManager.hpp | 16 ++++++ src/drivers/cyphal/parameters.c | 9 +++ 4 files changed, 92 insertions(+), 1 deletion(-) diff --git a/src/drivers/cyphal/Actuators/EscClient.hpp b/src/drivers/cyphal/Actuators/EscClient.hpp index 27cb715caed2..c5a0c41d5b16 100644 --- a/src/drivers/cyphal/Actuators/EscClient.hpp +++ b/src/drivers/cyphal/Actuators/EscClient.hpp @@ -56,13 +56,17 @@ #include #include #include +#include "../Subscribers/DynamicPortSubscriber.hpp" +#include "../Publishers/Publisher.hpp" #include +#include // UDRAL Specification Messages using std::isfinite; #include #include + class ReadinessPublisher : public UavcanPublisher { public: @@ -223,3 +227,64 @@ class UavcanEscController : public UavcanPublisher uint8_t _rotor_count {0}; }; + +class UavcanEscFeedbackSubscriber : public UavcanDynamicPortSubscriber +{ +public: + UavcanEscFeedbackSubscriber(CanardHandle &handle, UavcanParamManager &pmgr, uint8_t instance = 0) : + UavcanDynamicPortSubscriber(handle, pmgr, "zubax.", "feedback", instance) {} + + void subscribe() override + { + _canard_handle.RxSubscribe(CanardTransferKindMessage, + _subj_sub._canard_sub.port_id, + reg_udral_service_common_Readiness_0_1_EXTENT_BYTES_, + CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, + &_subj_sub._canard_sub); + }; + + void callback(const CanardRxTransfer &receive) override + { + const ZubaxCompactFeedback* feedback = ((const ZubaxCompactFeedback*)(receive.payload)); + uint8_t esc_index = 0; + float voltage = 0.2 * feedback->dc_voltage; + float current = 0.2 * feedback->dc_current; + int32_t velocity = 0.10472 * feedback->velocity; + + mavlink_log_info(&_mavlink_log_pub, "zubax.feedback size is %d", receive.payload_size); + + if (esc_index < esc_status_s::CONNECTED_ESC_MAX) { + auto &ref = _esc_status.esc[esc_index]; + + ref.timestamp = hrt_absolute_time(); + ref.esc_address = receive.metadata.remote_node_id; + ref.esc_voltage = voltage; + ref.esc_current = current; + ref.esc_temperature = NAN; + ref.esc_rpm = velocity; + ref.esc_errorcount = 0; + + _esc_status.esc_count = 4; // _rotor_count; + _esc_status.counter += 1; + _esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_CAN; + _esc_status.esc_online_flags = 7; // check_escs_status(); + _esc_status.esc_armed_flags = 7 ; // (1 << _rotor_count) - 1; + _esc_status.timestamp = hrt_absolute_time(); + _esc_status_pub.publish(_esc_status); + } + }; + +private: + // https://telega.zubax.com/interfaces/cyphal.html#compact + struct ZubaxCompactFeedback { + uint32_t dc_voltage : 11; + int32_t dc_current : 12; + int32_t phase_current_amplitude : 12; + int32_t velocity : 13; + int8_t demand_factor_pct : 8; + }; + + esc_status_s _esc_status{}; + uORB::PublicationMulti _esc_status_pub{ORB_ID(esc_status)}; + orb_advert_t _mavlink_log_pub{nullptr}; +}; diff --git a/src/drivers/cyphal/ParamManager.hpp b/src/drivers/cyphal/ParamManager.hpp index ef7c6ba50425..3eab0818bc33 100644 --- a/src/drivers/cyphal/ParamManager.hpp +++ b/src/drivers/cyphal/ParamManager.hpp @@ -116,7 +116,7 @@ class UavcanParamManager private: - const UavcanParamBinder _uavcan_params[14] { + const UavcanParamBinder _uavcan_params[15] { {"uavcan.pub.udral.esc.0.id", "UCAN1_ESC_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.udral.readiness.0.id", "UCAN1_READ_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.udral.servo.0.id", "UCAN1_SERVO_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, @@ -131,6 +131,7 @@ class UavcanParamManager {"uavcan.sub.udral.legacy_bms.0.id", "UCAN1_LG_BMS_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.sub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS_P", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.0.id", "UCAN1_FB_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, //{"uavcan.sub.bms.0.id", "UCAN1_BMS0_SUB"}, //FIXME instancing //{"uavcan.sub.bms.1.id", "UCAN1_BMS1_SUB"}, }; diff --git a/src/drivers/cyphal/SubscriptionManager.hpp b/src/drivers/cyphal/SubscriptionManager.hpp index ce5b12a54d57..eb9609aa5e3f 100644 --- a/src/drivers/cyphal/SubscriptionManager.hpp +++ b/src/drivers/cyphal/SubscriptionManager.hpp @@ -45,6 +45,10 @@ #define CONFIG_CYPHAL_ESC_SUBSCRIBER 0 #endif +#ifndef CONFIG_CYPHAL_ESC_CONTROLLER +#define CONFIG_CYPHAL_ESC_CONTROLLER 0 +#endif + #ifndef CONFIG_CYPHAL_GNSS_SUBSCRIBER_0 #define CONFIG_CYPHAL_GNSS_SUBSCRIBER_0 0 #endif @@ -65,6 +69,7 @@ #define UAVCAN_SUB_COUNT CONFIG_CYPHAL_ESC_SUBSCRIBER + \ CONFIG_CYPHAL_GNSS_SUBSCRIBER_0 + \ + CONFIG_CYPHAL_ESC_CONTROLLER + \ CONFIG_CYPHAL_GNSS_SUBSCRIBER_1 + \ CONFIG_CYPHAL_BMS_SUBSCRIBER + \ CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER @@ -72,6 +77,7 @@ #include #include #include +#include "Actuators/EscClient.hpp" #include "Subscribers/DynamicPortSubscriber.hpp" #include "CanardInterface.hpp" @@ -132,6 +138,16 @@ class SubscriptionManager 0 }, #endif +#if CONFIG_CYPHAL_ESC_CONTROLLER + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 0); + }, + "zubax.feedback", + 0 + }, +#endif #if CONFIG_CYPHAL_GNSS_SUBSCRIBER_0 { [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * diff --git a/src/drivers/cyphal/parameters.c b/src/drivers/cyphal/parameters.c index 2cb06ddc2e60..7564b5b3ca63 100644 --- a/src/drivers/cyphal/parameters.c +++ b/src/drivers/cyphal/parameters.c @@ -171,6 +171,15 @@ PARAM_DEFINE_INT32(UCAN1_ESC_PUB, -1); */ PARAM_DEFINE_INT32(UCAN1_READ_PUB, -1); +/** + * Cyphal ESC zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB_SUB, -1); + /** * Cyphal GPS publication port ID. * From f81e36a3a092136fc7ca4f664702ed3a08933232 Mon Sep 17 00:00:00 2001 From: PonomarevDA Date: Mon, 24 Apr 2023 08:17:40 +0300 Subject: [PATCH 433/652] Cyphal: optimize ESC setpoint --- src/drivers/cyphal/Actuators/EscClient.hpp | 73 +++++++++++----------- 1 file changed, 35 insertions(+), 38 deletions(-) diff --git a/src/drivers/cyphal/Actuators/EscClient.hpp b/src/drivers/cyphal/Actuators/EscClient.hpp index c5a0c41d5b16..f4d1d81b7d4c 100644 --- a/src/drivers/cyphal/Actuators/EscClient.hpp +++ b/src/drivers/cyphal/Actuators/EscClient.hpp @@ -166,53 +166,48 @@ class UavcanEscController : public UavcanPublisher static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS; UavcanEscController(CanardHandle &handle, UavcanParamManager &pmgr) : - UavcanPublisher(handle, pmgr, "udral.", "esc") { }; + UavcanPublisher(handle, pmgr, "udral.", "esc") { } - ~UavcanEscController() {}; + ~UavcanEscController() {} void update() override { - }; + } void update_outputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs) { - if (_port_id > 0 && _port_id != CANARD_PORT_ID_UNSET) { - reg_udral_service_actuator_common_sp_Vector31_0_1 msg_sp {0}; - size_t payload_size = reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_; - - for (uint8_t i = 0; i < MAX_ACTUATORS; i++) { - if (i < num_outputs) { - msg_sp.value[i] = static_cast(outputs[i] / 8192.0); - - } else { - // "unset" values published as NaN - msg_sp.value[i] = NAN; - } - } + if (_port_id == 0 || _port_id == CANARD_PORT_ID_UNSET) { + return; + } + + uint8_t max_num_outputs = MAX_ACTUATORS > num_outputs ? num_outputs : MAX_ACTUATORS; - uint8_t esc_sp_payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_]; - - const CanardTransferMetadata transfer_metadata = { - .priority = CanardPriorityNominal, - .transfer_kind = CanardTransferKindMessage, - .port_id = _port_id, // This is the subject-ID. - .remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET. - .transfer_id = _transfer_id, - }; - - int result = reg_udral_service_actuator_common_sp_Vector31_0_1_serialize_(&msg_sp, esc_sp_payload_buffer, - &payload_size); - - if (result == 0) { - // set the data ready in the buffer and chop if needed - ++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject. - result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, - &transfer_metadata, - payload_size, - &esc_sp_payload_buffer); + for (int8_t i = max_num_outputs - 1; i >= _max_number_of_nonzero_outputs; i--) { + if (outputs[i] != 0) { + _max_number_of_nonzero_outputs = i + 1; + break; } } - }; + + uint16_t payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_value_ARRAY_CAPACITY_]; + for (uint8_t i = 0; i < _max_number_of_nonzero_outputs; i++) { + payload_buffer[i] = nunavutFloat16Pack(outputs[i] / 8192.0); + } + + const CanardTransferMetadata transfer_metadata = { + .priority = CanardPriorityNominal, + .transfer_kind = CanardTransferKindMessage, + .port_id = _port_id, + .remote_node_id = CANARD_NODE_ID_UNSET, + .transfer_id = _transfer_id, + }; + + ++_transfer_id; + _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, + &transfer_metadata, + _max_number_of_nonzero_outputs * 2, + &payload_buffer); + } /** * Sets the number of rotors @@ -225,7 +220,9 @@ class UavcanEscController : public UavcanPublisher */ void esc_status_sub_cb(const CanardRxTransfer &msg); + uint8_t _max_number_of_nonzero_outputs{1}; uint8_t _rotor_count {0}; + orb_advert_t _mavlink_log_pub{nullptr}; }; class UavcanEscFeedbackSubscriber : public UavcanDynamicPortSubscriber @@ -268,7 +265,7 @@ class UavcanEscFeedbackSubscriber : public UavcanDynamicPortSubscriber _esc_status.counter += 1; _esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_CAN; _esc_status.esc_online_flags = 7; // check_escs_status(); - _esc_status.esc_armed_flags = 7 ; // (1 << _rotor_count) - 1; + _esc_status.esc_armed_flags = 7; // (1 << _rotor_count) - 1; _esc_status.timestamp = hrt_absolute_time(); _esc_status_pub.publish(_esc_status); } From 8569eeb90c918ca3e7f4bd269035ec05538bf586 Mon Sep 17 00:00:00 2001 From: PonomarevDA Date: Mon, 24 Apr 2023 18:44:32 +0300 Subject: [PATCH 434/652] Cyphal: add *type registers for ESC --- src/drivers/cyphal/ParamManager.cpp | 33 ++++++++++++++++++++++++----- src/drivers/cyphal/ParamManager.hpp | 10 +++++++++ 2 files changed, 38 insertions(+), 5 deletions(-) diff --git a/src/drivers/cyphal/ParamManager.cpp b/src/drivers/cyphal/ParamManager.cpp index 15a57f3744ed..c792101ad46c 100644 --- a/src/drivers/cyphal/ParamManager.cpp +++ b/src/drivers/cyphal/ParamManager.cpp @@ -56,6 +56,15 @@ bool UavcanParamManager::GetParamByName(const char *param_name, uavcan_register_ } } + for (auto ¶m : _type_registers) { + if (strcmp(param_name, param.name) == 0) { + uavcan_register_Value_1_0_select_string_(&value); + value._string.value.count = strlen(param.value); + memcpy(&value._string, param.value, value._string.value.count); + return true; + } + } + return false; } @@ -73,19 +82,33 @@ bool UavcanParamManager::GetParamByName(const uavcan_register_Name_1_0 &name, ua } } + for (auto ¶m : _type_registers) { + if (strncmp((char *)name.name.elements, param.name, name.name.count) == 0) { + uavcan_register_Value_1_0_select_string_(&value); + value._string.value.count = strlen(param.value); + memcpy(&value._string, param.value, value._string.value.count); + return true; + } + } + return false; } bool UavcanParamManager::GetParamName(uint32_t id, uavcan_register_Name_1_0 &name) { - if (id >= sizeof(_uavcan_params) / sizeof(UavcanParamBinder)) { + size_t number_of_integer_registers = sizeof(_uavcan_params) / sizeof(UavcanParamBinder); + size_t number_of_type_registers = sizeof(_type_registers) / sizeof(CyphalTypeRegister); + if (id < sizeof(_uavcan_params) / sizeof(UavcanParamBinder)) { + strncpy((char *)name.name.elements, _uavcan_params[id].uavcan_name, uavcan_register_Name_1_0_name_ARRAY_CAPACITY_); + name.name.count = strlen(_uavcan_params[id].uavcan_name); + } else if (id < number_of_integer_registers + number_of_type_registers) { + id -= number_of_integer_registers; + strncpy((char *)name.name.elements, _type_registers[id].name, strlen(_type_registers[id].name)); + name.name.count = strlen(_type_registers[id].name); + } else { return false; } - strncpy((char *)name.name.elements, _uavcan_params[id].uavcan_name, uavcan_register_Name_1_0_name_ARRAY_CAPACITY_); - - name.name.count = strlen(_uavcan_params[id].uavcan_name); - return true; } diff --git a/src/drivers/cyphal/ParamManager.hpp b/src/drivers/cyphal/ParamManager.hpp index 3eab0818bc33..056be7378506 100644 --- a/src/drivers/cyphal/ParamManager.hpp +++ b/src/drivers/cyphal/ParamManager.hpp @@ -103,6 +103,10 @@ typedef struct { bool is_persistent {true}; } UavcanParamBinder; +typedef struct { + const char *name; + const char *value; +} CyphalTypeRegister; class UavcanParamManager { @@ -135,4 +139,10 @@ class UavcanParamManager //{"uavcan.sub.bms.0.id", "UCAN1_BMS0_SUB"}, //FIXME instancing //{"uavcan.sub.bms.1.id", "UCAN1_BMS1_SUB"}, }; + + CyphalTypeRegister _type_registers[3] { + {"uavcan.pub.udral.esc.0.type", "reg.udral.service.actuator.common.sp.Vector31"}, + {"uavcan.pub.udral.readiness.0.type", "reg.udral.service.common.Readiness.0.1"}, + {"uavcan.sub.zubax.feedback.0.type", "zubax.telega.CompactFeedback.0.1"}, + }; }; From 4c5ce7af6b3c1a53c419b6c5d7686d6df87f34d1 Mon Sep 17 00:00:00 2001 From: PonomarevDA Date: Thu, 4 May 2023 00:53:05 +0300 Subject: [PATCH 435/652] Cyphal: add feedback for 8 ESC --- src/drivers/cyphal/Actuators/EscClient.hpp | 109 +++++++++++---------- src/drivers/cyphal/Cyphal.cpp | 2 + src/drivers/cyphal/ParamManager.cpp | 3 + src/drivers/cyphal/ParamManager.hpp | 20 +++- src/drivers/cyphal/SubscriptionManager.hpp | 58 ++++++++++- src/drivers/cyphal/parameters.c | 67 ++++++++++++- 6 files changed, 199 insertions(+), 60 deletions(-) diff --git a/src/drivers/cyphal/Actuators/EscClient.hpp b/src/drivers/cyphal/Actuators/EscClient.hpp index f4d1d81b7d4c..8dbe2aff90ad 100644 --- a/src/drivers/cyphal/Actuators/EscClient.hpp +++ b/src/drivers/cyphal/Actuators/EscClient.hpp @@ -37,12 +37,11 @@ * Client-side implementation of UDRAL specification ESC service * * Publishes the following Cyphal messages: - * reg.drone.service.actuator.common.sp.Value8.0.1 - * reg.drone.service.common.Readiness.0.1 + * reg.udral.service.actuator.common.sp.Value31.0.1 + * reg.udral.service.common.Readiness.0.1 * * Subscribes to the following Cyphal messages: - * reg.drone.service.actuator.common.Feedback.0.1 - * reg.drone.service.actuator.common.Status.0.1 + * zubax.telega.CompactFeedback.0.1 * * @author Pavel Kirienko * @author Jacob Crabill @@ -51,7 +50,7 @@ #pragma once #include -#include +#include #include #include #include @@ -59,7 +58,6 @@ #include "../Subscribers/DynamicPortSubscriber.hpp" #include "../Publishers/Publisher.hpp" #include -#include // UDRAL Specification Messages using std::isfinite; @@ -117,7 +115,6 @@ class ReadinessPublisher : public UavcanPublisher size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_; - // Only publish if we have a valid publication ID set if (_port_id == 0 || _port_id == CANARD_PORT_ID_UNSET) { return; } @@ -140,8 +137,8 @@ class ReadinessPublisher : public UavcanPublisher const CanardTransferMetadata transfer_metadata = { .priority = CanardPriorityNominal, .transfer_kind = CanardTransferKindMessage, - .port_id = arming_pid, // This is the subject-ID. - .remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET. + .port_id = arming_pid, + .remote_node_id = CANARD_NODE_ID_UNSET, .transfer_id = _arming_transfer_id, }; @@ -149,8 +146,7 @@ class ReadinessPublisher : public UavcanPublisher &payload_size); if (result == 0) { - // set the data ready in the buffer and chop if needed - ++_arming_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject. + ++_arming_transfer_id; result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, &transfer_metadata, payload_size, @@ -159,7 +155,6 @@ class ReadinessPublisher : public UavcanPublisher }; }; -/// TODO: Allow derived class of Subscription at same time, to handle ESC Feedback/Status class UavcanEscController : public UavcanPublisher { public: @@ -190,6 +185,7 @@ class UavcanEscController : public UavcanPublisher } uint16_t payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_value_ARRAY_CAPACITY_]; + for (uint8_t i = 0; i < _max_number_of_nonzero_outputs; i++) { payload_buffer[i] = nunavutFloat16Pack(outputs[i] / 8192.0); } @@ -209,20 +205,8 @@ class UavcanEscController : public UavcanPublisher &payload_buffer); } - /** - * Sets the number of rotors - */ - void set_rotor_count(uint8_t count) { _rotor_count = count; } - private: - /** - * ESC status message reception will be reported via this callback. - */ - void esc_status_sub_cb(const CanardRxTransfer &msg); - uint8_t _max_number_of_nonzero_outputs{1}; - uint8_t _rotor_count {0}; - orb_advert_t _mavlink_log_pub{nullptr}; }; class UavcanEscFeedbackSubscriber : public UavcanDynamicPortSubscriber @@ -235,44 +219,59 @@ class UavcanEscFeedbackSubscriber : public UavcanDynamicPortSubscriber { _canard_handle.RxSubscribe(CanardTransferKindMessage, _subj_sub._canard_sub.port_id, - reg_udral_service_common_Readiness_0_1_EXTENT_BYTES_, + zubax_telega_CompactFeedback_0_1_SERIALIZATION_BUFFER_SIZE_BYTES, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, &_subj_sub._canard_sub); + _esc_status.esc_armed_flags |= 1 << _instance; + _esc_status.esc_count++; + }; + + void unsubscribe() override + { + _canard_handle.RxUnsubscribe(CanardTransferKindMessage, _subj_sub._canard_sub.port_id); + _esc_status.esc_armed_flags &= ~(1 << _instance); + _esc_status.esc_count--; }; void callback(const CanardRxTransfer &receive) override { - const ZubaxCompactFeedback* feedback = ((const ZubaxCompactFeedback*)(receive.payload)); - uint8_t esc_index = 0; - float voltage = 0.2 * feedback->dc_voltage; - float current = 0.2 * feedback->dc_current; - int32_t velocity = 0.10472 * feedback->velocity; - - mavlink_log_info(&_mavlink_log_pub, "zubax.feedback size is %d", receive.payload_size); - - if (esc_index < esc_status_s::CONNECTED_ESC_MAX) { - auto &ref = _esc_status.esc[esc_index]; - - ref.timestamp = hrt_absolute_time(); - ref.esc_address = receive.metadata.remote_node_id; - ref.esc_voltage = voltage; - ref.esc_current = current; - ref.esc_temperature = NAN; - ref.esc_rpm = velocity; - ref.esc_errorcount = 0; - - _esc_status.esc_count = 4; // _rotor_count; - _esc_status.counter += 1; - _esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_CAN; - _esc_status.esc_online_flags = 7; // check_escs_status(); - _esc_status.esc_armed_flags = 7; // (1 << _rotor_count) - 1; - _esc_status.timestamp = hrt_absolute_time(); - _esc_status_pub.publish(_esc_status); + if (_instance >= esc_status_s::CONNECTED_ESC_MAX) { + return; + } + + auto &ref = _esc_status.esc[_instance]; + const ZubaxCompactFeedback *feedback = ((const ZubaxCompactFeedback *)(receive.payload)); + + ref.timestamp = hrt_absolute_time(); + ref.esc_address = receive.metadata.remote_node_id; + ref.esc_voltage = 0.2 * feedback->dc_voltage; + ref.esc_current = 0.2 * feedback->dc_current; + ref.esc_temperature = NAN; + ref.esc_rpm = feedback->velocity * RAD_PER_SEC_TO_RPM; + ref.esc_errorcount = 0; + + _esc_status.counter++; + _esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_CAN; + _esc_status.esc_armed_flags = (1 << _esc_status.esc_count) - 1; + _esc_status.timestamp = hrt_absolute_time(); + _esc_status_pub.publish(_esc_status); + + _esc_status.esc_online_flags = 0; + const hrt_abstime now = hrt_absolute_time(); + + for (int index = 0; index < esc_status_s::CONNECTED_ESC_MAX; index++) { + if (_esc_status.esc[index].timestamp > 0 && now - _esc_status.esc[index].timestamp < 1200_ms) { + _esc_status.esc_online_flags |= (1 << index); + } } }; private: + static constexpr float RAD_PER_SEC_TO_RPM = 9.5492968; + static constexpr size_t zubax_telega_CompactFeedback_0_1_SERIALIZATION_BUFFER_SIZE_BYTES = 7; + // https://telega.zubax.com/interfaces/cyphal.html#compact +#pragma pack(push, 1) struct ZubaxCompactFeedback { uint32_t dc_voltage : 11; int32_t dc_current : 12; @@ -280,8 +279,10 @@ class UavcanEscFeedbackSubscriber : public UavcanDynamicPortSubscriber int32_t velocity : 13; int8_t demand_factor_pct : 8; }; +#pragma pack(pop) + static_assert(sizeof(ZubaxCompactFeedback) == zubax_telega_CompactFeedback_0_1_SERIALIZATION_BUFFER_SIZE_BYTES); + + static esc_status_s _esc_status; - esc_status_s _esc_status{}; - uORB::PublicationMulti _esc_status_pub{ORB_ID(esc_status)}; - orb_advert_t _mavlink_log_pub{nullptr}; + uORB::Publication _esc_status_pub{ORB_ID(esc_status)}; }; diff --git a/src/drivers/cyphal/Cyphal.cpp b/src/drivers/cyphal/Cyphal.cpp index 94030971b54e..5a288274cf5d 100644 --- a/src/drivers/cyphal/Cyphal.cpp +++ b/src/drivers/cyphal/Cyphal.cpp @@ -62,6 +62,8 @@ using namespace time_literals; CyphalNode *CyphalNode::_instance; +esc_status_s UavcanEscFeedbackSubscriber::_esc_status; + CyphalNode::CyphalNode(uint32_t node_id, size_t capacity, size_t mtu_bytes) : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::uavcan), diff --git a/src/drivers/cyphal/ParamManager.cpp b/src/drivers/cyphal/ParamManager.cpp index c792101ad46c..0dba575cde1d 100644 --- a/src/drivers/cyphal/ParamManager.cpp +++ b/src/drivers/cyphal/ParamManager.cpp @@ -98,13 +98,16 @@ bool UavcanParamManager::GetParamName(uint32_t id, uavcan_register_Name_1_0 &nam { size_t number_of_integer_registers = sizeof(_uavcan_params) / sizeof(UavcanParamBinder); size_t number_of_type_registers = sizeof(_type_registers) / sizeof(CyphalTypeRegister); + if (id < sizeof(_uavcan_params) / sizeof(UavcanParamBinder)) { strncpy((char *)name.name.elements, _uavcan_params[id].uavcan_name, uavcan_register_Name_1_0_name_ARRAY_CAPACITY_); name.name.count = strlen(_uavcan_params[id].uavcan_name); + } else if (id < number_of_integer_registers + number_of_type_registers) { id -= number_of_integer_registers; strncpy((char *)name.name.elements, _type_registers[id].name, strlen(_type_registers[id].name)); name.name.count = strlen(_type_registers[id].name); + } else { return false; } diff --git a/src/drivers/cyphal/ParamManager.hpp b/src/drivers/cyphal/ParamManager.hpp index 056be7378506..e1330c4e5f31 100644 --- a/src/drivers/cyphal/ParamManager.hpp +++ b/src/drivers/cyphal/ParamManager.hpp @@ -120,7 +120,7 @@ class UavcanParamManager private: - const UavcanParamBinder _uavcan_params[15] { + const UavcanParamBinder _uavcan_params[22] { {"uavcan.pub.udral.esc.0.id", "UCAN1_ESC_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.udral.readiness.0.id", "UCAN1_READ_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.udral.servo.0.id", "UCAN1_SERVO_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, @@ -135,14 +135,28 @@ class UavcanParamManager {"uavcan.sub.udral.legacy_bms.0.id", "UCAN1_LG_BMS_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.sub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, {"uavcan.pub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS_P", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, - {"uavcan.sub.zubax.feedback.0.id", "UCAN1_FB_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.0.id", "UCAN1_FB0_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.1.id", "UCAN1_FB1_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.2.id", "UCAN1_FB2_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.3.id", "UCAN1_FB3_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.4.id", "UCAN1_FB4_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.5.id", "UCAN1_FB5_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.6.id", "UCAN1_FB6_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, + {"uavcan.sub.zubax.feedback.7.id", "UCAN1_FB7_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param}, //{"uavcan.sub.bms.0.id", "UCAN1_BMS0_SUB"}, //FIXME instancing //{"uavcan.sub.bms.1.id", "UCAN1_BMS1_SUB"}, }; - CyphalTypeRegister _type_registers[3] { + CyphalTypeRegister _type_registers[10] { {"uavcan.pub.udral.esc.0.type", "reg.udral.service.actuator.common.sp.Vector31"}, {"uavcan.pub.udral.readiness.0.type", "reg.udral.service.common.Readiness.0.1"}, {"uavcan.sub.zubax.feedback.0.type", "zubax.telega.CompactFeedback.0.1"}, + {"uavcan.sub.zubax.feedback.1.type", "zubax.telega.CompactFeedback.0.1"}, + {"uavcan.sub.zubax.feedback.2.type", "zubax.telega.CompactFeedback.0.1"}, + {"uavcan.sub.zubax.feedback.3.type", "zubax.telega.CompactFeedback.0.1"}, + {"uavcan.sub.zubax.feedback.4.type", "zubax.telega.CompactFeedback.0.1"}, + {"uavcan.sub.zubax.feedback.5.type", "zubax.telega.CompactFeedback.0.1"}, + {"uavcan.sub.zubax.feedback.6.type", "zubax.telega.CompactFeedback.0.1"}, + {"uavcan.sub.zubax.feedback.7.type", "zubax.telega.CompactFeedback.0.1"}, }; }; diff --git a/src/drivers/cyphal/SubscriptionManager.hpp b/src/drivers/cyphal/SubscriptionManager.hpp index eb9609aa5e3f..c9218d2f886c 100644 --- a/src/drivers/cyphal/SubscriptionManager.hpp +++ b/src/drivers/cyphal/SubscriptionManager.hpp @@ -69,7 +69,7 @@ #define UAVCAN_SUB_COUNT CONFIG_CYPHAL_ESC_SUBSCRIBER + \ CONFIG_CYPHAL_GNSS_SUBSCRIBER_0 + \ - CONFIG_CYPHAL_ESC_CONTROLLER + \ + 8 * CONFIG_CYPHAL_ESC_CONTROLLER + \ CONFIG_CYPHAL_GNSS_SUBSCRIBER_1 + \ CONFIG_CYPHAL_BMS_SUBSCRIBER + \ CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER @@ -147,6 +147,62 @@ class SubscriptionManager "zubax.feedback", 0 }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 1); + }, + "zubax.feedback", + 1 + }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 2); + }, + "zubax.feedback", + 2 + }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 3); + }, + "zubax.feedback", + 3 + }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 4); + }, + "zubax.feedback", + 4 + }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 5); + }, + "zubax.feedback", + 5 + }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 6); + }, + "zubax.feedback", + 6 + }, + { + [](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanDynamicPortSubscriber * + { + return new UavcanEscFeedbackSubscriber(handle, pmgr, 7); + }, + "zubax.feedback", + 7 + }, #endif #if CONFIG_CYPHAL_GNSS_SUBSCRIBER_0 { diff --git a/src/drivers/cyphal/parameters.c b/src/drivers/cyphal/parameters.c index 7564b5b3ca63..4731f1c14e9c 100644 --- a/src/drivers/cyphal/parameters.c +++ b/src/drivers/cyphal/parameters.c @@ -172,13 +172,76 @@ PARAM_DEFINE_INT32(UCAN1_ESC_PUB, -1); PARAM_DEFINE_INT32(UCAN1_READ_PUB, -1); /** - * Cyphal ESC zubax feedback port ID. + * Cyphal ESC 0 zubax feedback port ID. * * @min -1 * @max 6143 * @group Cyphal */ -PARAM_DEFINE_INT32(UCAN1_FB_SUB, -1); +PARAM_DEFINE_INT32(UCAN1_FB0_SUB, -1); + +/** + * Cyphal ESC 1 zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB1_SUB, -1); + +/** + * Cyphal ESC 2 zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB2_SUB, -1); + +/** + * Cyphal ESC 3 zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB3_SUB, -1); + +/** + * Cyphal ESC 4 zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB4_SUB, -1); + +/** + * Cyphal ESC 5 zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB5_SUB, -1); + +/** + * Cyphal ESC 6 zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB6_SUB, -1); + +/** + * Cyphal ESC 7 zubax feedback port ID. + * + * @min -1 + * @max 6143 + * @group Cyphal + */ +PARAM_DEFINE_INT32(UCAN1_FB7_SUB, -1); /** * Cyphal GPS publication port ID. From 1f33abb4e964d3e9c69bb71c0f84f456054a821b Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 4 Jul 2024 11:57:26 +0200 Subject: [PATCH 436/652] battery_status.msg: remove unused fields (#22938) Signed-off-by: Silvan Fuhrer --- msg/BatteryStatus.msg | 4 ---- 1 file changed, 4 deletions(-) diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index d0beda6dbc9d..00d2efef4c5d 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -66,12 +66,8 @@ uint8 BATTERY_MODE_COUNT = 3 # Counter - keep it as last element (once we're ful uint8 MAX_INSTANCES = 4 -float32 average_power # The average power of the current discharge -float32 available_energy # The predicted charge or energy remaining in the battery float32 full_charge_capacity_wh # The compensated battery capacity float32 remaining_capacity_wh # The compensated battery capacity remaining -float32 design_capacity # The design capacity of the battery -uint16 average_time_to_full # The predicted remaining time until the battery reaches full charge, in minutes uint16 over_discharge_count # Number of battery overdischarge float32 nominal_voltage # Nominal voltage of the battery pack From a1f43636f314f05791c97d2915111bab89a82c5a Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Fri, 5 Jul 2024 03:17:19 +0200 Subject: [PATCH 437/652] ekf2: EV fusion in body frame (#23191) --- .../init.d/airframes/4061_atl_mantis_edu | 1 + .../init.d/airframes/4901_crazyflie21 | 1 + .../external_vision/ev_vel_control.cpp | 206 +++++++++++++----- src/modules/ekf2/EKF/ekf.h | 8 + .../EKF/python/ekf_derivation/derivation.py | 37 ++++ .../generated/compute_ev_body_vel_hx.h | 63 ++++++ .../generated/compute_ev_body_vel_hy.h | 67 ++++++ .../generated/compute_ev_body_vel_hz.h | 63 ++++++ .../ekf2/test/test_EKF_externalVision.cpp | 25 +-- 9 files changed, 393 insertions(+), 78 deletions(-) create mode 100644 src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hx.h create mode 100644 src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hy.h create mode 100644 src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hz.h diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index 95df14d54ec0..27bd8397758c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -7,6 +7,7 @@ # # @maintainer # @board px4_fmu-v2 exclude +# @board px4_fmu-v6x exclude # . ${R}etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 index d16230d3583c..4833d17af23c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -13,6 +13,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board px4_fmu-v6x exclude # @board diatone_mamba-f405-mk2 exclude # . ${R}etc/init.d/rc.mc_defaults diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp index e612452b762b..c338b75ba136 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp @@ -37,6 +37,9 @@ */ #include "ekf.h" +#include +#include +#include void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src) @@ -57,14 +60,16 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body; // rotate measurement into correct earth frame if required - Vector3f vel{NAN, NAN, NAN}; - Matrix3f vel_cov{}; + Vector3f measurement{}; + Vector3f measurement_var{}; + + float minimum_variance = math::max(sq(0.01f), sq(_params.ev_vel_noise)); switch (ev_sample.vel_frame) { case VelocityFrame::LOCAL_FRAME_NED: if (_control_status.flags.yaw_align) { - vel = ev_sample.vel - vel_offset_earth; - vel_cov = matrix::diag(ev_sample.velocity_var); + measurement = ev_sample.vel - vel_offset_earth; + measurement_var = ev_sample.velocity_var; } else { continuing_conditions_passing = false; @@ -75,31 +80,28 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common case VelocityFrame::LOCAL_FRAME_FRD: if (_control_status.flags.ev_yaw) { // using EV frame - vel = ev_sample.vel - vel_offset_earth; - vel_cov = matrix::diag(ev_sample.velocity_var); + measurement = ev_sample.vel - vel_offset_earth; + measurement_var = ev_sample.velocity_var; } else { // rotate EV to the EKF reference frame const Dcmf R_ev_to_ekf = Dcmf(_ev_q_error_filt.getState()); - vel = R_ev_to_ekf * ev_sample.vel - vel_offset_earth; - vel_cov = R_ev_to_ekf * matrix::diag(ev_sample.velocity_var) * R_ev_to_ekf.transpose(); - - // increase minimum variance to include EV orientation variance - // TODO: do this properly - const float orientation_var_max = ev_sample.orientation_var.max(); - - for (int i = 0; i < 2; i++) { - vel_cov(i, i) = math::max(vel_cov(i, i), orientation_var_max); - } + measurement = R_ev_to_ekf * ev_sample.vel - vel_offset_earth; + measurement_var = matrix::SquareMatrix3f(R_ev_to_ekf * matrix::diag(ev_sample.velocity_var) * + R_ev_to_ekf.transpose()).diag(); + minimum_variance = math::max(minimum_variance, ev_sample.orientation_var.max()); } break; - case VelocityFrame::BODY_FRAME_FRD: - vel = _R_to_earth * (ev_sample.vel - vel_offset_body); - vel_cov = _R_to_earth * matrix::diag(ev_sample.velocity_var) * _R_to_earth.transpose(); - break; + case VelocityFrame::BODY_FRAME_FRD: { + + // currently it is assumed that the orientation of the EV frame and the body frame are the same + measurement = ev_sample.vel - vel_offset_body; + measurement_var = ev_sample.velocity_var; + break; + } default: continuing_conditions_passing = false; @@ -111,48 +113,56 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common // increase minimum variance if GPS active (position reference) if (_control_status.flags.gps) { for (int i = 0; i < 2; i++) { - vel_cov(i, i) = math::max(vel_cov(i, i), sq(_params.gps_vel_noise)); + measurement_var(i) = math::max(measurement_var(i), sq(_params.gps_vel_noise)); } } #endif // CONFIG_EKF2_GNSS - const Vector3f measurement{vel}; - - const Vector3f measurement_var{ - math::max(vel_cov(0, 0), sq(_params.ev_vel_noise), sq(0.01f)), - math::max(vel_cov(1, 1), sq(_params.ev_vel_noise), sq(0.01f)), - math::max(vel_cov(2, 2), sq(_params.ev_vel_noise), sq(0.01f)) + measurement_var = Vector3f{ + math::max(measurement_var(0), minimum_variance), + math::max(measurement_var(1), minimum_variance), + math::max(measurement_var(2), minimum_variance) }; + continuing_conditions_passing &= measurement.isAllFinite() && measurement_var.isAllFinite(); + + if (ev_sample.vel_frame == VelocityFrame::BODY_FRAME_FRD) { + const Vector3f measurement_var_ekf_frame = rotateVarianceToEkf(measurement_var); + const Vector3f measurement_ekf_frame = _R_to_earth * measurement; + const uint64_t t = aid_src.timestamp_sample; + updateAidSourceStatus(aid_src, + ev_sample.time_us, // sample timestamp + measurement_ekf_frame, // observation + measurement_var_ekf_frame, // observation variance + _state.vel - measurement_ekf_frame, // innovation + getVelocityVariance() + measurement_var_ekf_frame, // innovation variance + math::max(_params.ev_vel_innov_gate, 1.f)); // innovation gate + aid_src.timestamp_sample = t; + measurement.copyTo(aid_src.observation); + measurement_var.copyTo(aid_src.observation_variance); - const bool measurement_valid = measurement.isAllFinite() && measurement_var.isAllFinite(); - - updateAidSourceStatus(aid_src, - ev_sample.time_us, // sample timestamp - measurement, // observation - measurement_var, // observation variance - _state.vel - measurement, // innovation - getVelocityVariance() + measurement_var, // innovation variance - math::max(_params.ev_vel_innov_gate, 1.f)); // innovation gate - - if (!measurement_valid) { - continuing_conditions_passing = false; + } else { + updateAidSourceStatus(aid_src, + ev_sample.time_us, // sample timestamp + measurement, // observation + measurement_var, // observation variance + _state.vel - measurement, // innovation + getVelocityVariance() + measurement_var, // innovation variance + math::max(_params.ev_vel_innov_gate, 1.f)); // innovation gate } + const bool starting_conditions_passing = common_starting_conditions_passing && continuing_conditions_passing && ((Vector3f(aid_src.test_ratio).max() < 0.1f) || !isHorizontalAidingActive()); if (_control_status.flags.ev_vel) { - if (continuing_conditions_passing) { - if ((ev_reset && isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.ev_vel)) || yaw_alignment_changed) { - if (quality_sufficient) { ECL_INFO("reset to %s", AID_SRC_NAME); _information_events.flags.reset_vel_to_vision = true; - resetVelocityTo(measurement, measurement_var); + resetVelocityToEV(measurement, measurement_var, ev_sample.vel_frame); resetAidSourceStatusZeroInnovation(aid_src); } else { @@ -163,7 +173,7 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common } } else if (quality_sufficient) { - fuseVelocity(aid_src); + fuseEvVelocity(aid_src, ev_sample); } else { aid_src.innovation_rejected = true; @@ -177,24 +187,27 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common // Data seems good, attempt a reset _information_events.flags.reset_vel_to_vision = true; ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); - resetVelocityTo(measurement, measurement_var); + resetVelocityToEV(measurement, measurement_var, ev_sample.vel_frame); resetAidSourceStatusZeroInnovation(aid_src); if (_control_status.flags.in_air) { _nb_ev_vel_reset_available--; } - } else if (starting_conditions_passing) { - // Data seems good, but previous reset did not fix the issue - // something else must be wrong, declare the sensor faulty and stop the fusion - //_control_status.flags.ev_vel_fault = true; - ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); - stopEvVelFusion(); - } else { - // A reset did not fix the issue but all the starting checks are not passing - // This could be a temporary issue, stop the fusion without declaring the sensor faulty - ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); + // differ warning message based on whether the starting conditions are passing + if (starting_conditions_passing) { + // Data seems good, but previous reset did not fix the issue + // something else must be wrong, declare the sensor faulty and stop the fusion + //_control_status.flags.ev_vel_fault = true; + ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); + + } else { + // A reset did not fix the issue but all the starting checks are not passing + // This could be a temporary issue, stop the fusion without declaring the sensor faulty + ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); + } + stopEvVelFusion(); } } @@ -211,15 +224,13 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common if (!isHorizontalAidingActive() || yaw_alignment_changed) { ECL_INFO("starting %s fusion, resetting velocity to (%.3f, %.3f, %.3f)", AID_SRC_NAME, (double)measurement(0), (double)measurement(1), (double)measurement(2)); - _information_events.flags.reset_vel_to_vision = true; - - resetVelocityTo(measurement, measurement_var); + resetVelocityToEV(measurement, measurement_var, ev_sample.vel_frame); resetAidSourceStatusZeroInnovation(aid_src); _control_status.flags.ev_vel = true; - } else if (fuseVelocity(aid_src)) { + } else if (fuseEvVelocity(aid_src, ev_sample)) { ECL_INFO("starting %s fusion", AID_SRC_NAME); _control_status.flags.ev_vel = true; } @@ -232,6 +243,63 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common } } +bool Ekf::fuseEvVelocity(estimator_aid_source3d_s &aid_src, const extVisionSample &ev_sample) +{ + if (ev_sample.vel_frame == VelocityFrame::BODY_FRAME_FRD) { + + VectorState H; + estimator_aid_source1d_s current_aid_src; + const auto state_vector = _state.vector(); + + for (uint8_t index = 0; index <= 2; index++) { + current_aid_src.timestamp_sample = aid_src.timestamp_sample; + + if (index == 0) { + sym::ComputeEvBodyVelHx(state_vector, &H); + + } else if (index == 1) { + sym::ComputeEvBodyVelHy(state_vector, &H); + + } else { + sym::ComputeEvBodyVelHz(state_vector, &H); + } + + const float innov_var = (H.T() * P * H)(0, 0) + aid_src.observation_variance[index]; + const float innov = (_R_to_earth.transpose() * _state.vel - Vector3f(aid_src.observation))(index, 0); + + updateAidSourceStatus(current_aid_src, + ev_sample.time_us, // sample timestamp + aid_src.observation[index], // observation + aid_src.observation_variance[index], // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.ev_vel_innov_gate, 1.f)); // innovation gate + + if (!current_aid_src.innovation_rejected) { + fuseBodyVelocity(current_aid_src, current_aid_src.innovation_variance, H); + + } + + aid_src.innovation[index] = current_aid_src.innovation; + aid_src.innovation_variance[index] = current_aid_src.innovation_variance; + aid_src.test_ratio[index] = current_aid_src.test_ratio; + aid_src.fused = current_aid_src.fused; + aid_src.innovation_rejected |= current_aid_src.innovation_rejected; + + if (aid_src.fused) { + aid_src.time_last_fuse = _time_delayed_us; + } + + } + + aid_src.timestamp_sample = current_aid_src.timestamp_sample; + return !aid_src.innovation_rejected; + + } else { + return fuseVelocity(aid_src); + } +} + void Ekf::stopEvVelFusion() { if (_control_status.flags.ev_vel) { @@ -239,3 +307,23 @@ void Ekf::stopEvVelFusion() _control_status.flags.ev_vel = false; } } + +void Ekf::resetVelocityToEV(const Vector3f &measurement, const Vector3f &measurement_var, + const VelocityFrame &vel_frame) +{ + if (vel_frame == VelocityFrame::BODY_FRAME_FRD) { + const Vector3f measurement_var_ekf_frame = rotateVarianceToEkf(measurement_var); + resetVelocityTo(_R_to_earth * measurement, measurement_var_ekf_frame); + + } else { + resetVelocityTo(measurement, measurement_var); + } + +} + +Vector3f Ekf::rotateVarianceToEkf(const Vector3f &measurement_var) +{ + // rotate the covariance matrix into the EKF frame + const matrix::SquareMatrix R_cov = _R_to_earth * matrix::diag(measurement_var) * _R_to_earth.transpose(); + return R_cov.diag(); +} diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 2a23d1d283b4..f7c4ee2dcfc6 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -921,6 +921,8 @@ class Ekf final : public EstimatorInterface void controlEvPosFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source2d_s &aid_src); void controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src); void controlEvYawFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src); + void resetVelocityToEV(const Vector3f &measurement, const Vector3f &measurement_var, const VelocityFrame &vel_frame); + Vector3f rotateVarianceToEkf(const Vector3f &measurement_var); void startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, estimator_aid_source2d_s &aid_src); void updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, bool reset, estimator_aid_source2d_s &aid_src); @@ -928,6 +930,12 @@ class Ekf final : public EstimatorInterface void stopEvHgtFusion(); void stopEvVelFusion(); void stopEvYawFusion(); + bool fuseEvVelocity(estimator_aid_source3d_s &aid_src, const extVisionSample &ev_sample); + void fuseBodyVelocity(estimator_aid_source1d_s &aid_src, float &innov_var, VectorState &H) + { + VectorState Kfusion = P * H / innov_var; + aid_src.fused = measurementUpdate(Kfusion, H, aid_src.observation_variance, aid_src.innovation); + } #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_GNSS) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py index 4d8b5278dbcf..a206ea62954c 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py @@ -362,6 +362,40 @@ def compute_sideslip_h_and_k( return (H.T, K) +def predict_vel_body( + state: VState +) -> (sf.V3): + vel = state["vel"] + R_to_body = state["quat_nominal"].inverse() + return R_to_body * vel + +def compute_ev_body_vel_hx( + state: VState, +) -> (VTangent): + + state = vstate_to_state(state) + meas_pred = predict_vel_body(state) + Hx = jacobian_chain_rule(meas_pred[0], state) + return (Hx.T) + +def compute_ev_body_vel_hy( + state: VState, +) -> (VTangent): + + state = vstate_to_state(state) + meas_pred = predict_vel_body(state)[1] + Hy = jacobian_chain_rule(meas_pred, state) + return (Hy.T) + +def compute_ev_body_vel_hz( + state: VState, +) -> (VTangent): + + state = vstate_to_state(state) + meas_pred = predict_vel_body(state)[2] + Hz = jacobian_chain_rule(meas_pred, state) + return (Hz.T) + def predict_mag_body(state) -> sf.V3: mag_field_earth = state["mag_I"] mag_bias_body = state["mag_B"] @@ -697,5 +731,8 @@ def compute_gravity_z_innov_var_and_h( generate_px4_function(compute_gravity_xyz_innov_var_and_hx, output_names=["innov_var", "Hx"]) generate_px4_function(compute_gravity_y_innov_var_and_h, output_names=["innov_var", "Hy"]) generate_px4_function(compute_gravity_z_innov_var_and_h, output_names=["innov_var", "Hz"]) +generate_px4_function(compute_ev_body_vel_hx, output_names=["H"]) +generate_px4_function(compute_ev_body_vel_hy, output_names=["H"]) +generate_px4_function(compute_ev_body_vel_hz, output_names=["H"]) generate_px4_state(State, tangent_idx) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hx.h new file mode 100644 index 000000000000..72a2adf0f67a --- /dev/null +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hx.h @@ -0,0 +1,63 @@ +// ----------------------------------------------------------------------------- +// This file was autogenerated by symforce from template: +// function/FUNCTION.h.jinja +// Do NOT modify by hand. +// ----------------------------------------------------------------------------- + +#pragma once + +#include + +namespace sym { + +/** + * This function was autogenerated from a symbolic function. Do not modify by hand. + * + * Symbolic function: compute_ev_body_vel_hx + * + * Args: + * state: Matrix25_1 + * + * Outputs: + * H: Matrix24_1 + */ +template +void ComputeEvBodyVelHx(const matrix::Matrix& state, + matrix::Matrix* const H = nullptr) { + // Total ops: 60 + + // Input arrays + + // Intermediate terms (13) + const Scalar _tmp0 = 2 * state(5, 0); + const Scalar _tmp1 = 2 * state(6, 0); + const Scalar _tmp2 = _tmp0 * state(3, 0) - _tmp1 * state(2, 0); + const Scalar _tmp3 = (Scalar(1) / Scalar(2)) * state(1, 0); + const Scalar _tmp4 = + (Scalar(1) / Scalar(2)) * _tmp0 * state(2, 0) + (Scalar(1) / Scalar(2)) * _tmp1 * state(3, 0); + const Scalar _tmp5 = 4 * state(4, 0); + const Scalar _tmp6 = 2 * state(1, 0); + const Scalar _tmp7 = _tmp0 * state(0, 0) - _tmp5 * state(3, 0) + _tmp6 * state(6, 0); + const Scalar _tmp8 = (Scalar(1) / Scalar(2)) * _tmp7; + const Scalar _tmp9 = 2 * state(0, 0); + const Scalar _tmp10 = _tmp0 * state(1, 0) - _tmp5 * state(2, 0) - _tmp9 * state(6, 0); + const Scalar _tmp11 = (Scalar(1) / Scalar(2)) * _tmp10; + const Scalar _tmp12 = (Scalar(1) / Scalar(2)) * _tmp2; + + // Output terms (1) + if (H != nullptr) { + matrix::Matrix& _h = (*H); + + _h.setZero(); + + _h(0, 0) = -_tmp11 * state(3, 0) - _tmp2 * _tmp3 + _tmp4 * state(0, 0) + _tmp8 * state(2, 0); + _h(1, 0) = _tmp11 * state(0, 0) - _tmp12 * state(2, 0) - _tmp3 * _tmp7 + _tmp4 * state(3, 0); + _h(2, 0) = _tmp10 * _tmp3 - _tmp12 * state(3, 0) - _tmp4 * state(2, 0) + _tmp8 * state(0, 0); + _h(3, 0) = -2 * std::pow(state(2, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; + _h(4, 0) = _tmp6 * state(2, 0) + _tmp9 * state(3, 0); + _h(5, 0) = _tmp6 * state(3, 0) - _tmp9 * state(2, 0); + } +} // NOLINT(readability/fn_size) + +// NOLINTNEXTLINE(readability/fn_size) +} // namespace sym diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hy.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hy.h new file mode 100644 index 000000000000..a4dd6f94d94c --- /dev/null +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hy.h @@ -0,0 +1,67 @@ +// ----------------------------------------------------------------------------- +// This file was autogenerated by symforce from template: +// function/FUNCTION.h.jinja +// Do NOT modify by hand. +// ----------------------------------------------------------------------------- + +#pragma once + +#include + +namespace sym { + +/** + * This function was autogenerated from a symbolic function. Do not modify by hand. + * + * Symbolic function: compute_ev_body_vel_hy + * + * Args: + * state: Matrix25_1 + * + * Outputs: + * H: Matrix24_1 + */ +template +void ComputeEvBodyVelHy(const matrix::Matrix& state, + matrix::Matrix* const H = nullptr) { + // Total ops: 64 + + // Input arrays + + // Intermediate terms (9) + const Scalar _tmp0 = 2 * state(4, 0); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = + -Scalar(1) / Scalar(2) * _tmp0 * state(3, 0) + (Scalar(1) / Scalar(2)) * _tmp1 * state(6, 0); + const Scalar _tmp3 = 2 * state(3, 0); + const Scalar _tmp4 = + (Scalar(1) / Scalar(2)) * _tmp0 * state(1, 0) + (Scalar(1) / Scalar(2)) * _tmp3 * state(6, 0); + const Scalar _tmp5 = 4 * state(5, 0); + const Scalar _tmp6 = 2 * state(6, 0); + const Scalar _tmp7 = -Scalar(1) / Scalar(2) * _tmp0 * state(0, 0) - + Scalar(1) / Scalar(2) * _tmp5 * state(3, 0) + + (Scalar(1) / Scalar(2)) * _tmp6 * state(2, 0); + const Scalar _tmp8 = (Scalar(1) / Scalar(2)) * _tmp0 * state(2, 0) - + Scalar(1) / Scalar(2) * _tmp5 * state(1, 0) + + (Scalar(1) / Scalar(2)) * _tmp6 * state(0, 0); + + // Output terms (1) + if (H != nullptr) { + matrix::Matrix& _h = (*H); + + _h.setZero(); + + _h(0, 0) = + -_tmp2 * state(1, 0) - _tmp4 * state(3, 0) + _tmp7 * state(2, 0) + _tmp8 * state(0, 0); + _h(1, 0) = + -_tmp2 * state(2, 0) + _tmp4 * state(0, 0) - _tmp7 * state(1, 0) + _tmp8 * state(3, 0); + _h(2, 0) = + -_tmp2 * state(3, 0) + _tmp4 * state(1, 0) + _tmp7 * state(0, 0) - _tmp8 * state(2, 0); + _h(3, 0) = _tmp1 * state(2, 0) - _tmp3 * state(0, 0); + _h(4, 0) = -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; + _h(5, 0) = _tmp1 * state(0, 0) + _tmp3 * state(2, 0); + } +} // NOLINT(readability/fn_size) + +// NOLINTNEXTLINE(readability/fn_size) +} // namespace sym diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hz.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hz.h new file mode 100644 index 000000000000..395bb85b4a2e --- /dev/null +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_ev_body_vel_hz.h @@ -0,0 +1,63 @@ +// ----------------------------------------------------------------------------- +// This file was autogenerated by symforce from template: +// function/FUNCTION.h.jinja +// Do NOT modify by hand. +// ----------------------------------------------------------------------------- + +#pragma once + +#include + +namespace sym { + +/** + * This function was autogenerated from a symbolic function. Do not modify by hand. + * + * Symbolic function: compute_ev_body_vel_hz + * + * Args: + * state: Matrix25_1 + * + * Outputs: + * H: Matrix24_1 + */ +template +void ComputeEvBodyVelHz(const matrix::Matrix& state, + matrix::Matrix* const H = nullptr) { + // Total ops: 60 + + // Input arrays + + // Intermediate terms (13) + const Scalar _tmp0 = 2 * state(4, 0); + const Scalar _tmp1 = 2 * state(5, 0); + const Scalar _tmp2 = + (Scalar(1) / Scalar(2)) * _tmp0 * state(1, 0) + (Scalar(1) / Scalar(2)) * _tmp1 * state(2, 0); + const Scalar _tmp3 = _tmp0 * state(2, 0) - _tmp1 * state(1, 0); + const Scalar _tmp4 = (Scalar(1) / Scalar(2)) * _tmp3; + const Scalar _tmp5 = 4 * state(6, 0); + const Scalar _tmp6 = _tmp0 * state(3, 0) - _tmp1 * state(0, 0) - _tmp5 * state(1, 0); + const Scalar _tmp7 = (Scalar(1) / Scalar(2)) * _tmp6; + const Scalar _tmp8 = _tmp0 * state(0, 0) + _tmp1 * state(3, 0) - _tmp5 * state(2, 0); + const Scalar _tmp9 = (Scalar(1) / Scalar(2)) * state(3, 0); + const Scalar _tmp10 = (Scalar(1) / Scalar(2)) * _tmp8; + const Scalar _tmp11 = 2 * state(2, 0); + const Scalar _tmp12 = 2 * state(1, 0); + + // Output terms (1) + if (H != nullptr) { + matrix::Matrix& _h = (*H); + + _h.setZero(); + + _h(0, 0) = _tmp2 * state(2, 0) - _tmp4 * state(1, 0) + _tmp7 * state(0, 0) - _tmp8 * _tmp9; + _h(1, 0) = _tmp10 * state(0, 0) - _tmp2 * state(1, 0) - _tmp4 * state(2, 0) + _tmp6 * _tmp9; + _h(2, 0) = _tmp10 * state(1, 0) + _tmp2 * state(0, 0) - _tmp3 * _tmp9 - _tmp7 * state(2, 0); + _h(3, 0) = _tmp11 * state(0, 0) + _tmp12 * state(3, 0); + _h(4, 0) = _tmp11 * state(3, 0) - _tmp12 * state(0, 0); + _h(5, 0) = -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(2, 0), Scalar(2)) + 1; + } +} // NOLINT(readability/fn_size) + +// NOLINTNEXTLINE(readability/fn_size) +} // namespace sym diff --git a/src/modules/ekf2/test/test_EKF_externalVision.cpp b/src/modules/ekf2/test/test_EKF_externalVision.cpp index 734d485fbcd3..5b1439edd9f2 100644 --- a/src/modules/ekf2/test/test_EKF_externalVision.cpp +++ b/src/modules/ekf2/test/test_EKF_externalVision.cpp @@ -259,37 +259,24 @@ TEST_F(EkfExternalVisionTest, visionAlignment) TEST_F(EkfExternalVisionTest, velocityFrameBody) { - // GIVEN: Drone is turned 90 degrees - const Quatf quat_sim(Eulerf(0.0f, 0.0f, math::radians(90.0f))); - _sensor_simulator.simulateOrientation(quat_sim); + _ekf_wrapper.setMagFuseTypeNone(); _sensor_simulator.runSeconds(_tilt_align_time); - _ekf->set_vehicle_at_rest(false); - // Without any measurement x and y velocity variance are close - const Vector3f velVar_init = _ekf->getVelocityVariance(); - EXPECT_NEAR(velVar_init(0), velVar_init(1), 0.0001); - - // WHEN: measurement is given in BODY-FRAME and - // x variance is bigger than y variance - _sensor_simulator._vio.setVelocityFrameToBody(); + float yaw_var0 = _ekf->getYawVar(); const Vector3f vel_cov_body(2.0f, 0.01f, 0.01f); const Vector3f vel_body(1.0f, 0.0f, 0.0f); + _sensor_simulator._vio.setVelocityFrameToBody(); _sensor_simulator._vio.setVelocityVariance(vel_cov_body); _sensor_simulator._vio.setVelocity(vel_body); _ekf_wrapper.enableExternalVisionVelocityFusion(); _sensor_simulator.startExternalVision(); _sensor_simulator.runSeconds(4); - // THEN: As the drone is turned 90 degrees, velocity variance - // along local y axis is expected to be bigger - const Vector3f velVar_new = _ekf->getVelocityVariance(); - EXPECT_NEAR(velVar_new(1) / velVar_new(0), 30.f, 15.f); - - const Vector3f vel_earth_est = _ekf->getVelocity(); - EXPECT_NEAR(vel_earth_est(0), 0.0f, 0.1f); - EXPECT_NEAR(vel_earth_est(1), 1.0f, 0.1f); + const Vector3f vel_var = _ekf->getVelocityVariance(); + EXPECT_TRUE(yaw_var0 < _ekf->getYawVar()); + EXPECT_TRUE(vel_var(1) < vel_var(0)); } TEST_F(EkfExternalVisionTest, velocityFrameLocal) From fd8df2e84d04ac9fff36ece9eda1c5a0a432bc69 Mon Sep 17 00:00:00 2001 From: Ryan Johnston <31726584+ryanjAA@users.noreply.github.com> Date: Fri, 5 Jul 2024 04:04:45 -0500 Subject: [PATCH 438/652] Update int_res_est_replay.py (#23351) Pulls cell count, min voltage and max voltage from log file but still allows for over-rides. Also added debug info to tell user what what it found in the log and what it is using Co-authored-by: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> --- src/lib/battery/int_res_est_replay.py | 40 ++++++++++++++++++++++++--- 1 file changed, 36 insertions(+), 4 deletions(-) diff --git a/src/lib/battery/int_res_est_replay.py b/src/lib/battery/int_res_est_replay.py index 2ed092d6c791..336dba474478 100644 --- a/src/lib/battery/int_res_est_replay.py +++ b/src/lib/battery/int_res_est_replay.py @@ -19,6 +19,13 @@ def getData(log, topic_name, variable_name, instance=0): def us2s(time_us): return time_us * 1e-6 +def getParam(log, param_name): + if param_name in log.initial_parameters: + return log.initial_parameters[param_name] + else: + print(f"Parameter {param_name} not found in log.") + return None + def rls_update(theta, P, x, V, I, lam): gamma = P @ x / (lam + x.T @ P @ x) error = V - x.T @ theta @@ -33,6 +40,31 @@ def rls_update(theta, P, x, V, I, lam): def main(log_name, n_cells, full_cell, empty_cell, lam): log = ULog(log_name) + + log_n_cells = getParam(log, 'BAT1_N_CELLS') + log_full_cell = getParam(log, 'BAT1_V_CHARGED') + log_empty_cell = getParam(log, 'BAT1_V_EMPTY') + + # Debug information + print(f"Extracted from log - BAT1_N_CELLS: {log_n_cells}, BAT1_V_CHARGED: {log_full_cell}, BAT1_V_EMPTY: {log_empty_cell}") + + # Use log parameters unless overridden + if n_cells is None: + n_cells = log_n_cells + else: + print(f"Using override for n_cells: {n_cells}") + if full_cell is None: + full_cell = log_full_cell + else: + print(f"Using override for full_cell: {full_cell}") + if empty_cell is None: + empty_cell = log_empty_cell + else: + print(f"Using override for empty_cell: {empty_cell}") + + # Debug information for final parameter values + print(f"Using parameters - n_cells: {n_cells}, full_cell: {full_cell}, empty_cell: {empty_cell}") + timestamps = us2s(getData(log, 'battery_status', 'timestamp')) I = getData(log, 'battery_status', 'current_a') V = getData(log, 'battery_status', 'voltage_v') @@ -79,7 +111,7 @@ def main(log_name, n_cells, full_cell, empty_cell, lam): data_cov_hist[index] = data_cov internal_resistance_stable[index] = max(R_est[index]/n_cells, 0.001) - ## Plot data + # Plot data print("Internal Resistance mean (per cell): ", np.mean(R_est) / n_cells) # Summary plot @@ -168,9 +200,9 @@ def main(log_name, n_cells, full_cell, empty_cell, lam): if __name__ == "__main__": parser = argparse.ArgumentParser(description='Estimate battery parameters from ulog file.') parser.add_argument('-f', type = str, required = True, help = 'Full path to ulog file') - parser.add_argument('-c', type = float, required = True, help = 'Number of cells in battery') - parser.add_argument('-u', type = float, required = False, default = 4.05, help = 'Full cell voltage') - parser.add_argument('-e', type = float, required = False, default = 3.6, help = 'Empty cell voltage') + parser.add_argument('-c', type = float, required = False, help = 'Number of cells in battery') + parser.add_argument('-u', type = float, required = False, default = None, help = 'Full cell voltage') + parser.add_argument('-e', type = float, required = False, default = None, help = 'Empty cell voltage') parser.add_argument('-l', type = float, required = False, default = 0.99, help = 'Forgetting factor') args = parser.parse_args() main(args.f, args.c, args.u, args.e, args.l) From ac1effa32a4bc4541481778295d4a0d0c213f86f Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 3 Jul 2024 15:41:26 +0200 Subject: [PATCH 439/652] fmu-v6xrt: MTD use full FRAM (32KB) --- boards/px4/fmu-v6xrt/src/mtd.cpp | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/boards/px4/fmu-v6xrt/src/mtd.cpp b/boards/px4/fmu-v6xrt/src/mtd.cpp index 38fa63a7eda3..68f79e4897e8 100644 --- a/boards/px4/fmu-v6xrt/src/mtd.cpp +++ b/boards/px4/fmu-v6xrt/src/mtd.cpp @@ -53,18 +53,12 @@ static const px4_mft_device_t i2c6 = { // 24LC64T on BASE 8K 32 X 2 static const px4_mtd_entry_t fmum_fram = { .device = &qspi_flash, - .npart = 2, + .npart = 1, .partd = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 32 - }, - { - .type = MTD_WAYPOINTS, - .path = "/fs/mtd_waypoints", - .nblocks = 32 - + .nblocks = 256 } }, }; From e04c53241a44a60e8644da14dfc815d3c012d98f Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Sun, 7 Jul 2024 22:43:55 +0200 Subject: [PATCH 440/652] EKF2: reset position by fusion (#23279) * reset position by fusion * handle local_pos_valid for fixed wing in gnss denied * [WIP] ekf2: setEkfGlobalOrigin respect current height reference and vertical position aiding * global origin, also reset vertical pos without gps as ref * fix wo gnss, that bitcraze ci passes * revert some changes as requested * remove duplicate reset messages * undo unrelated whitespace changes, I'll fix it everywhere in a followup * [SQUASH] ekf2: add vehicle_command_ack * resetGlobalPosToExternalObservation consolidate logic * remove gnss check from local_pos validation check * reset when 0 --- .../init.d/airframes/4061_atl_mantis_edu | 1 + .../EKF/aid_sources/ZeroVelocityUpdate.cpp | 6 +- .../EKF/aid_sources/ZeroVelocityUpdate.hpp | 4 +- .../ekf2/EKF/aid_sources/fake_pos_control.cpp | 10 +- src/modules/ekf2/EKF/ekf.cpp | 63 ++++++++-- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF/ekf_helper.cpp | 115 ++++++++++++------ src/modules/ekf2/EKF2.cpp | 36 +++++- src/modules/ekf2/EKF2.hpp | 5 +- src/modules/ekf2/test/test_EKF_gps.cpp | 2 +- 10 files changed, 179 insertions(+), 65 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index 27bd8397758c..66d0973caa52 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -7,6 +7,7 @@ # # @maintainer # @board px4_fmu-v2 exclude +# @board px4_fmu-v5x exclude # @board px4_fmu-v6x exclude # diff --git a/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.cpp b/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.cpp index 48d07d583dac..052e37312c02 100644 --- a/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.cpp +++ b/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.cpp @@ -42,13 +42,13 @@ ZeroVelocityUpdate::ZeroVelocityUpdate() void ZeroVelocityUpdate::reset() { - _time_last_zero_velocity_fuse = 0; + _time_last_fuse = 0; } bool ZeroVelocityUpdate::update(Ekf &ekf, const estimator::imuSample &imu_delayed) { // Fuse zero velocity at a limited rate (every 200 milliseconds) - const bool zero_velocity_update_data_ready = (_time_last_zero_velocity_fuse + 200'000 < imu_delayed.time_us); + const bool zero_velocity_update_data_ready = (_time_last_fuse + 200'000 < imu_delayed.time_us); if (zero_velocity_update_data_ready) { const bool continuing_conditions_passing = ekf.control_status_flags().vehicle_at_rest @@ -69,7 +69,7 @@ bool ZeroVelocityUpdate::update(Ekf &ekf, const estimator::imuSample &imu_delaye ekf.fuseDirectStateMeasurement(innovation, innov_var(i), obs_var, State::vel.idx + i); } - _time_last_zero_velocity_fuse = imu_delayed.time_us; + _time_last_fuse = imu_delayed.time_us; return true; } diff --git a/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.hpp b/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.hpp index 0016c584c6ec..a591d9dc96f1 100644 --- a/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.hpp +++ b/src/modules/ekf2/EKF/aid_sources/ZeroVelocityUpdate.hpp @@ -45,9 +45,11 @@ class ZeroVelocityUpdate : public EstimatorAidSource void reset() override; bool update(Ekf &ekf, const estimator::imuSample &imu_delayed) override; + const auto &time_last_fuse() const { return _time_last_fuse; } + private: - uint64_t _time_last_zero_velocity_fuse{0}; ///< last time of zero velocity update (uSec) + uint64_t _time_last_fuse{0}; ///< last time of zero velocity update (uSec) }; diff --git a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp index 33f05ac68e8f..9ea6485e64fd 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp @@ -75,15 +75,13 @@ void Ekf::controlFakePosFusion() Vector2f(getStateVariance()) + obs_var, // innovation variance innov_gate); // innovation gate - const bool continuing_conditions_passing = !isHorizontalAidingActive() + const bool enable_conditions_passing = !isHorizontalAidingActive() && ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest) - && (!(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest); - - const bool starting_conditions_passing = continuing_conditions_passing + && (!(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest) && _horizontal_deadreckon_time_exceeded; if (_control_status.flags.fake_pos) { - if (continuing_conditions_passing) { + if (enable_conditions_passing) { // always protect against extreme values that could result in a NaN if ((aid_src.test_ratio[0] < sq(100.0f / innov_gate)) @@ -104,7 +102,7 @@ void Ekf::controlFakePosFusion() } } else { - if (starting_conditions_passing) { + if (enable_conditions_passing) { ECL_INFO("start fake position fusion"); _control_status.flags.fake_pos = true; resetFakePosFusion(); diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 1571aa06ca86..983db8aa8612 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -281,23 +281,66 @@ 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; } -void Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation) +bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation) { if (!_pos_ref.isInitialized()) { - return; + ECL_WARN("unable to reset global position, position reference not initialized"); + return false; + } + + Vector2f pos_corrected = _pos_ref.project(lat_deg, lon_deg); + + // 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)) { + + timestamp_observation = math::min(_time_latest_us, timestamp_observation); + + float diff_us = 0.f; + + if (_time_delayed_us >= timestamp_observation) { + diff_us = static_cast(_time_delayed_us - timestamp_observation); + + } else { + diff_us = -static_cast(timestamp_observation - _time_delayed_us); + } + + const float dt_s = diff_us * 1e-6f; + pos_corrected += _state.vel.xy() * dt_s; } - // apply a first order correction using velocity at the delated time horizon and the delta time - timestamp_observation = math::min(_time_latest_us, timestamp_observation); - const float dt = _time_delayed_us > timestamp_observation ? static_cast(_time_delayed_us - timestamp_observation) - * 1e-6f : -static_cast(timestamp_observation - _time_delayed_us) * 1e-6f; + const float obs_var = math::max(accuracy, sq(0.01f)); - Vector2f pos_corrected = _pos_ref.project(lat_deg, lon_deg) + _state.vel.xy() * dt; + const Vector2f innov = Vector2f(_state.pos.xy()) - pos_corrected; + const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; - resetHorizontalPositionTo(pos_corrected, sq(math::max(accuracy, 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))}; - ECL_INFO("reset position to external observation"); - _information_events.flags.reset_pos_to_ext_obs = true; + const bool innov_rejected = (test_ratio.max() > 1.f); + + 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; + + resetHorizontalPositionTo(pos_corrected, obs_var); + _last_known_pos.xy() = _state.pos.xy(); + return 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"); + _time_last_hor_pos_fuse = _time_delayed_us; + _last_known_pos.xy() = _state.pos.xy(); + return true; + } + } + + return false; } void Ekf::updateParameters() diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index f7c4ee2dcfc6..966a45a650f5 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -501,7 +501,7 @@ class Ekf final : public EstimatorInterface return true; } - void resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation); + bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation); void updateParameters(); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 94b1046dbaec..791ed89e2672 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -89,7 +89,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons current_pos_available = true; } - const float gps_alt_ref_prev = getEkfGlobalOriginAltitude(); + const float gps_alt_ref_prev = _gps_alt_ref; // reinitialize map projection to latitude, longitude, altitude, and reset position _pos_ref.initReference(latitude, longitude, _time_delayed_us); @@ -114,30 +114,24 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons _NED_origin_initialised = true; - // minimum change in position or height that triggers a reset - static constexpr float MIN_RESET_DIST_M = 0.01f; - if (current_pos_available) { - // reset horizontal position + // reset horizontal position if we already have a global origin Vector2f position = _pos_ref.project(current_lat, current_lon); - - if (Vector2f(position - Vector2f(_state.pos)).longerThan(MIN_RESET_DIST_M)) { - resetHorizontalPositionTo(position); - } + resetHorizontalPositionTo(position); } - // reset vertical position (if there's any change) - if (fabsf(altitude - gps_alt_ref_prev) > MIN_RESET_DIST_M) { + if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { // determine current z - float current_alt = -_state.pos(2) + gps_alt_ref_prev; - + const float z_prev = _state.pos(2); + const float current_alt = -z_prev + gps_alt_ref_prev; #if defined(CONFIG_EKF2_GNSS) const float gps_hgt_bias = _gps_hgt_b_est.getBias(); #endif // CONFIG_EKF2_GNSS resetVerticalPositionTo(_gps_alt_ref - current_alt); - + ECL_DEBUG("EKF global origin updated, resetting vertical position %.1fm -> %.1fm", (double)z_prev, + (double)_state.pos(2)); #if defined(CONFIG_EKF2_GNSS) - // preserve GPS height bias + // adjust existing GPS height bias _gps_hgt_b_est.setBias(gps_hgt_bias); #endif // CONFIG_EKF2_GNSS } @@ -574,44 +568,91 @@ void Ekf::updateDeadReckoningStatus() void Ekf::updateHorizontalDeadReckoningstatus() { - const bool velPosAiding = (_control_status.flags.gps || _control_status.flags.ev_pos || _control_status.flags.ev_vel || _control_status.flags.aux_gpos) - && (isRecent(_time_last_hor_pos_fuse, _params.no_aid_timeout_max) - || isRecent(_time_last_hor_vel_fuse, _params.no_aid_timeout_max)); + bool inertial_dead_reckoning = true; + bool aiding_expected_in_air = false; + + // velocity aiding active + if ((_control_status.flags.gps || _control_status.flags.ev_vel) + && isRecent(_time_last_hor_vel_fuse, _params.no_aid_timeout_max) + ) { + inertial_dead_reckoning = false; + } + + // position aiding active + if ((_control_status.flags.gps || _control_status.flags.ev_pos || _control_status.flags.aux_gpos) + && isRecent(_time_last_hor_pos_fuse, _params.no_aid_timeout_max) + ) { + inertial_dead_reckoning = false; + } - bool optFlowAiding = false; #if defined(CONFIG_EKF2_OPTICAL_FLOW) - optFlowAiding = _control_status.flags.opt_flow && isRecent(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max); -#endif // CONFIG_EKF2_OPTICAL_FLOW + // optical flow active + if (_control_status.flags.opt_flow + && isRecent(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max) + ) { + inertial_dead_reckoning = false; - bool airDataAiding = false; + } else { + if (!_control_status.flags.in_air && (_params.flow_ctrl == 1) + && isRecent(_aid_src_optical_flow.timestamp_sample, _params.no_aid_timeout_max) + ) { + // currently landed, but optical flow aiding should be possible once in air + aiding_expected_in_air = true; + } + } +#endif // CONFIG_EKF2_OPTICAL_FLOW #if defined(CONFIG_EKF2_AIRSPEED) - airDataAiding = _control_status.flags.wind && - isRecent(_aid_src_airspeed.time_last_fuse, _params.no_aid_timeout_max) && - isRecent(_aid_src_sideslip.time_last_fuse, _params.no_aid_timeout_max); + // air data aiding active + if ((_control_status.flags.fuse_aspd && isRecent(_aid_src_airspeed.time_last_fuse, _params.no_aid_timeout_max)) + && (_control_status.flags.fuse_beta && isRecent(_aid_src_sideslip.time_last_fuse, _params.no_aid_timeout_max)) + ) { + // wind_dead_reckoning: no other aiding but air data + _control_status.flags.wind_dead_reckoning = inertial_dead_reckoning; - _control_status.flags.wind_dead_reckoning = !velPosAiding && !optFlowAiding && airDataAiding; -#else - _control_status.flags.wind_dead_reckoning = false; + // air data aiding is active, we're not inertial dead reckoning + inertial_dead_reckoning = false; + + } else { + _control_status.flags.wind_dead_reckoning = false; + + if (!_control_status.flags.in_air && _control_status.flags.fixed_wing + && (_params.beta_fusion_enabled == 1) + && (_params.arsp_thr > 0.f) && isRecent(_aid_src_airspeed.timestamp_sample, _params.no_aid_timeout_max) + ) { + // currently landed, but air data aiding should be possible once in air + aiding_expected_in_air = true; + } + } #endif // CONFIG_EKF2_AIRSPEED - _control_status.flags.inertial_dead_reckoning = !velPosAiding && !optFlowAiding && !airDataAiding; + // zero velocity update + if (isRecent(_zero_velocity_update.time_last_fuse(), _params.no_aid_timeout_max)) { + // only respect as a valid aiding source now if we expect to have another valid source once in air + if (aiding_expected_in_air) { + inertial_dead_reckoning = false; + } + } - if (!_control_status.flags.inertial_dead_reckoning) { + if (inertial_dead_reckoning) { + if (isTimedOut(_time_last_horizontal_aiding, (uint64_t)_params.valid_timeout_max)) { + // deadreckon time exceeded + if (!_horizontal_deadreckon_time_exceeded) { + ECL_WARN("horizontal dead reckon time exceeded"); + _horizontal_deadreckon_time_exceeded = true; + } + } + + } else { if (_time_delayed_us > _params.no_aid_timeout_max) { _time_last_horizontal_aiding = _time_delayed_us - _params.no_aid_timeout_max; } - } - // report if we have been deadreckoning for too long, initial state is deadreckoning until aiding is present - bool deadreckon_time_exceeded = isTimedOut(_time_last_horizontal_aiding, (uint64_t)_params.valid_timeout_max); + _horizontal_deadreckon_time_exceeded = false; - if (!_horizontal_deadreckon_time_exceeded && deadreckon_time_exceeded) { - // deadreckon time now exceeded - ECL_WARN("dead reckon time exceeded"); } - _horizontal_deadreckon_time_exceeded = deadreckon_time_exceeded; + _control_status.flags.inertial_dead_reckoning = inertial_dead_reckoning; } void Ekf::updateVerticalDeadReckoningStatus() diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 17d55ab740b4..362c68c372ad 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -497,6 +497,12 @@ void EKF2::Run() vehicle_command_s vehicle_command; if (_vehicle_command_sub.update(&vehicle_command)) { + + vehicle_command_ack_s command_ack{}; + command_ack.command = vehicle_command.command; + command_ack.target_system = vehicle_command.source_system; + command_ack.target_component = vehicle_command.source_component; + if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN) { double latitude = vehicle_command.param5; double longitude = vehicle_command.param6; @@ -509,15 +515,23 @@ void EKF2::Run() PX4_INFO("%d - New NED origin (LLA): %3.10f, %3.10f, %4.3f\n", _instance, latitude, longitude, static_cast(altitude)); + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; + } else { PX4_ERR("%d - Failed to set new NED origin (LLA): %3.10f, %3.10f, %4.3f\n", _instance, latitude, longitude, static_cast(altitude)); + + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED; } - } - if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE) { + command_ack.timestamp = hrt_absolute_time(); + _vehicle_command_ack_pub.publish(command_ack); + + } else if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE) { + if ((_ekf.control_status_flags().wind_dead_reckoning || _ekf.control_status_flags().inertial_dead_reckoning) && - PX4_ISFINITE(vehicle_command.param2) && PX4_ISFINITE(vehicle_command.param5) && PX4_ISFINITE(vehicle_command.param6)) { + PX4_ISFINITE(vehicle_command.param2) && PX4_ISFINITE(vehicle_command.param5) && PX4_ISFINITE(vehicle_command.param6) + ) { const float measurement_delay_seconds = math::constrain(vehicle_command.param2, 0.0f, kMaxDelaySecondsExternalPosMeasurement); @@ -530,9 +544,21 @@ void EKF2::Run() } // TODO add check for lat and long validity - _ekf.resetGlobalPosToExternalObservation(vehicle_command.param5, vehicle_command.param6, - accuracy, timestamp_observation); + if (_ekf.resetGlobalPosToExternalObservation(vehicle_command.param5, vehicle_command.param6, + accuracy, timestamp_observation) + ) { + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; + + } else { + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED; + } + + } else { + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; // TODO: expand } + + command_ack.timestamp = hrt_absolute_time(); + _vehicle_command_ack_pub.publish(command_ack); } } } diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 2de08049cb53..3bc2b99f953d 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -78,6 +78,7 @@ #include #include #include +#include #include #include #include @@ -387,9 +388,11 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)}; uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; - uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; + uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; + uORB::Publication _vehicle_command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::SubscriptionCallbackWorkItem _sensor_combined_sub{this, ORB_ID(sensor_combined)}; uORB::SubscriptionCallbackWorkItem _vehicle_imu_sub{this, ORB_ID(vehicle_imu)}; diff --git a/src/modules/ekf2/test/test_EKF_gps.cpp b/src/modules/ekf2/test/test_EKF_gps.cpp index 0e243176a2af..b03a8701d52a 100644 --- a/src/modules/ekf2/test/test_EKF_gps.cpp +++ b/src/modules/ekf2/test/test_EKF_gps.cpp @@ -105,7 +105,7 @@ TEST_F(EkfGpsTest, gpsFixLoss) _sensor_simulator._gps.setFixType(0); // THEN: after dead-reconing for a couple of seconds, the local position gets invalidated - _sensor_simulator.runSeconds(5); + _sensor_simulator.runSeconds(6); EXPECT_TRUE(_ekf->control_status_flags().inertial_dead_reckoning); EXPECT_FALSE(_ekf->local_position_is_valid()); From 4bc0286eb82df4ec90d1d063ba2c4a2061468442 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Mon, 8 Jul 2024 13:55:05 +0200 Subject: [PATCH 441/652] fix error from refactring commit, fix reset on ground (#23370) --- src/modules/ekf2/EKF/ekf.cpp | 4 ++-- src/modules/ekf2/EKF2.cpp | 5 +++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 983db8aa8612..ac410b4d8d64 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -308,10 +308,10 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl pos_corrected += _state.vel.xy() * dt_s; } - const float obs_var = math::max(accuracy, sq(0.01f)); + const float obs_var = math::max(sq(accuracy), sq(0.01f)); const Vector2f innov = Vector2f(_state.pos.xy()) - pos_corrected; - const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; + const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; const float sq_gate = sq(5.f); // magic hardcoded gate const Vector2f test_ratio{sq(innov(0)) / (sq_gate * innov_var(0)), diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 362c68c372ad..c42a499e0961 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -529,8 +529,9 @@ void EKF2::Run() } else if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE) { - if ((_ekf.control_status_flags().wind_dead_reckoning || _ekf.control_status_flags().inertial_dead_reckoning) && - PX4_ISFINITE(vehicle_command.param2) && PX4_ISFINITE(vehicle_command.param5) && PX4_ISFINITE(vehicle_command.param6) + if ((_ekf.control_status_flags().wind_dead_reckoning || _ekf.control_status_flags().inertial_dead_reckoning + || (!_ekf.control_status_flags().in_air && !_ekf.control_status_flags().gps)) && PX4_ISFINITE(vehicle_command.param2) + && PX4_ISFINITE(vehicle_command.param5) && PX4_ISFINITE(vehicle_command.param6) ) { const float measurement_delay_seconds = math::constrain(vehicle_command.param2, 0.0f, From aed0fd41cf2a1f85893576718e534db5656be519 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Mon, 8 Jul 2024 14:51:08 +0200 Subject: [PATCH 442/652] SIH - change how LAT and LON is used for Takeoff location (#23363) change how lat long is used for SIH --- .../init.d-posix/px4-rc.simulator | 3 +++ src/modules/simulation/simulator_sih/sih.cpp | 4 ++-- src/modules/simulation/simulator_sih/sih.hpp | 4 ++-- .../simulation/simulator_sih/sih_params.c | 20 +++++++++---------- 4 files changed, 16 insertions(+), 15 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator index 8121f3914c2a..76be887e84bb 100644 --- a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator +++ b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator @@ -15,6 +15,9 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0" if [ -n "${PX4_HOME_LON}" ]; then param set SIH_LOC_LON0 ${PX4_HOME_LON} fi + if [ -n "${PX4_HOME_ALT}" ]; then + param set SIH_LOC_H0 ${PX4_HOME_ALT} + fi if simulator_sih start; then diff --git a/src/modules/simulation/simulator_sih/sih.cpp b/src/modules/simulation/simulator_sih/sih.cpp index 1fa076568be5..399a4ecc938d 100644 --- a/src/modules/simulation/simulator_sih/sih.cpp +++ b/src/modules/simulation/simulator_sih/sih.cpp @@ -243,8 +243,8 @@ void Sih::parameters_updated() _KDW = _sih_kdw.get(); _H0 = _sih_h0.get(); - _LAT0 = (double)_sih_lat0.get() * 1.0e-7; - _LON0 = (double)_sih_lon0.get() * 1.0e-7; + _LAT0 = (double)_sih_lat0.get(); + _LON0 = (double)_sih_lon0.get(); _COS_LAT0 = cosl((long double)radians(_LAT0)); _MASS = _sih_mass.get(); diff --git a/src/modules/simulation/simulator_sih/sih.hpp b/src/modules/simulation/simulator_sih/sih.hpp index a4227978be6b..8988474e01b1 100644 --- a/src/modules/simulation/simulator_sih/sih.hpp +++ b/src/modules/simulation/simulator_sih/sih.hpp @@ -273,8 +273,8 @@ class Sih : public ModuleBase, public ModuleParams (ParamFloat) _sih_l_pitch, (ParamFloat) _sih_kdv, (ParamFloat) _sih_kdw, - (ParamInt) _sih_lat0, - (ParamInt) _sih_lon0, + (ParamFloat) _sih_lat0, + (ParamFloat) _sih_lon0, (ParamFloat) _sih_h0, (ParamFloat) _sih_distance_snsr_min, (ParamFloat) _sih_distance_snsr_max, diff --git a/src/modules/simulation/simulator_sih/sih_params.c b/src/modules/simulation/simulator_sih/sih_params.c index 60dd336a9bde..16c58430f63e 100644 --- a/src/modules/simulation/simulator_sih/sih_params.c +++ b/src/modules/simulation/simulator_sih/sih_params.c @@ -235,33 +235,31 @@ PARAM_DEFINE_FLOAT(SIH_KDW, 0.025f); * Initial geodetic latitude * * This value represents the North-South location on Earth where the simulation begins. - * A value of 45 deg should be written 450000000. * * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others * to represent a physical ground location on Earth. * - * @unit deg*1e7 - * @min -850000000 - * @max 850000000 + * @unit deg + * @min -90 + * @max 90 * @group Simulation In Hardware */ -PARAM_DEFINE_INT32(SIH_LOC_LAT0, 454671160); +PARAM_DEFINE_FLOAT(SIH_LOC_LAT0, 47.397742f); /** * Initial geodetic longitude * * This value represents the East-West location on Earth where the simulation begins. - * A value of 45 deg should be written 450000000. * * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others * to represent a physical ground location on Earth. * - * @unit deg*1e7 - * @min -1800000000 - * @max 1800000000 + * @unit deg + * @min -180 + * @max 180 * @group Simulation In Hardware */ -PARAM_DEFINE_INT32(SIH_LOC_LON0, -737578370); +PARAM_DEFINE_FLOAT(SIH_LOC_LON0, 8.545594f); /** * Initial AMSL ground altitude @@ -282,7 +280,7 @@ PARAM_DEFINE_INT32(SIH_LOC_LON0, -737578370); * @increment 0.01 * @group Simulation In Hardware */ -PARAM_DEFINE_FLOAT(SIH_LOC_H0, 32.34f); +PARAM_DEFINE_FLOAT(SIH_LOC_H0, 489.4f); /** * distance sensor minimum range From 77709c29487c5e8788ce7b28dd969e08b3bd94bf Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 12 Jun 2024 09:46:02 +0200 Subject: [PATCH 443/652] FW Position control: clean up param descriptions Mostly to save flash, but also to improve generally. Signed-off-by: Silvan Fuhrer --- .../fw_performance_model/PerformanceModel.hpp | 1 - .../FixedwingPositionControl.hpp | 1 - .../fw_path_navigation_params.c | 147 ++++++------------ 3 files changed, 51 insertions(+), 98 deletions(-) diff --git a/src/lib/fw_performance_model/PerformanceModel.hpp b/src/lib/fw_performance_model/PerformanceModel.hpp index c283fd4d01ab..fbdd8693c21d 100644 --- a/src/lib/fw_performance_model/PerformanceModel.hpp +++ b/src/lib/fw_performance_model/PerformanceModel.hpp @@ -131,7 +131,6 @@ class PerformanceModel : public ModuleParams (ParamFloat) _param_weight_gross, (ParamFloat) _param_service_ceiling, (ParamFloat) _param_fw_thr_trim, - (ParamFloat) _param_fw_thr_idle, (ParamFloat) _param_fw_thr_max, (ParamFloat) _param_fw_thr_min, (ParamFloat) _param_fw_thr_aspd_min, diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index eb4216048367..3f2398f340c4 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -990,7 +990,6 @@ class FixedwingPositionControl final : public ModuleBase) _param_fw_flaps_lnd_scl, (ParamFloat) _param_fw_flaps_to_scl, (ParamFloat) _param_fw_spoilers_lnd, - (ParamFloat) _param_fw_spoilers_desc, (ParamInt) _param_fw_pos_stk_conf, diff --git a/src/modules/fw_pos_control/fw_path_navigation_params.c b/src/modules/fw_pos_control/fw_path_navigation_params.c index 7666167452de..a5d9c851f3bd 100644 --- a/src/modules/fw_pos_control/fw_path_navigation_params.c +++ b/src/modules/fw_pos_control/fw_path_navigation_params.c @@ -193,9 +193,9 @@ PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f); PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); /** - * Minimum pitch angle + * Minimum pitch angle setpoint * - * The minimum pitch angle setpoint for a height-rate or altitude controlled mode. + * Applies in any altitude controlled flight mode. * * @unit deg * @min -60.0 @@ -207,9 +207,9 @@ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f); /** - * Maximum pitch angle + * Maximum pitch angle setpoint * - * The maximum pitch angle setpoint setpoint for a height-rate or altitude controlled mode. + * Applies in any altitude controlled flight mode. * * @unit deg * @min 0.0 @@ -221,9 +221,9 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f); PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 30.0f); /** - * Maximum roll angle + * Maximum roll angle setpoint * - * The maximum roll angle setpoint for setpoint for a height-rate or altitude controlled mode. + * Applies in any altitude controlled flight mode. * * @unit deg * @min 35.0 @@ -237,7 +237,7 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f); /** * Throttle limit max * - * Maximum throttle limit in altitude controlled modes. + * Applies in any altitude controlled flight mode. * Should be set accordingly to achieve FW_T_CLMB_MAX. * * @unit norm @@ -252,13 +252,10 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); /** * Throttle limit min * - * Minimum throttle limit in altitude controlled modes. + * Applies in any altitude controlled flight mode. * Usually set to 0 but can be increased to prevent the motor from stopping when * descending, which can increase achievable descent rates. * - * For aircraft with internal combustion engine this parameter should be set - * for desired idle rpm. - * * @unit norm * @min 0.0 * @max 1.0 @@ -271,13 +268,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); /** * Idle throttle * - * This is the minimum throttle while on the ground - * - * For aircraft with internal combustion engines, this parameter should be set - * above the desired idle rpm. For electric motors, idle should typically be set - * to zero. - * - * Note that in automatic modes, "landed" conditions will engage idle throttle. + * This is the minimum throttle while on the ground ("landed") in auto modes. * * @unit norm * @min 0.0 @@ -318,9 +309,9 @@ PARAM_DEFINE_FLOAT(FW_TKO_PITCH_MIN, 10.0f); /** * Takeoff Airspeed * - * The calibrated airspeed setpoint TECS will stabilize to during the takeoff climbout. + * The calibrated airspeed setpoint during the takeoff climbout. * - * If set <= 0.0, FW_AIRSPD_MIN will be set by default. + * If set <= 0, FW_AIRSPD_MIN will be set by default. * * @unit m/s * @min -1.0 @@ -344,7 +335,9 @@ PARAM_DEFINE_FLOAT(FW_TKO_AIRSPD, -1.0f); PARAM_DEFINE_FLOAT(FW_LND_FLALT, 0.5f); /** - * Use terrain estimation during landing. This is critical for detecting when to flare, and should be enabled if possible. + * Use terrain estimation during landing. + * + * This is critical for detecting when to flare, and should be enabled if possible. * * NOTE: terrain estimate is currently solely derived from a distance sensor. * @@ -365,9 +358,9 @@ PARAM_DEFINE_INT32(FW_LND_USETER, 1); /** * Early landing configuration deployment * - * When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated - * on the final approach to landing. When enabled, it is already activated when entering the - * final loiter-down (loiter-to-alt) waypoint before the landing approach. + * Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in + * the loiter-down waypoint before the final approach. + * Otherwise is enabled only in the final approach. * * @boolean * @@ -378,8 +371,7 @@ PARAM_DEFINE_INT32(FW_LND_EARLYCFG, 0); /** * Flare, minimum pitch * - * Minimum pitch during flare, a positive sign means nose up - * Applied once flaring is triggered + * Minimum pitch during landing flare. * * @unit deg * @min -5 @@ -393,8 +385,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f); /** * Flare, maximum pitch * - * Maximum pitch during flare, a positive sign means nose up - * Applied once flaring is triggered + * Maximum pitch during landing flare. * * @unit deg * @min 0 @@ -410,7 +401,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f); * * The calibrated airspeed setpoint during landing. * - * If set <= 0.0, landing airspeed = FW_AIRSPD_MIN by default. + * If set <= 0, landing airspeed = FW_AIRSPD_MIN by default. * * @unit m/s * @min -1.0 @@ -423,9 +414,8 @@ PARAM_DEFINE_FLOAT(FW_LND_AIRSPD, -1.f); /** * Altitude time constant factor for landing * - * Set this parameter to less than 1.0 to make TECS react faster to altitude errors during - * landing than during normal flight. During landing, the TECS - * altitude time constant (FW_T_ALT_TC) is multiplied by this value. + * During landing, the TECS altitude time constant (FW_T_ALT_TC) + * is multiplied by this value. * * @unit * @min 0.2 @@ -445,10 +435,6 @@ PARAM_DEFINE_FLOAT(FW_LND_THRTC_SC, 1.0f); * Maximum descent rate * * This sets the maximum descent rate that the controller will use. - * If this value is too large, the aircraft can over-speed on descent. - * This should be set to a value that can be achieved without - * exceeding the lower pitch angle limit and without over-speeding - * the aircraft. * * @unit m/s * @min 1.0 @@ -463,7 +449,6 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); * Throttle damping factor * * This is the damping gain for the throttle demand loop. - * Increase to add damping to correct for oscillations in speed and height. * * @min 0.0 * @max 1.0 @@ -476,7 +461,6 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMPING, 0.05f); /** * Integrator gain throttle * - * Integrator gain on the throttle part of the control loop. * Increase it to trim out speed and height offsets faster, * with the downside of possible overshoots and oscillations. * @@ -491,7 +475,6 @@ PARAM_DEFINE_FLOAT(FW_T_THR_INTEG, 0.02f); /** * Integrator gain pitch * - * Integrator gain on the pitch part of the control loop. * Increase it to trim out speed and height offsets faster, * with the downside of possible overshoots and oscillations. * @@ -506,11 +489,9 @@ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f); /** * Maximum vertical acceleration * - * This is the maximum vertical acceleration (in m/s/s) + * This is the maximum vertical acceleration * either up or down that the controller will use to correct speed - * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) - * allows for reasonably aggressive pitch changes if required to recover - * from under-speed conditions. + * or height errors. * * @unit m/s^2 * @min 1.0 @@ -522,9 +503,9 @@ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f); PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); /** - * Airspeed measurement standard deviation for airspeed filter. + * Airspeed measurement standard deviation * - * This is the measurement standard deviation for the airspeed used in the airspeed filter in TECS. + * For the airspeed filter in TECS. * * @unit m/s * @min 0.01 @@ -536,9 +517,9 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.2f); /** - * Airspeed rate measurement standard deviation for airspeed filter. + * Airspeed rate measurement standard deviation * - * This is the measurement standard deviation for the airspeed rate used in the airspeed filter in TECS. + * For the airspeed filter in TECS. * * @unit m/s^2 * @min 0.01 @@ -550,12 +531,10 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.2f); PARAM_DEFINE_FLOAT(FW_T_SPD_DEV_STD, 0.2f); /** - * Process noise standard deviation for the airspeed rate in the airspeed filter. + * Process noise standard deviation for the airspeed rate * - * This is the process noise standard deviation in the airspeed filter filter defining the noise in the - * airspeed rate for the constant airspeed rate model. This is used to define how much the airspeed and - * the airspeed rate are filtered. The smaller the value the more the measurements are smoothed with the - * drawback for delays. + * This is defining the noise in the airspeed rate for the constant airspeed rate model + * of the TECS airspeed filter. * * @unit m/s^2 * @min 0.01 @@ -570,14 +549,9 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_PRC_STD, 0.2f); /** * Roll -> Throttle feedforward * - * Increasing this gain turn increases the amount of throttle that will - * be used to compensate for the additional drag created by turning. - * Ideally this should be set to approximately 10 x the extra sink rate - * in m/s created by a 45 degree bank turn. Increase this gain if - * the aircraft initially loses energy in turns and reduce if the - * aircraft initially gains energy in turns. Efficient high aspect-ratio - * aircraft (eg powered sailplanes) can use a lower value, whereas - * inefficient low aspect-ratio models (eg delta wings) can use a higher value. + * Is used to compensate for the additional drag created by turning. + * Increase this gain if the aircraft initially loses energy in turns + * and reduce if the aircraft initially gains energy in turns. * * @min 0.0 * @max 20.0 @@ -590,13 +564,11 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); /** * Speed <--> Altitude priority * - * This parameter adjusts the amount of weighting that the pitch control + * Adjusts the amount of weighting that the pitch control * applies to speed vs height errors. Setting it to 0.0 will cause the - * pitch control to control height and ignore speed errors. This will - * normally improve height accuracy but give larger airspeed errors. + * pitch control to control height and ignore speed errors. * Setting it to 2.0 will cause the pitch control loop to control speed - * and ignore height errors. This will normally reduce airspeed errors, - * but give larger height errors. The default value of 1.0 allows the pitch + * and ignore height errors. The default value of 1.0 allows the pitch * control to simultaneously control height and speed. * Set to 2 for gliders. * @@ -609,12 +581,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); /** - * Pitch damping factor - * - * This is the damping gain for the pitch demand loop. Increase to add - * damping to correct for oscillations in height. The default value of 0.0 - * will work well provided the pitch to servo controller has been tuned - * properly. + * Pitch damping gain * * @min 0.0 * @max 2.0 @@ -635,7 +602,10 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f); PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f); /** - * Minimum altitude error needed to descend with max airspeed. A negative value disables fast descend. + * Fast descend: minimum altitude error + * + * Minimum altitude error needed to descend with max airspeed and minimal throttle. + * A negative value disables fast descend. * * @min -1.0 * @decimal 0 @@ -680,9 +650,9 @@ PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f); PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); /** - * RC stick configuration fixed-wing. + * Custom stick configuration * - * Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight. + * Applies in manual Position and Altitude flight modes. * * @min 0 * @max 3 @@ -720,9 +690,8 @@ PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f); /** * Default target climbrate. * - * The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints. - * In manual modes this defines the maximum rate at which the altitude setpoint can be increased. - * + * In auto modes: default climb rate output by controller to achieve altitude setpoints. + * In manual modes: maximum climb rate setpoint. * * @unit m/s * @min 0.5 @@ -736,9 +705,8 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_R_SP, 3.0f); /** * Default target sinkrate. * - * - * The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints. - * In manual modes this defines the maximum rate at which the altitude setpoint can be decreased. + * In auto modes: default sink rate output by controller to achieve altitude setpoints. + * In manual modes: maximum sink rate setpoint. * * @unit m/s * @min 0.5 @@ -752,7 +720,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_R_SP, 2.0f); /** * GPS failure loiter time * - * The time in seconds the system should do open loop loiter and wait for GPS recovery + * The time the system should do open loop loiter and wait for GPS recovery * before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. * Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. * @@ -766,7 +734,7 @@ PARAM_DEFINE_INT32(FW_GPSF_LT, 30); /** * GPS failure fixed roll angle * - * Roll in degrees during the loiter after the vehicle has lost GPS in an auto mode (e.g. mission or loiter). + * Roll angle in GPS failure loiter mode. * * @unit deg * @min 0.0 @@ -875,7 +843,7 @@ PARAM_DEFINE_FLOAT(FW_LND_TD_OFF, 3.0); * Approach path nudging: shifts the touchdown point laterally along with the entire approach path * * This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the - * desired landing vector. Nuding is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is + * desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is * relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle). * * @min 0 @@ -914,7 +882,6 @@ PARAM_DEFINE_INT32(FW_LND_ABORT, 3); * Multiplying this factor with the current absolute wind estimate gives the airspeed offset * added to the minimum airspeed setpoint limit. This helps to make the * system more robust against disturbances (turbulence) in high wind. - * Only applies to AUTO flight mode. * * @min 0 * @decimal 2 @@ -975,15 +942,3 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f); * @group FW Attitude Control */ PARAM_DEFINE_FLOAT(FW_SPOILERS_LND, 0.f); - -/** - * Spoiler descend setting - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_SPOILERS_DESC, 0.f); From 6bd81f38a6335492dbf8f116a48f0f9a29b0fca2 Mon Sep 17 00:00:00 2001 From: Peter van der Perk <57130844+PetervdPerk-NXP@users.noreply.github.com> Date: Mon, 8 Jul 2024 18:57:15 +0200 Subject: [PATCH 444/652] imxrt dshot timing fix (#23365) * imxrt: Change PLL settings for more accurate dshot timing * Update NuttX submodule --- boards/px4/fmu-v6xrt/nuttx-config/include/board.h | 1 + boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c | 12 ++++++------ platforms/nuttx/NuttX/nuttx | 2 +- platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 5 ++--- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/include/board.h b/boards/px4/fmu-v6xrt/nuttx-config/include/board.h index 83832f228da1..3c0753df7dd4 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/include/board.h +++ b/boards/px4/fmu-v6xrt/nuttx-config/include/board.h @@ -52,6 +52,7 @@ #define IMXRT_IPG_PODF_DIVIDER 5 #define BOARD_GPT_FREQUENCY 24000000 #define BOARD_XTAL_FREQUENCY 24000000 +#define BOARD_FLEXIO_PREQ 108000000 /* SDIO *********************************************************************/ diff --git a/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c b/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c index db591baf81c9..3223d585aa76 100644 --- a/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c +++ b/boards/px4/fmu-v6xrt/src/imxrt_clockconfig.c @@ -114,11 +114,11 @@ const struct clock_configuration_s g_initial_clkconfig = { .div = 1, .mux = ACMP_CLK_ROOT_OSC_RC_48M_DIV2, }, - .flexio1_clk_root = /* 240 / 2 = 120Mhz */ + .flexio1_clk_root = /* 432 / 4 = 108Mhz */ { .enable = 1, - .div = 2, - .mux = FLEXIO1_CLK_ROOT_SYS_PLL3_DIV2, + .div = 4, + .mux = FLEXIO1_CLK_ROOT_SYS_PLL2_PFD3, }, .flexio2_clk_root = { @@ -492,9 +492,9 @@ const struct clock_configuration_s g_initial_clkconfig = { .mfd = 268435455, .ss_enable = 0, .pfd0 = 27, /* (528 * 18) / 27 = 352 MHz */ - .pfd1 = 16, /* (528 * 16) / 16 = 594 MHz */ - .pfd2 = 24, /* (528 * 24) / 27 = 396 MHz */ - .pfd3 = 32, /* (528 * 32) / 27 = 297 MHz */ + .pfd1 = 16, /* (528 * 18) / 16 = 594 MHz */ + .pfd2 = 24, /* (528 * 18) / 24 = 396 MHz */ + .pfd3 = 22, /* (528 * 18) / 22 = 216 MHz */ }, .sys_pll3 = { diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index d72688cba139..d3b85f3e545d 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit d72688cba1396c882ab74fc921483c8decb0b094 +Subproject commit d3b85f3e545de3692c100143f4a9ae67762ce679 diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index cb92dd1209a3..22a27427f9dc 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -46,7 +46,6 @@ #include "arm_internal.h" #define FLEXIO_BASE IMXRT_FLEXIO1_BASE -#define FLEXIO_PREQ 120000000 #define DSHOT_TIMERS FLEXIO_SHIFTBUFNIS_COUNT #define DSHOT_THROTTLE_POSITION 5u #define DSHOT_TELEMETRY_POSITION 4u @@ -305,8 +304,8 @@ static int flexio_irq_handler(int irq, void *context, void *arg) int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot) { /* Calculate dshot timings based on dshot_pwm_freq */ - dshot_tcmp = 0x2F00 | (((FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2)) & 0xFF); - bdshot_tcmp = 0x2900 | (((FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 1) & 0xFF); + dshot_tcmp = 0x2F00 | (((BOARD_FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2) - 1) & 0xFF); + bdshot_tcmp = 0x2900 | (((BOARD_FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 3) & 0xFF); /* Clock FlexIO peripheral */ imxrt_clockall_flexio1(); From a35cecece450db1ecf5a961cef90daa99be31cff Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 9 Jul 2024 10:05:23 +1200 Subject: [PATCH 445/652] gnss: add missing include Breaks CLion otherwise. --- src/drivers/gnss/septentrio/util.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/gnss/septentrio/util.h b/src/drivers/gnss/septentrio/util.h index e9de9af50dff..aeb9369ad5ac 100644 --- a/src/drivers/gnss/septentrio/util.h +++ b/src/drivers/gnss/septentrio/util.h @@ -39,6 +39,8 @@ #pragma once +#include + namespace septentrio { From 8221940b60493b791f317064ccac9a38e3a8ea77 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 9 Jul 2024 11:16:40 +0200 Subject: [PATCH 446/652] Added pitot tube icing detection (#23206) * lib: add FilteredDerivative class * AirspeedValidator: add first principle check - filters throttle, pitch and airspeed rate, and triggers if the airspeed rate is negative even though the vehicle is pitching down and giving high throttle. Check has to fail for duration defined by ASPD_FP_T_WINDOW to trigger an airspeed failure. * AirspeedValidator: define constants for first principle check * FilteredDerivative: set initialised to false if sample interval is invalid * airspeed_selector: improved comment * increase IAS derivative filter time constant from 4 to 5 * use legacy parameter handling for FW_PSP_OFF * handle FW_THR_MAX as well * ROMFS/airframes: exclude some airframes for v6x and v4pro to save flash on them --------- Signed-off-by: Silvan Fuhrer Signed-off-by: RomanBapst Co-authored-by: Silvan Fuhrer --- .../init.d/airframes/4061_atl_mantis_edu | 1 + ROMFS/px4fmu_common/init.d/airframes/4071_ifo | 1 + .../px4fmu_common/init.d/airframes/4073_ifo-s | 1 + .../init.d/airframes/4500_clover4 | 1 + msg/AirspeedValidated.msg | 4 + src/lib/mathlib/CMakeLists.txt | 1 + .../math/filter/FilteredDerivative.hpp | 114 ++++++++++++++++++ .../airspeed_selector/AirspeedValidator.cpp | 66 +++++++++- .../airspeed_selector/AirspeedValidator.hpp | 32 +++++ .../airspeed_selector_main.cpp | 43 ++++++- .../airspeed_selector_params.c | 19 ++- 11 files changed, 278 insertions(+), 5 deletions(-) create mode 100644 src/lib/mathlib/math/filter/FilteredDerivative.hpp diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index 66d0973caa52..2e52f24ac1d4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -7,6 +7,7 @@ # # @maintainer # @board px4_fmu-v2 exclude +# @board px4_fmu-v4pro exclude # @board px4_fmu-v5x exclude # @board px4_fmu-v6x exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index ce1c3f8f0e54..8cfc14ae1ef7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -12,6 +12,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s index a544a49e0367..276e1b45db27 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s @@ -10,6 +10,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 b/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 index 22f8d74462be..885f0239d589 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 +++ b/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 @@ -8,6 +8,7 @@ # @maintainer Oleg Kalachev # # @board px4_fmu-v2 exclude +# @board px4_fmu-v4pro exclude # @board bitcraze_crazyflie exclude # diff --git a/msg/AirspeedValidated.msg b/msg/AirspeedValidated.msg index 06731cc4106a..9ee0f518314e 100644 --- a/msg/AirspeedValidated.msg +++ b/msg/AirspeedValidated.msg @@ -10,3 +10,7 @@ float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspe bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid + +float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] +float32 throttle_filtered # filtered fixed-wing throttle [-] +float32 pitch_filtered # filtered pitch [rad] diff --git a/src/lib/mathlib/CMakeLists.txt b/src/lib/mathlib/CMakeLists.txt index aad1d3446c51..7f3a3d534e0a 100644 --- a/src/lib/mathlib/CMakeLists.txt +++ b/src/lib/mathlib/CMakeLists.txt @@ -33,6 +33,7 @@ px4_add_library(mathlib math/test/test.cpp + math/filter/FilteredDerivative.hpp math/filter/LowPassFilter2p.hpp math/filter/MedianFilter.hpp math/filter/NotchFilter.hpp diff --git a/src/lib/mathlib/math/filter/FilteredDerivative.hpp b/src/lib/mathlib/math/filter/FilteredDerivative.hpp new file mode 100644 index 000000000000..f0099334d2e7 --- /dev/null +++ b/src/lib/mathlib/math/filter/FilteredDerivative.hpp @@ -0,0 +1,114 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file FilteredDerivative.hpp + * + * @brief Derivative function passed through a first order "alpha" IIR digital filter + * + * @author Silvan Fuhrer + */ + +#pragma once + +// #include +// #include +#include + +using namespace math; + +template +class FilteredDerivative +{ +public: + FilteredDerivative() = default; + ~FilteredDerivative() = default; + + /** + * Set filter parameters for time abstraction + * + * Both parameters have to be provided in the same units. + * + * @param sample_interval interval between two samples + * @param time_constant filter time constant determining convergence + */ + void setParameters(float sample_interval, float time_constant) + { + _alpha_filter.setParameters(sample_interval, time_constant); + _sample_interval = sample_interval; + } + + /** + * Set filter state to an initial value + * + * @param sample new initial value + */ + void reset(const T &sample) + { + _alpha_filter.reset(sample); + _initialized = false; + } + + /** + * Add a new raw value to the filter + * + * @return retrieve the filtered result + */ + const T &update(const T &sample) + { + if (_initialized) { + if (_sample_interval > FLT_EPSILON) { + _alpha_filter.update((sample - _previous_sample) / _sample_interval); + + } else { + _initialized = false; + } + + } else { + // don't update in the first iteration + _initialized = true; + } + + _previous_sample = sample; + return _alpha_filter.getState(); + } + + const T &getState() const { return _alpha_filter.getState(); } + + +private: + AlphaFilter _alpha_filter; + float _sample_interval{0.f}; + T _previous_sample{0.f}; + bool _initialized{false}; +}; diff --git a/src/modules/airspeed_selector/AirspeedValidator.cpp b/src/modules/airspeed_selector/AirspeedValidator.cpp index b83d419b5fdd..4ebacdbeb804 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.cpp +++ b/src/modules/airspeed_selector/AirspeedValidator.cpp @@ -60,6 +60,8 @@ AirspeedValidator::update_airspeed_validator(const airspeed_validator_update_dat check_load_factor(input_data.accel_z); check_airspeed_innovation(input_data.timestamp, input_data.vel_test_ratio, input_data.mag_test_ratio, input_data.ground_velocity, input_data.gnss_valid); + check_first_principle(input_data.timestamp, input_data.fixed_wing_tecs_throttle, + input_data.fixed_wing_tecs_throttle_trim, input_data.tecs_timestamp, input_data.q_att); update_airspeed_valid_status(input_data.timestamp); } @@ -277,16 +279,76 @@ AirspeedValidator::check_load_factor(float accel_z) } } +void +AirspeedValidator::check_first_principle(const uint64_t timestamp, const float throttle_fw, const float throttle_trim, + const uint64_t tecs_timestamp, const Quatf &att_q) +{ + if (! _first_principle_check_enabled) { + _first_principle_check_failed = false; + _time_last_first_principle_check_passing = timestamp; + return; + } + + const float pitch = matrix::Eulerf(att_q).theta(); + const hrt_abstime tecs_dt = timestamp - tecs_timestamp; // return if TECS data is old (TECS not running) + + if (!_in_fixed_wing_flight || tecs_dt > 500_ms || !PX4_ISFINITE(_IAS) || !PX4_ISFINITE(throttle_fw) + || !PX4_ISFINITE(throttle_trim) || !PX4_ISFINITE(pitch)) { + // do not do anything in that case + return; + } + + const float dt = static_cast(timestamp - _time_last_first_principle_check) / 1_s; + _time_last_first_principle_check = timestamp; + + // update filters + if (dt < FLT_EPSILON || dt > 1.f) { + // reset if dt is too large + _IAS_derivative.reset(0.f); + _throttle_filtered.reset(throttle_fw); + _pitch_filtered.reset(pitch); + _time_last_first_principle_check_passing = timestamp; + + } else { + // update filters, with different time constant + _IAS_derivative.setParameters(dt, 5.f); + _throttle_filtered.setParameters(dt, 0.5f); + _pitch_filtered.setParameters(dt, 1.5f); + + _IAS_derivative.update(_IAS); + _throttle_filtered.update(throttle_fw); + _pitch_filtered.update(pitch); + } + + // declare high throttle if more than 5% above trim + const float high_throttle_threshold = math::min(throttle_trim + kHighThrottleDelta, _param_throttle_max); + const bool high_throttle = _throttle_filtered.getState() > high_throttle_threshold; + const bool pitching_down = _pitch_filtered.getState() < _param_psp_off; + + // check if the airspeed derivative is too low given the throttle and pitch + const bool check_failing = _IAS_derivative.getState() < kIASDerivateThreshold && high_throttle && pitching_down; + + if (!check_failing) { + _time_last_first_principle_check_passing = timestamp; + _first_principle_check_failed = false; + } + + if (timestamp - _time_last_first_principle_check_passing > _aspd_fp_t_window * 1_s) { + // only update the test_failed flag once the timeout since first principle check failing is over + _first_principle_check_failed = check_failing; + } +} void AirspeedValidator::update_airspeed_valid_status(const uint64_t timestamp) { - if (_data_stuck_test_failed || _innovations_check_failed || _load_factor_check_failed) { + if (_data_stuck_test_failed || _innovations_check_failed || _load_factor_check_failed + || _first_principle_check_failed) { // at least one check (data stuck, innovation or load factor) failed, so record timestamp _time_checks_failed = timestamp; } else if (! _data_stuck_test_failed && !_innovations_check_failed - && !_load_factor_check_failed) { + && !_load_factor_check_failed && !_first_principle_check_failed) { // all checks(data stuck, innovation and load factor) must pass to declare airspeed good _time_checks_passed = timestamp; } diff --git a/src/modules/airspeed_selector/AirspeedValidator.hpp b/src/modules/airspeed_selector/AirspeedValidator.hpp index 58f79e0009ce..19c3cc88d1b1 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.hpp +++ b/src/modules/airspeed_selector/AirspeedValidator.hpp @@ -41,6 +41,8 @@ #include #include #include +#include +#include using matrix::Dcmf; @@ -66,6 +68,9 @@ struct airspeed_validator_update_data { float vel_test_ratio; float mag_test_ratio; bool in_fixed_wing_flight; + float fixed_wing_tecs_throttle; + float fixed_wing_tecs_throttle_trim; + uint64_t tecs_timestamp; }; class AirspeedValidator @@ -83,6 +88,9 @@ class AirspeedValidator float get_TAS() { return _TAS; } bool get_airspeed_valid() { return _airspeed_valid; } float get_CAS_scale_validated() {return _CAS_scale_validated;} + float get_airspeed_derivative() { return _IAS_derivative.getState(); } + float get_throttle_filtered() { return _throttle_filtered.getState(); } + float get_pitch_filtered() { return _pitch_filtered.getState(); } airspeed_wind_s get_wind_estimator_states(uint64_t timestamp); @@ -118,6 +126,10 @@ class AirspeedValidator void set_enable_data_stuck_check(bool enable) { _data_stuck_check_enabled = enable; } void set_enable_innovation_check(bool enable) { _innovation_check_enabled = enable; } void set_enable_load_factor_check(bool enable) { _load_factor_check_enabled = enable; } + void set_enable_first_principle_check(bool enable) { _first_principle_check_enabled = enable; } + void set_psp_off_param(float psp_off_param) { _param_psp_off = psp_off_param; } + void set_throttle_max_param(float throttle_max_param) { _param_throttle_max = throttle_max_param; } + void set_fp_t_window(float t_window) { _aspd_fp_t_window = t_window; } private: @@ -127,10 +139,17 @@ class AirspeedValidator bool _data_stuck_check_enabled{false}; bool _innovation_check_enabled{false}; bool _load_factor_check_enabled{false}; + bool _first_principle_check_enabled{false}; // airspeed scale validity check static constexpr int SCALE_CHECK_SAMPLES = 12; ///< take samples from 12 segments (every 360/12=30°) + static constexpr float kHighThrottleDelta = + 0.05f; ///< throttle delta above trim throttle required to consider throttle high + static constexpr float kIASDerivateThreshold = + 0.1f; ///< threshold for IAS derivative to detect airspeed failure. Failure is + // detected if in a high throttle and low pitch situation and the filtered IAS derivative is below this threshold + // general states bool _in_fixed_wing_flight{false}; ///< variable to bypass innovation and load factor checks float _IAS{0.0f}; ///< indicated airsped in m/s @@ -158,6 +177,17 @@ class AirspeedValidator float _airspeed_stall{8.0f}; ///< stall speed of aircraft used for load factor check float _load_factor_ratio{0.5f}; ///< ratio of maximum load factor predicted by stall speed to measured load factor + // first principle check + bool _first_principle_check_failed{false}; ///< first principle check has detected failure + float _aspd_fp_t_window{0.f}; ///< time window for first principle check + FilteredDerivative _IAS_derivative; ///< indicated airspeed derivative for first principle check + AlphaFilter _throttle_filtered; ///< filtered throttle for first principle check + AlphaFilter _pitch_filtered; ///< filtered pitch for first principle check + hrt_abstime _time_last_first_principle_check{0}; ///< time airspeed first principle was last checked (uSec) + hrt_abstime _time_last_first_principle_check_passing{0}; ///< time airspeed first principle was last passing (uSec) + float _param_psp_off{0.0f}; ///< parameter pitch in level flight [rad] + float _param_throttle_max{0.0f}; ///< parameter maximum throttle value + // states of airspeed valid declaration bool _airspeed_valid{true}; ///< airspeed valid (pitot or groundspeed-windspeed) float _checks_fail_delay{2.f}; ///< delay for airspeed invalid declaration after single check failure (Sec) @@ -185,6 +215,8 @@ class AirspeedValidator void check_airspeed_innovation(uint64_t timestamp, float estimator_status_vel_test_ratio, float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool gnss_valid); void check_load_factor(float accel_z); + void check_first_principle(const uint64_t timestamp, const float throttle, const float throttle_trim, + const uint64_t tecs_timestamp, const Quatf &att_q); void update_airspeed_valid_status(const uint64_t timestamp); void reset(); void reset_CAS_scale_check(); diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index 28fb87c2b6c1..a3f8bcbc2351 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -57,6 +57,7 @@ #include #include #include +#include #include #include #include @@ -112,6 +113,7 @@ class AirspeedModule : public ModuleBase, public ModuleParams, uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _tecs_status_sub{ORB_ID(tecs_status)}; uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _estimator_status_sub{ORB_ID(estimator_status)}; uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)}; @@ -125,6 +127,7 @@ class AirspeedModule : public ModuleBase, public ModuleParams, uORB::SubscriptionMultiArray _airspeed_subs{ORB_ID::airspeed}; + tecs_status_s _tecs_status {}; estimator_status_s _estimator_status {}; vehicle_acceleration_s _accel {}; vehicle_air_data_s _vehicle_air_data {}; @@ -162,9 +165,16 @@ class AirspeedModule : public ModuleBase, public ModuleParams, CHECK_TYPE_ONLY_DATA_MISSING_BIT = (1 << 0), CHECK_TYPE_DATA_STUCK_BIT = (1 << 1), CHECK_TYPE_INNOVATION_BIT = (1 << 2), - CHECK_TYPE_LOAD_FACTOR_BIT = (1 << 3) + CHECK_TYPE_LOAD_FACTOR_BIT = (1 << 3), + CHECK_TYPE_FIRST_PRINCIPLE_BIT = (1 << 4) }; + + param_t _param_handle_pitch_sp_offset{PARAM_INVALID}; + float _param_pitch_sp_offset{0.0f}; + param_t _param_handle_fw_thr_max{PARAM_INVALID}; + float _param_fw_thr_max{0.0f}; + DEFINE_PARAMETERS( (ParamFloat) _param_aspd_wind_nsd, (ParamFloat) _param_aspd_scale_nsd, @@ -185,8 +195,12 @@ class AirspeedModule : public ModuleBase, public ModuleParams, (ParamFloat) _checks_fail_delay, /**< delay to declare airspeed invalid */ (ParamFloat) _checks_clear_delay, /**< delay to declare airspeed valid again */ + (ParamFloat) _param_wind_sigma_max_synth_tas, + (ParamFloat) _aspd_fp_t_window, + + // external parameters (ParamFloat) _param_fw_airspd_stall, - (ParamFloat) _param_wind_sigma_max_synth_tas + (ParamFloat) _param_fw_airspd_trim ) void init(); /**< initialization of the airspeed validator instances */ @@ -203,6 +217,8 @@ AirspeedModule::AirspeedModule(): ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers) { + _param_handle_pitch_sp_offset = param_find("FW_PSP_OFF"); + _param_handle_fw_thr_max = param_find("FW_THR_MAX"); // initialise parameters update_params(); @@ -355,6 +371,9 @@ AirspeedModule::Run() input_data.accel_z = _accel.xyz[2]; input_data.vel_test_ratio = _estimator_status.vel_test_ratio; input_data.mag_test_ratio = _estimator_status.mag_test_ratio; + input_data.tecs_timestamp = _tecs_status.timestamp; + input_data.fixed_wing_tecs_throttle = _tecs_status.throttle_sp; + input_data.fixed_wing_tecs_throttle_trim = _tecs_status.throttle_trim; // iterate through all airspeed sensors, poll new data from them and update their validators for (int i = 0; i < _number_of_airspeed_sensors; i++) { @@ -442,6 +461,14 @@ void AirspeedModule::update_params() { updateParams(); + if (_param_handle_pitch_sp_offset != PARAM_INVALID) { + param_get(_param_handle_pitch_sp_offset, &_param_pitch_sp_offset); + } + + if (_param_handle_fw_thr_max != PARAM_INVALID) { + param_get(_param_handle_fw_thr_max, &_param_fw_thr_max); + } + _param_airspeed_scale[0] = _param_airspeed_scale_1.get(); _param_airspeed_scale[1] = _param_airspeed_scale_2.get(); _param_airspeed_scale[2] = _param_airspeed_scale_3.get(); @@ -476,6 +503,11 @@ void AirspeedModule::update_params() CheckTypeBits::CHECK_TYPE_INNOVATION_BIT); _airspeed_validator[i].set_enable_load_factor_check(_param_airspeed_checks_on.get() & CheckTypeBits::CHECK_TYPE_LOAD_FACTOR_BIT); + _airspeed_validator[i].set_enable_first_principle_check(_param_airspeed_checks_on.get() & + CheckTypeBits::CHECK_TYPE_FIRST_PRINCIPLE_BIT); + _airspeed_validator[i].set_psp_off_param(math::radians(_param_pitch_sp_offset)); + _airspeed_validator[i].set_throttle_max_param(_param_fw_thr_max); + _airspeed_validator[i].set_fp_t_window(_aspd_fp_t_window.get()); } } @@ -501,6 +533,8 @@ void AirspeedModule::poll_topics() _vehicle_local_position_sub.update(&_vehicle_local_position); _position_setpoint_sub.update(&_position_setpoint); + _tecs_status_sub.update(&_tecs_status); + if (_vehicle_attitude_sub.updated()) { vehicle_attitude_s vehicle_attitude; _vehicle_attitude_sub.update(&vehicle_attitude); @@ -661,6 +695,11 @@ void AirspeedModule::select_airspeed_and_publish() airspeed_validated.airspeed_sensor_measurement_valid = false; airspeed_validated.selected_airspeed_index = _valid_airspeed_index; + airspeed_validated.airspeed_derivative_filtered = _airspeed_validator[_valid_airspeed_index - + 1].get_airspeed_derivative(); + airspeed_validated.throttle_filtered = _airspeed_validator[_valid_airspeed_index - 1].get_throttle_filtered(); + airspeed_validated.pitch_filtered = _airspeed_validator[_valid_airspeed_index - 1].get_pitch_filtered(); + switch (_valid_airspeed_index) { case airspeed_index::DISABLED_INDEX: break; diff --git a/src/modules/airspeed_selector/airspeed_selector_params.c b/src/modules/airspeed_selector/airspeed_selector_params.c index 9ef58a78c8bd..0462fbbc34f3 100644 --- a/src/modules/airspeed_selector/airspeed_selector_params.c +++ b/src/modules/airspeed_selector/airspeed_selector_params.c @@ -149,11 +149,12 @@ PARAM_DEFINE_INT32(ASPD_PRIMARY, 1); * Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0. * * @min 0 - * @max 15 + * @max 31 * @bit 0 Only data missing check (triggers if more than 1s no data) * @bit 1 Data stuck (triggers if data is exactly constant for 2s in FW mode) * @bit 2 Innovation check (see ASPD_FS_INNOV) * @bit 3 Load factor check (triggers if measurement is below stall speed) + * @bit 4 First principle check (airspeed change vs. throttle and pitch) * @group Airspeed Validator */ PARAM_DEFINE_INT32(ASPD_DO_CHECKS, 7); @@ -239,3 +240,19 @@ PARAM_DEFINE_FLOAT(ASPD_FS_T_START, -1.f); * @group Airspeed Validator */ PARAM_DEFINE_FLOAT(ASPD_WERR_THR, 0.55f); + +/** + * First principle airspeed check time window + * + * Window for comparing airspeed change to throttle and pitch change. + * Triggers when the airspeed change within this window is negative while throttle increases + * and the vehicle pitches down. + * Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions. + * Relies on FW_THR_TRIM being set accurately. + * + * @unit s + * @min 0 + * @decimal 1 + * @group Airspeed Validator + */ +PARAM_DEFINE_FLOAT(ASPD_FP_T_WINDOW, 2.0f); From 1df8f3f9d26feb6daa14f6349982faadd9df0dd7 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 14:45:28 -0400 Subject: [PATCH 447/652] ekf2: resetFlowFusion() reset aid src status appropriately --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 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 d9b0887237dd..6cccdeece361 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 @@ -171,11 +171,10 @@ void Ekf::resetFlowFusion() resetHorizontalPositionTo(Vector2f(0.f, 0.f), 0.f); } - updateOptFlow(_aid_src_optical_flow); + resetAidSourceStatusZeroInnovation(_aid_src_optical_flow); + _innov_check_fail_status.flags.reject_optflow_X = false; _innov_check_fail_status.flags.reject_optflow_Y = false; - - _aid_src_optical_flow.time_last_fuse = _time_delayed_us; } void Ekf::resetTerrainToFlow() From ced609daa8b53552ac392e302138e5bc6f97c3c3 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 14:48:03 -0400 Subject: [PATCH 448/652] ekf2: flow fusion start require valid fusion --- .../optical_flow/optical_flow_control.cpp | 3 +-- .../aid_sources/optical_flow/optical_flow_fusion.cpp | 12 ++++++++---- src/modules/ekf2/EKF/ekf.h | 2 +- 3 files changed, 10 insertions(+), 7 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 6cccdeece361..8d4792d7fa3f 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 @@ -134,9 +134,8 @@ void Ekf::startFlowFusion() } if (isHorizontalAidingActive()) { - if (!_aid_src_optical_flow.innovation_rejected) { + if (fuseOptFlow(_hagl_sensor_status.flags.flow)) { ECL_INFO("starting optical flow no reset"); - fuseOptFlow(_hagl_sensor_status.flags.flow); } else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) { resetTerrainToFlow(); diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 8cd8f559f2a4..2ba97942a20f 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -79,7 +79,7 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) math::max(_params.flow_innov_gate, 1.f)); // innovation gate } -void Ekf::fuseOptFlow(const bool update_terrain) +bool Ekf::fuseOptFlow(const bool update_terrain) { const float R_LOS = _aid_src_optical_flow.observation_variance[0]; @@ -98,7 +98,7 @@ void Ekf::fuseOptFlow(const bool update_terrain) // we need to reinitialise the covariance matrix and abort this fusion step ECL_ERR("Opt flow error - covariance reset"); initialiseCovariance(); - return; + return false; } _innov_check_fail_status.flags.reject_optflow_X = (_aid_src_optical_flow.test_ratio[0] > 1.f); @@ -106,7 +106,7 @@ void Ekf::fuseOptFlow(const bool update_terrain) // if either axis fails we abort the fusion if (_aid_src_optical_flow.innovation_rejected) { - return; + return false; } bool fused[2] {false, false}; @@ -129,7 +129,7 @@ void Ekf::fuseOptFlow(const bool update_terrain) // we need to reinitialise the covariance matrix and abort this fusion step ECL_ERR("Opt flow error - covariance reset"); initialiseCovariance(); - return; + return false; } } @@ -150,7 +150,11 @@ void Ekf::fuseOptFlow(const bool update_terrain) if (fused[0] && fused[1]) { _aid_src_optical_flow.time_last_fuse = _time_delayed_us; _aid_src_optical_flow.fused = true; + + return true; } + + return false; } float Ekf::predictFlowRange() diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 966a45a650f5..a8a5778d89a5 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -850,7 +850,7 @@ class Ekf final : public EstimatorInterface // fuse optical flow line of sight rate measurements void updateOptFlow(estimator_aid_source2d_s &aid_src); - void fuseOptFlow(bool update_terrain); + bool fuseOptFlow(bool update_terrain); float predictFlowRange(); Vector2f predictFlowVelBody(); #endif // CONFIG_EKF2_OPTICAL_FLOW From bf4e564b2307e540b456a59e3874ac64deb822fd Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 14:49:48 -0400 Subject: [PATCH 449/652] ekf2: resetTerrainToFlow() reset aid src status appropriately --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 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 8d4792d7fa3f..b1847e24275a 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 @@ -184,10 +184,10 @@ void Ekf::resetTerrainToFlow() P.uncorrelateCovarianceSetVariance(State::terrain.idx, 100.f); _terrain_vpos_reset_counter++; + resetAidSourceStatusZeroInnovation(_aid_src_optical_flow); + _innov_check_fail_status.flags.reject_optflow_X = false; _innov_check_fail_status.flags.reject_optflow_Y = false; - - _aid_src_optical_flow.time_last_fuse = _time_delayed_us; } void Ekf::stopFlowFusion() From bcd666b3f8686e711b00557ba75a27d1e99263bb Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 14:53:18 -0400 Subject: [PATCH 450/652] ekf2: fix optical flow start logic - remove fallthrough that enables flow regardless of success - add appropriate start messages for each case --- .../optical_flow/optical_flow_control.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 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 b1847e24275a..04243f240d30 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 @@ -126,8 +126,6 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) void Ekf::startFlowFusion() { - ECL_INFO("starting optical flow fusion"); - if (_height_sensor_ref != HeightSensor::RANGE) { // If the height is relative to the ground, terrain height cannot be observed. _hagl_sensor_status.flags.flow = true; @@ -135,27 +133,29 @@ void Ekf::startFlowFusion() if (isHorizontalAidingActive()) { if (fuseOptFlow(_hagl_sensor_status.flags.flow)) { - ECL_INFO("starting optical flow no reset"); + ECL_INFO("starting optical flow"); + _control_status.flags.opt_flow = true; } else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) { + ECL_INFO("starting optical flow, resetting terrain"); resetTerrainToFlow(); - - } else { - ECL_INFO("optical flow fusion failed to start"); - _control_status.flags.opt_flow = false; - _hagl_sensor_status.flags.flow = false; + _control_status.flags.opt_flow = true; } } else { if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) { + ECL_INFO("starting optical flow, resetting"); resetFlowFusion(); + _control_status.flags.opt_flow = true; } else if (_hagl_sensor_status.flags.flow) { + ECL_INFO("starting optical flow, resetting terrain"); resetTerrainToFlow(); + _control_status.flags.opt_flow = true; } } - _control_status.flags.opt_flow = true; // needs to be here because of isHorizontalAidingActive + _hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); } void Ekf::resetFlowFusion() From 4d324da9f8e329f4853512738b58d6687ad98a88 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 16:01:05 -0400 Subject: [PATCH 451/652] ekf2: update flow aid src status every sample --- .../optical_flow/optical_flow_control.cpp | 11 ++- .../optical_flow/optical_flow_fusion.cpp | 85 +++++++++---------- src/modules/ekf2/EKF/ekf.h | 12 +-- 3 files changed, 55 insertions(+), 53 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 04243f240d30..5941616be764 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 @@ -64,19 +64,22 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) if (is_quality_good && is_magnitude_good && is_tilt_good) { - // compensate for body motion to give a LOS rate + calcOptFlowBodyRateComp(imu_delayed); - _flow_rate_compensated = _flow_sample_delayed.flow_rate - _flow_sample_delayed.gyro_rate.xy(); } else { // don't use this flow data and wait for the next data to arrive _flow_data_ready = false; - _flow_rate_compensated.setZero(); } + + updateOptFlow(_aid_src_optical_flow, _flow_sample_delayed); + + // logging + const Vector3f flow_gyro_corrected = _flow_sample_delayed.gyro_rate - _flow_gyro_bias; + _flow_rate_compensated = _flow_sample_delayed.flow_rate - flow_gyro_corrected.xy(); } if (_flow_data_ready) { - updateOptFlow(_aid_src_optical_flow); // Check if we are in-air and require optical flow to control position drift bool is_flow_required = _control_status.flags.in_air diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 2ba97942a20f..74e203e85915 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -42,28 +42,18 @@ #include #include -void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) +void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src, const flowSample &flow_sample) { - const Vector2f vel_body = predictFlowVelBody(); - const float range = predictFlowRange(); - // calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed // correct for gyro bias errors in the data used to do the motion compensation // Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis. - const Vector2f opt_flow_rate = _flow_rate_compensated; - - // compute the velocities in body and local frames from corrected optical flow measurement for logging only - _flow_vel_body(0) = -opt_flow_rate(1) * range; - _flow_vel_body(1) = opt_flow_rate(0) * range; - _flow_vel_ne = Vector2f(_R_to_earth * Vector3f(_flow_vel_body(0), _flow_vel_body(1), 0.f)); + const Vector3f flow_gyro_corrected = flow_sample.gyro_rate - _flow_gyro_bias; + const Vector2f flow_compensated = flow_sample.flow_rate - flow_gyro_corrected.xy(); - Vector2f innovation{ - (vel_body(1) / range) - opt_flow_rate(0), - (-vel_body(0) / range) - opt_flow_rate(1) - }; + const Vector2f innovation = predictFlow(flow_gyro_corrected) - flow_compensated; // calculate the optical flow observation variance - const float R_LOS = calcOptFlowMeasVar(_flow_sample_delayed); + const float R_LOS = calcOptFlowMeasVar(flow_sample); Vector2f innov_var; VectorState H; @@ -71,23 +61,26 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) // run the innovation consistency check and record result updateAidSourceStatus(aid_src, - _flow_sample_delayed.time_us, // sample timestamp - opt_flow_rate, // observation - Vector2f{R_LOS, R_LOS}, // observation variance - innovation, // innovation - innov_var, // innovation variance - math::max(_params.flow_innov_gate, 1.f)); // innovation gate + flow_sample.time_us, // sample timestamp + flow_compensated, // observation + Vector2f{R_LOS, R_LOS}, // observation variance + innovation, // innovation + innov_var, // innovation variance + math::max(_params.flow_innov_gate, 1.f)); // innovation gate + + + // compute the velocities in body and local frames from corrected optical flow measurement for logging only + 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)); + } bool Ekf::fuseOptFlow(const bool update_terrain) { - const float R_LOS = _aid_src_optical_flow.observation_variance[0]; - - // calculate the height above the ground of the optical flow camera. Since earth frame is NED - // a positive offset in earth frame leads to a smaller height above the ground. - float range = predictFlowRange(); - const auto state_vector = _state.vector(); + const float R_LOS = _aid_src_optical_flow.observation_variance[0]; Vector2f innov_var; VectorState H; @@ -113,6 +106,14 @@ bool Ekf::fuseOptFlow(const bool update_terrain) // fuse observation axes sequentially for (uint8_t index = 0; index <= 1; index++) { + + if (_aid_src_optical_flow.innovation_variance[index] < R_LOS) { + // we need to reinitialise the covariance matrix and abort this fusion step + ECL_ERR("Opt flow error - covariance reset"); + initialiseCovariance(); + return false; + } + if (index == 0) { // everything was already computed above @@ -121,16 +122,8 @@ bool Ekf::fuseOptFlow(const bool update_terrain) sym::ComputeFlowYInnovVarAndH(state_vector, P, R_LOS, FLT_EPSILON, &_aid_src_optical_flow.innovation_variance[1], &H); // recalculate the innovation using the updated state - const Vector2f vel_body = predictFlowVelBody(); - range = predictFlowRange(); - _aid_src_optical_flow.innovation[1] = (-vel_body(0) / range) - _aid_src_optical_flow.observation[1]; - - if (_aid_src_optical_flow.innovation_variance[1] < R_LOS) { - // we need to reinitialise the covariance matrix and abort this fusion step - ECL_ERR("Opt flow error - covariance reset"); - initialiseCovariance(); - return false; - } + const Vector3f flow_gyro_corrected = _flow_sample_delayed.gyro_rate - _flow_gyro_bias; + _aid_src_optical_flow.innovation[1] = predictFlow(flow_gyro_corrected)(1) - _aid_src_optical_flow.observation[1]; } VectorState Kfusion = P * H / _aid_src_optical_flow.innovation_variance[index]; @@ -157,7 +150,7 @@ bool Ekf::fuseOptFlow(const bool update_terrain) return false; } -float Ekf::predictFlowRange() +float Ekf::predictFlowRange() const { // calculate the sensor position relative to the IMU const Vector3f pos_offset_body = _params.flow_pos_body - _params.imu_pos_body; @@ -180,24 +173,28 @@ float Ekf::predictFlowRange() return flow_range; } -Vector2f Ekf::predictFlowVelBody() +Vector2f Ekf::predictFlow(const Vector3f &flow_gyro) const { // calculate the sensor position relative to the IMU const Vector3f pos_offset_body = _params.flow_pos_body - _params.imu_pos_body; // calculate the velocity of the sensor relative to the imu in body frame - // Note: _flow_sample_delayed.gyro_rate is the negative of the body angular velocity, thus use minus sign - const Vector3f vel_rel_imu_body = Vector3f(-(_flow_sample_delayed.gyro_rate - _flow_gyro_bias)) % pos_offset_body; + // Note: flow gyro is the negative of the body angular velocity, thus use minus sign + const Vector3f vel_rel_imu_body = -flow_gyro % pos_offset_body; // calculate the velocity of the sensor in the earth frame const Vector3f vel_rel_earth = _state.vel + _R_to_earth * vel_rel_imu_body; // rotate into body frame - return _state.quat_nominal.rotateVectorInverse(vel_rel_earth).xy(); + const Vector2f vel_body = _state.quat_nominal.rotateVectorInverse(vel_rel_earth).xy(); + + // calculate range from focal point to centre of image + const float range = predictFlowRange(); + + return Vector2f(vel_body(1) / range, -vel_body(0) / range); } -// calculate the measurement variance for the optical flow sensor (rad/sec)^2 -float Ekf::calcOptFlowMeasVar(const flowSample &flow_sample) +float Ekf::calcOptFlowMeasVar(const flowSample &flow_sample) const { // calculate the observation noise variance - scaling noise linearly across flow quality range const float R_LOS_best = fmaxf(_params.flow_noise, 0.05f); diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index a8a5778d89a5..f4368c0f2869 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -842,17 +842,19 @@ class Ekf final : public EstimatorInterface void updateOnGroundMotionForOpticalFlowChecks(); void resetOnGroundMotionForOpticalFlowChecks(); - // calculate the measurement variance for the optical flow sensor - float calcOptFlowMeasVar(const flowSample &flow_sample); + // calculate the measurement variance for the optical flow sensor (rad/sec)^2 + float calcOptFlowMeasVar(const flowSample &flow_sample) const; // calculate optical flow body angular rate compensation void calcOptFlowBodyRateComp(const imuSample &imu_delayed); + float predictFlowRange() const; + Vector2f predictFlow(const Vector3f &flow_gyro) const; + // fuse optical flow line of sight rate measurements - void updateOptFlow(estimator_aid_source2d_s &aid_src); + void updateOptFlow(estimator_aid_source2d_s &aid_src, const flowSample &flow_sample); bool fuseOptFlow(bool update_terrain); - float predictFlowRange(); - Vector2f predictFlowVelBody(); + #endif // CONFIG_EKF2_OPTICAL_FLOW #if defined(CONFIG_EKF2_MAGNETOMETER) From 7047f9441ccea52a0fd57a04500f5fdc70bb9a52 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 16:40:30 -0400 Subject: [PATCH 452/652] ekf2: fix calcOptFlowBodyRateComp() gyro bias - adjust flow sample gyro_rate immediately after popping from ring buffer - always update flow gyro bias (calcOptFlowBodyRateComp()) regardless of flow quality or magnitude --- .../optical_flow/optical_flow_control.cpp | 54 +++++++++---------- src/modules/ekf2/EKF/ekf.h | 4 +- src/modules/ekf2/EKF2.cpp | 2 +- 3 files changed, 30 insertions(+), 30 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 5941616be764..2aad323e35a8 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 @@ -46,13 +46,28 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) // New optical flow data is available and is ready to be fused when the midpoint of the sample falls behind the fusion time horizon if (_flow_data_ready) { + + // flow gyro has opposite sign convention + _ref_body_rate = -(imu_delayed.delta_ang / imu_delayed.delta_ang_dt - getGyroBias()); + + // ensure valid flow sample gyro rate before proceeding + if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(0)) || !PX4_ISFINITE(_flow_sample_delayed.gyro_rate(1))) { + _flow_sample_delayed.gyro_rate = _ref_body_rate; + + } else if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(2))) { + // Some flow modules only provide X ind Y angular rates. If this is the case, complete the vector with our own Z gyro + _flow_sample_delayed.gyro_rate(2) = _ref_body_rate(2); + } + + const flowSample &flow_sample = _flow_sample_delayed; + const int32_t min_quality = _control_status.flags.in_air ? _params.flow_qual_min : _params.flow_qual_min_gnd; - const bool is_quality_good = (_flow_sample_delayed.quality >= min_quality); - const bool is_magnitude_good = _flow_sample_delayed.flow_rate.isAllFinite() - && !_flow_sample_delayed.flow_rate.longerThan(_flow_max_rate); + const bool is_quality_good = (flow_sample.quality >= min_quality); + const bool is_magnitude_good = flow_sample.flow_rate.isAllFinite() + && !flow_sample.flow_rate.longerThan(_flow_max_rate); bool is_tilt_good = true; @@ -61,22 +76,23 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) #endif // CONFIG_EKF2_RANGE_FINDER + calcOptFlowBodyRateComp(flow_sample); + if (is_quality_good && is_magnitude_good && is_tilt_good) { - calcOptFlowBodyRateComp(imu_delayed); } else { // don't use this flow data and wait for the next data to arrive _flow_data_ready = false; } - updateOptFlow(_aid_src_optical_flow, _flow_sample_delayed); + updateOptFlow(_aid_src_optical_flow, flow_sample); // logging - const Vector3f flow_gyro_corrected = _flow_sample_delayed.gyro_rate - _flow_gyro_bias; - _flow_rate_compensated = _flow_sample_delayed.flow_rate - flow_gyro_corrected.xy(); + const Vector3f flow_gyro_corrected = flow_sample.gyro_rate - _flow_gyro_bias; + _flow_rate_compensated = flow_sample.flow_rate - flow_gyro_corrected.xy(); } if (_flow_data_ready) { @@ -202,25 +218,9 @@ void Ekf::stopFlowFusion() } } -void Ekf::calcOptFlowBodyRateComp(const imuSample &imu_delayed) +void Ekf::calcOptFlowBodyRateComp(const flowSample &flow_sample) { - if (imu_delayed.delta_ang_dt > FLT_EPSILON) { - _ref_body_rate = -imu_delayed.delta_ang / imu_delayed.delta_ang_dt - - getGyroBias(); // flow gyro has opposite sign convention - - } else { - _ref_body_rate.zero(); - } - - if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(0)) || !PX4_ISFINITE(_flow_sample_delayed.gyro_rate(1))) { - _flow_sample_delayed.gyro_rate = _ref_body_rate; - - } else if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(2))) { - // Some flow modules only provide X ind Y angular rates. If this is the case, complete the vector with our own Z gyro - _flow_sample_delayed.gyro_rate(2) = _ref_body_rate(2); - } - - // calculate the bias estimate using a combined LPF and spike filter - _flow_gyro_bias = _flow_gyro_bias * 0.99f + matrix::constrain(_flow_sample_delayed.gyro_rate - _ref_body_rate, -0.1f, - 0.1f) * 0.01f; + // calculate the bias estimate using a combined LPF and spike filter + _flow_gyro_bias = 0.99f * _flow_gyro_bias + + 0.01f * matrix::constrain(flow_sample.gyro_rate - _ref_body_rate, -0.1f, 0.1f); } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index f4368c0f2869..6548b7054a1c 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -134,7 +134,7 @@ class Ekf final : public EstimatorInterface const Vector3f getFlowGyro() const { return _flow_sample_delayed.gyro_rate; } const Vector3f &getFlowGyroBias() const { return _flow_gyro_bias; } - const Vector3f &getRefBodyRate() const { return _ref_body_rate; } + const Vector3f &getFlowRefBodyRate() const { return _ref_body_rate; } #endif // CONFIG_EKF2_OPTICAL_FLOW float getHeadingInnov() const @@ -846,7 +846,7 @@ class Ekf final : public EstimatorInterface float calcOptFlowMeasVar(const flowSample &flow_sample) const; // calculate optical flow body angular rate compensation - void calcOptFlowBodyRateComp(const imuSample &imu_delayed); + void calcOptFlowBodyRateComp(const flowSample &flow_sample); float predictFlowRange() const; Vector2f predictFlow(const Vector3f &flow_gyro) const; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index c42a499e0961..9c330f5f4076 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2043,7 +2043,7 @@ void EKF2::PublishOpticalFlowVel(const hrt_abstime ×tamp) _ekf.getFlowGyro().copyTo(flow_vel.gyro_rate); _ekf.getFlowGyroBias().copyTo(flow_vel.gyro_bias); - _ekf.getRefBodyRate().copyTo(flow_vel.ref_gyro); + _ekf.getFlowRefBodyRate().copyTo(flow_vel.ref_gyro); flow_vel.timestamp = _replay_mode ? timestamp : hrt_absolute_time(); From 9dfd82ab062df4ac22519320ad634b41edd8a7b7 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 16:21:17 -0400 Subject: [PATCH 453/652] ekf2: optical flow remove _flow_data_ready flag --- .../optical_flow/optical_flow_control.cpp | 16 ++++++++-------- src/modules/ekf2/EKF/ekf.h | 2 -- 2 files changed, 8 insertions(+), 10 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 2aad323e35a8..2e3db2037a48 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 @@ -40,12 +40,15 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) { - if (_flow_buffer) { - _flow_data_ready = _flow_buffer->pop_first_older_than(imu_delayed.time_us, &_flow_sample_delayed); + if (!_flow_buffer || (_params.flow_ctrl != 1)) { + stopFlowFusion(); + return; } + bool flow_data_ready = false; + // New optical flow data is available and is ready to be fused when the midpoint of the sample falls behind the fusion time horizon - if (_flow_data_ready) { + if (_flow_buffer->pop_first_older_than(imu_delayed.time_us, &_flow_sample_delayed)) { // flow gyro has opposite sign convention _ref_body_rate = -(imu_delayed.delta_ang / imu_delayed.delta_ang_dt - getGyroBias()); @@ -82,10 +85,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && is_magnitude_good && is_tilt_good) { - - } else { - // don't use this flow data and wait for the next data to arrive - _flow_data_ready = false; + flow_data_ready = true; } updateOptFlow(_aid_src_optical_flow, flow_sample); @@ -95,7 +95,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) _flow_rate_compensated = flow_sample.flow_rate - flow_gyro_corrected.xy(); } - if (_flow_data_ready) { + if (flow_data_ready) { // Check if we are in-air and require optical flow to control position drift bool is_flow_required = _control_status.flags.in_air diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 6548b7054a1c..e5cc2cb24f5c 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -603,8 +603,6 @@ class Ekf final : public EstimatorInterface Vector3f _ref_body_rate{}; 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 - - bool _flow_data_ready{false}; ///< true when the leading edge of the optical flow integration period has fallen behind the fusion time horizon #endif // CONFIG_EKF2_OPTICAL_FLOW #if defined(CONFIG_EKF2_AIRSPEED) From f709ed409dfc60c4ba8886b9ee180149bf9bb997 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 16:23:25 -0400 Subject: [PATCH 454/652] ekf2: optical flow stop reset all flags --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 6 ++++++ 1 file changed, 6 insertions(+) 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 2e3db2037a48..ea78b14bf42b 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 @@ -215,6 +215,12 @@ void Ekf::stopFlowFusion() ECL_INFO("stopping optical flow fusion"); _control_status.flags.opt_flow = false; _hagl_sensor_status.flags.flow = false; + + _fault_status.flags.bad_optflow_X = false; + _fault_status.flags.bad_optflow_Y = false; + + _innov_check_fail_status.flags.reject_optflow_X = false; + _innov_check_fail_status.flags.reject_optflow_Y = false; } } From 8bf15b01c41929cd5f483549c0d8833d91d9d311 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 26 Jun 2024 16:58:01 -0400 Subject: [PATCH 455/652] ekf2: optical flow don't compute innovation variance twice - collapse updateOptFlow() and startFlowFusion() to avoid recomputing H - this is a relatively expensive call we can easily avoid with the right structure --- .../optical_flow/optical_flow_control.cpp | 99 +++++++++++-------- .../optical_flow/optical_flow_fusion.cpp | 53 +--------- src/modules/ekf2/EKF/ekf.h | 4 +- 3 files changed, 64 insertions(+), 92 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 ea78b14bf42b..8e44a04828e7 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 @@ -38,6 +38,8 @@ #include "ekf.h" +#include + void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) { if (!_flow_buffer || (_params.flow_ctrl != 1)) { @@ -47,6 +49,8 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) bool flow_data_ready = false; + VectorState H; + // New optical flow data is available and is ready to be fused when the midpoint of the sample falls behind the fusion time horizon if (_flow_buffer->pop_first_older_than(imu_delayed.time_us, &_flow_sample_delayed)) { @@ -88,11 +92,35 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) flow_data_ready = true; } - updateOptFlow(_aid_src_optical_flow, flow_sample); + // calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed + // correct for gyro bias errors in the data used to do the motion compensation + // Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis. + const Vector3f flow_gyro_corrected = flow_sample.gyro_rate - _flow_gyro_bias; + const Vector2f flow_compensated = flow_sample.flow_rate - flow_gyro_corrected.xy(); + + // calculate the optical flow observation variance + const float R_LOS = calcOptFlowMeasVar(flow_sample); + + Vector2f innov_var; + sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, R_LOS, FLT_EPSILON, &innov_var, &H); + + // run the innovation consistency check and record result + updateAidSourceStatus(_aid_src_optical_flow, + flow_sample.time_us, // sample timestamp + flow_compensated, // observation + Vector2f{R_LOS, R_LOS}, // observation variance + predictFlow(flow_gyro_corrected) - flow_compensated, // innovation + innov_var, // innovation variance + math::max(_params.flow_innov_gate, 1.f)); // innovation gate // logging - const Vector3f flow_gyro_corrected = flow_sample.gyro_rate - _flow_gyro_bias; - _flow_rate_compensated = flow_sample.flow_rate - flow_gyro_corrected.xy(); + _flow_rate_compensated = flow_compensated; + + // compute the velocities in body and local frames from corrected optical flow measurement for logging only + 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_data_ready) { @@ -116,7 +144,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) if (_control_status.flags.opt_flow) { if (continuing_conditions_passing) { - fuseOptFlow(_hagl_sensor_status.flags.flow); + fuseOptFlow(H, _hagl_sensor_status.flags.flow); // 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)) { @@ -134,47 +162,40 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) } else { if (starting_conditions_passing) { - startFlowFusion(); - } - } - - } else if (_control_status.flags.opt_flow && isTimedOut(_flow_sample_delayed.time_us, _params.reset_timeout_max)) { - stopFlowFusion(); - } -} + // If the height is relative to the ground, terrain height cannot be observed. + _hagl_sensor_status.flags.flow = (_height_sensor_ref != HeightSensor::RANGE); + + if (isHorizontalAidingActive()) { + if (fuseOptFlow(H, _hagl_sensor_status.flags.flow)) { + ECL_INFO("starting optical flow"); + _control_status.flags.opt_flow = true; + + } else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) { + ECL_INFO("starting optical flow, resetting terrain"); + resetTerrainToFlow(); + _control_status.flags.opt_flow = true; + } -void Ekf::startFlowFusion() -{ - if (_height_sensor_ref != HeightSensor::RANGE) { - // If the height is relative to the ground, terrain height cannot be observed. - _hagl_sensor_status.flags.flow = true; - } + } else { + if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) { + ECL_INFO("starting optical flow, resetting"); + resetFlowFusion(); + _control_status.flags.opt_flow = true; - if (isHorizontalAidingActive()) { - if (fuseOptFlow(_hagl_sensor_status.flags.flow)) { - ECL_INFO("starting optical flow"); - _control_status.flags.opt_flow = true; + } else if (_hagl_sensor_status.flags.flow) { + ECL_INFO("starting optical flow, resetting terrain"); + resetTerrainToFlow(); + _control_status.flags.opt_flow = true; + } + } - } else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) { - ECL_INFO("starting optical flow, resetting terrain"); - resetTerrainToFlow(); - _control_status.flags.opt_flow = true; + _hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); + } } - } else { - if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) { - ECL_INFO("starting optical flow, resetting"); - resetFlowFusion(); - _control_status.flags.opt_flow = true; - - } else if (_hagl_sensor_status.flags.flow) { - ECL_INFO("starting optical flow, resetting terrain"); - resetTerrainToFlow(); - _control_status.flags.opt_flow = true; - } + } else if (_control_status.flags.opt_flow && isTimedOut(_flow_sample_delayed.time_us, _params.reset_timeout_max)) { + stopFlowFusion(); } - - _hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); } void Ekf::resetFlowFusion() diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 74e203e85915..91efdace2e79 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -42,57 +42,9 @@ #include #include -void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src, const flowSample &flow_sample) -{ - // calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed - // correct for gyro bias errors in the data used to do the motion compensation - // Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis. - const Vector3f flow_gyro_corrected = flow_sample.gyro_rate - _flow_gyro_bias; - const Vector2f flow_compensated = flow_sample.flow_rate - flow_gyro_corrected.xy(); - - const Vector2f innovation = predictFlow(flow_gyro_corrected) - flow_compensated; - - // calculate the optical flow observation variance - const float R_LOS = calcOptFlowMeasVar(flow_sample); - - Vector2f innov_var; - VectorState H; - sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, R_LOS, FLT_EPSILON, &innov_var, &H); - - // run the innovation consistency check and record result - updateAidSourceStatus(aid_src, - flow_sample.time_us, // sample timestamp - flow_compensated, // observation - Vector2f{R_LOS, R_LOS}, // observation variance - innovation, // innovation - innov_var, // innovation variance - math::max(_params.flow_innov_gate, 1.f)); // innovation gate - - - // compute the velocities in body and local frames from corrected optical flow measurement for logging only - 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)); - -} - -bool Ekf::fuseOptFlow(const bool update_terrain) +bool Ekf::fuseOptFlow(VectorState &H, const bool update_terrain) { const auto state_vector = _state.vector(); - const float R_LOS = _aid_src_optical_flow.observation_variance[0]; - - Vector2f innov_var; - VectorState H; - sym::ComputeFlowXyInnovVarAndHx(state_vector, P, R_LOS, FLT_EPSILON, &innov_var, &H); - innov_var.copyTo(_aid_src_optical_flow.innovation_variance); - - if ((innov_var(0) < R_LOS) || (innov_var(1) < R_LOS)) { - // we need to reinitialise the covariance matrix and abort this fusion step - ECL_ERR("Opt flow error - covariance reset"); - initialiseCovariance(); - return false; - } _innov_check_fail_status.flags.reject_optflow_X = (_aid_src_optical_flow.test_ratio[0] > 1.f); _innov_check_fail_status.flags.reject_optflow_Y = (_aid_src_optical_flow.test_ratio[1] > 1.f); @@ -107,7 +59,7 @@ bool Ekf::fuseOptFlow(const bool update_terrain) // fuse observation axes sequentially for (uint8_t index = 0; index <= 1; index++) { - if (_aid_src_optical_flow.innovation_variance[index] < R_LOS) { + if (_aid_src_optical_flow.innovation_variance[index] < _aid_src_optical_flow.observation_variance[index]) { // we need to reinitialise the covariance matrix and abort this fusion step ECL_ERR("Opt flow error - covariance reset"); initialiseCovariance(); @@ -119,6 +71,7 @@ bool Ekf::fuseOptFlow(const bool update_terrain) } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) + const float R_LOS = _aid_src_optical_flow.observation_variance[1]; sym::ComputeFlowYInnovVarAndH(state_vector, P, R_LOS, FLT_EPSILON, &_aid_src_optical_flow.innovation_variance[1], &H); // recalculate the innovation using the updated state diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index e5cc2cb24f5c..b3f52e18d3da 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -833,7 +833,6 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_OPTICAL_FLOW) // control fusion of optical flow observations void controlOpticalFlowFusion(const imuSample &imu_delayed); - void startFlowFusion(); void resetFlowFusion(); void stopFlowFusion(); @@ -850,8 +849,7 @@ class Ekf final : public EstimatorInterface Vector2f predictFlow(const Vector3f &flow_gyro) const; // fuse optical flow line of sight rate measurements - void updateOptFlow(estimator_aid_source2d_s &aid_src, const flowSample &flow_sample); - bool fuseOptFlow(bool update_terrain); + bool fuseOptFlow(VectorState &H, bool update_terrain); #endif // CONFIG_EKF2_OPTICAL_FLOW From ea8f14b8838ae9edb4066f8ea9de1f13d6370d3e Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 27 Jun 2024 17:40:26 -0400 Subject: [PATCH 456/652] ekf2: optical flow logic, timeout if bad_tilt, etc - previously we could get stuck with optical flow still technically active (_control_status.flags.opt_flow=true), but nothing being updated due to excessive tilt, etc --- .../optical_flow/optical_flow_control.cpp | 20 +++++++------------ 1 file changed, 7 insertions(+), 13 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 8e44a04828e7..4a6813eaae52 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 @@ -47,8 +47,6 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) return; } - bool flow_data_ready = false; - VectorState H; // New optical flow data is available and is ready to be fused when the midpoint of the sample falls behind the fusion time horizon @@ -80,18 +78,10 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_RANGE_FINDER) is_tilt_good = (_R_to_earth(2, 2) > _params.range_cos_max_tilt); - #endif // CONFIG_EKF2_RANGE_FINDER calcOptFlowBodyRateComp(flow_sample); - if (is_quality_good - && is_magnitude_good - && is_tilt_good) { - - flow_data_ready = true; - } - // calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed // correct for gyro bias errors in the data used to do the motion compensation // Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis. @@ -121,9 +111,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) _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_data_ready) { // Check if we are in-air and require optical flow to control position drift bool is_flow_required = _control_status.flags.in_air @@ -137,6 +125,9 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && is_within_max_sensor_dist; const bool starting_conditions_passing = continuing_conditions_passing + && is_quality_good + && is_magnitude_good + && is_tilt_good && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching // If the height is relative to the ground, terrain height cannot be observed. @@ -144,7 +135,10 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) if (_control_status.flags.opt_flow) { if (continuing_conditions_passing) { - fuseOptFlow(H, _hagl_sensor_status.flags.flow); + + if (is_quality_good && is_magnitude_good && is_tilt_good) { + fuseOptFlow(H, _hagl_sensor_status.flags.flow); + } // 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)) { From 6be06ecbb3b2585ebf261e809451b85bc8ad9c9d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 27 Jun 2024 17:54:35 -0400 Subject: [PATCH 457/652] ekf2: optical flow failing also reset terrain if needed --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 4 ++++ 1 file changed, 4 insertions(+) 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 4a6813eaae52..299a9931cd56 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 @@ -145,6 +145,10 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) if (is_flow_required) { resetFlowFusion(); + if (_hagl_sensor_status.flags.flow && !isTerrainEstimateValid()) { + resetTerrainToFlow(); + } + } else { stopFlowFusion(); } From e52025cc2068fde1399067d13799769cc441562f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 27 Jun 2024 17:57:03 -0400 Subject: [PATCH 458/652] ekf2: optical flow fusion timeout only reset if quality is good --- .../ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 299a9931cd56..85e4e5ebe1dc 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 @@ -142,7 +142,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) { + if (is_flow_required && is_quality_good) { resetFlowFusion(); if (_hagl_sensor_status.flags.flow && !isTerrainEstimateValid()) { From c56f84fe8a089d1cd16480f5e9c3269001196b66 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 27 Jun 2024 18:28:42 -0400 Subject: [PATCH 459/652] ekf2: range, check if terrain valid for reset on fusion timeout --- .../ekf2/EKF/aid_sources/range_finder/range_height_control.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 104ec47d9190..93e15766eac7 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 @@ -187,7 +187,7 @@ void Ekf::controlRangeHaglFusion() } else if (is_fusion_failing) { // Some other height source is still working - if (_hagl_sensor_status.flags.flow) { + if (_hagl_sensor_status.flags.flow && isTerrainEstimateValid()) { ECL_WARN("stopping %s fusion, fusion failing", HGT_SRC_NAME); stopRngHgtFusion(); stopRngTerrFusion(); From 64a6971bdb8d92b702a56fe27c3acab8513f7c8f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 28 Jun 2024 01:37:24 -0400 Subject: [PATCH 460/652] ekf2: only limit opt flow HAGL if range only terrain - increase HALG limit from 75%->90% of sensor max --- src/modules/ekf2/EKF/ekf_helper.cpp | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 791ed89e2672..5ac5f5467d95 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -244,8 +244,8 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl // Calculate range finder limits const float rangefinder_hagl_min = _range_sensor.getValidMinVal(); - // Allow use of 75% of rangefinder maximum range to allow for angular motion - const float rangefinder_hagl_max = 0.75f * _range_sensor.getValidMaxVal(); + // Allow use of 90% of rangefinder maximum range to allow for angular motion + const float rangefinder_hagl_max = 0.9f * _range_sensor.getValidMaxVal(); // TODO : calculate visual odometry limits const bool relying_on_rangefinder = isOnlyActiveSourceOfVerticalPositionAiding(_control_status.flags.rng_hgt); @@ -262,8 +262,16 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl if (relying_on_optical_flow) { // Calculate optical flow limits - const float flow_hagl_min = fmaxf(rangefinder_hagl_min, _flow_min_distance); - const float flow_hagl_max = fminf(rangefinder_hagl_max, _flow_max_distance); + float flow_hagl_min = _flow_min_distance; + float flow_hagl_max = _flow_max_distance; + + // only limit optical flow height is dependent on range finder or terrain estimate invalid (precaution) + if ((!_hagl_sensor_status.flags.flow && _hagl_sensor_status.flags.range_finder) + || !isTerrainEstimateValid() + ) { + flow_hagl_min = math::max(flow_hagl_min, rangefinder_hagl_min); + flow_hagl_max = math::min(flow_hagl_max, rangefinder_hagl_max); + } const float flow_constrained_height = math::constrain(getHagl(), flow_hagl_min, flow_hagl_max); From 3e3b886b5d29d944ae67ff8fe304cc0c962fd9cb Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 28 Jun 2024 01:55:08 -0400 Subject: [PATCH 461/652] ekf2: add terrain estimator_status_flags --- msg/EstimatorStatusFlags.msg | 2 ++ .../optical_flow/optical_flow_control.cpp | 18 ++++++------- .../range_finder/range_height_control.cpp | 26 +++++++++---------- src/modules/ekf2/EKF/common.h | 14 +++------- src/modules/ekf2/EKF/ekf.h | 3 --- src/modules/ekf2/EKF/ekf_helper.cpp | 4 +-- src/modules/ekf2/EKF/terrain_control.cpp | 6 ++--- src/modules/ekf2/EKF2.cpp | 14 +++++++++- .../test/sensor_simulator/ekf_wrapper.cpp | 8 ++---- 9 files changed, 47 insertions(+), 48 deletions(-) diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index c6e0504f158f..2d6a7c39a171 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -43,6 +43,8 @@ bool cs_mag # 35 - true if 3-axis magnetometer measurement f bool cs_ev_yaw_fault # 36 - true when the EV heading has been declared faulty and is no longer being used bool cs_mag_heading_consistent # 37 - true when the heading obtained from mag data is declared consistent with the filter bool cs_aux_gpos # 38 - true if auxiliary global position measurement fusion is intended +bool cs_rng_terrain # 39 - true if we are fusing range finder data for terrain +bool cs_opt_flow_terrain # 40 - true if we are fusing flow data for terrain # fault status uint32 fault_status_changes # number of filter fault status (fs) changes 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 85e4e5ebe1dc..0e4b8b668ed6 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 @@ -131,13 +131,13 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching // If the height is relative to the ground, terrain height cannot be observed. - _hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); + _control_status.flags.opt_flow_terrain = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); if (_control_status.flags.opt_flow) { if (continuing_conditions_passing) { if (is_quality_good && is_magnitude_good && is_tilt_good) { - fuseOptFlow(H, _hagl_sensor_status.flags.flow); + fuseOptFlow(H, _control_status.flags.opt_flow_terrain); } // handle the case when we have optical flow, are reliant on it, but have not been using it for an extended period @@ -145,7 +145,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) if (is_flow_required && is_quality_good) { resetFlowFusion(); - if (_hagl_sensor_status.flags.flow && !isTerrainEstimateValid()) { + if (_control_status.flags.opt_flow_terrain && !isTerrainEstimateValid()) { resetTerrainToFlow(); } @@ -161,14 +161,14 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) } else { if (starting_conditions_passing) { // If the height is relative to the ground, terrain height cannot be observed. - _hagl_sensor_status.flags.flow = (_height_sensor_ref != HeightSensor::RANGE); + _control_status.flags.opt_flow_terrain = (_height_sensor_ref != HeightSensor::RANGE); if (isHorizontalAidingActive()) { - if (fuseOptFlow(H, _hagl_sensor_status.flags.flow)) { + if (fuseOptFlow(H, _control_status.flags.opt_flow_terrain)) { ECL_INFO("starting optical flow"); _control_status.flags.opt_flow = true; - } else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) { + } else if (_control_status.flags.opt_flow_terrain && !_control_status.flags.rng_terrain) { ECL_INFO("starting optical flow, resetting terrain"); resetTerrainToFlow(); _control_status.flags.opt_flow = true; @@ -180,14 +180,14 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) resetFlowFusion(); _control_status.flags.opt_flow = true; - } else if (_hagl_sensor_status.flags.flow) { + } else if (_control_status.flags.opt_flow_terrain) { ECL_INFO("starting optical flow, resetting terrain"); resetTerrainToFlow(); _control_status.flags.opt_flow = true; } } - _hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); + _control_status.flags.opt_flow_terrain = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE); } } @@ -233,7 +233,7 @@ void Ekf::stopFlowFusion() if (_control_status.flags.opt_flow) { ECL_INFO("stopping optical flow fusion"); _control_status.flags.opt_flow = false; - _hagl_sensor_status.flags.flow = false; + _control_status.flags.opt_flow_terrain = false; _fault_status.flags.bad_optflow_X = false; _fault_status.flags.bad_optflow_Y = false; 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 93e15766eac7..2bc07e7b22c7 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 @@ -112,11 +112,11 @@ void Ekf::controlRangeHaglFusion() && _range_sensor.isRegularlySendingData(); - const bool do_conditional_range_aid = (_hagl_sensor_status.flags.range_finder || _control_status.flags.rng_hgt) + const bool do_conditional_range_aid = (_control_status.flags.rng_terrain || _control_status.flags.rng_hgt) && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) && isConditionalRangeAidSuitable(); - const bool do_range_aid = (_hagl_sensor_status.flags.range_finder || _control_status.flags.rng_hgt) + const bool do_range_aid = (_control_status.flags.rng_terrain || _control_status.flags.rng_hgt) && (_params.rng_ctrl == static_cast(RngCtrl::ENABLED)); if (_control_status.flags.rng_hgt) { @@ -135,7 +135,7 @@ void Ekf::controlRangeHaglFusion() _control_status.flags.rng_hgt = true; stopRngTerrFusion(); - if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) { + if (!_control_status.flags.opt_flow_terrain && aid_src.innovation_rejected) { resetTerrainToRng(aid_src); } @@ -159,17 +159,17 @@ void Ekf::controlRangeHaglFusion() ECL_INFO("starting %s height fusion", HGT_SRC_NAME); _control_status.flags.rng_hgt = true; - if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) { + if (!_control_status.flags.opt_flow_terrain && aid_src.innovation_rejected) { resetTerrainToRng(aid_src); } } } } - if (_control_status.flags.rng_hgt || _hagl_sensor_status.flags.range_finder) { + if (_control_status.flags.rng_hgt || _control_status.flags.rng_terrain) { if (continuing_conditions_passing) { - fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _hagl_sensor_status.flags.range_finder); + fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _control_status.flags.rng_terrain); const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max); @@ -187,7 +187,7 @@ void Ekf::controlRangeHaglFusion() } else if (is_fusion_failing) { // Some other height source is still working - if (_hagl_sensor_status.flags.flow && isTerrainEstimateValid()) { + if (_control_status.flags.opt_flow_terrain && isTerrainEstimateValid()) { ECL_WARN("stopping %s fusion, fusion failing", HGT_SRC_NAME); stopRngHgtFusion(); stopRngTerrFusion(); @@ -205,10 +205,10 @@ void Ekf::controlRangeHaglFusion() } else { if (starting_conditions_passing) { - if (_hagl_sensor_status.flags.flow) { + if (_control_status.flags.opt_flow_terrain) { if (!aid_src.innovation_rejected) { - _hagl_sensor_status.flags.range_finder = true; - fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _hagl_sensor_status.flags.range_finder); + _control_status.flags.rng_terrain = true; + fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _control_status.flags.rng_terrain); } } else { @@ -216,12 +216,12 @@ void Ekf::controlRangeHaglFusion() resetTerrainToRng(aid_src); } - _hagl_sensor_status.flags.range_finder = true; + _control_status.flags.rng_terrain = true; } } } - } else if ((_control_status.flags.rng_hgt || _hagl_sensor_status.flags.range_finder) + } else if ((_control_status.flags.rng_hgt || _control_status.flags.rng_terrain) && !isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. ECL_WARN("stopping %s fusion, no data", HGT_SRC_NAME); @@ -317,5 +317,5 @@ void Ekf::stopRngHgtFusion() void Ekf::stopRngTerrFusion() { - _hagl_sensor_status.flags.range_finder = false; + _control_status.flags.rng_terrain = false; } diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index ae1d185860d9..3a1648b3d80a 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -581,7 +581,9 @@ union filter_control_status_u { uint64_t mag : 1; ///< 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended uint64_t ev_yaw_fault : 1; ///< 36 - true when the EV heading has been declared faulty and is no longer being used uint64_t mag_heading_consistent : 1; ///< 37 - true when the heading obtained from mag data is declared consistent with the filter - uint64_t aux_gpos : 1; + uint64_t aux_gpos : 1; ///< 38 - true if auxiliary global position measurement fusion is intended + uint64_t rng_terrain : 1; ///< 39 - true if we are fusing range finder data for terrain + uint64_t opt_flow_terrain : 1; ///< 40 - true if we are fusing flow data for terrain } flags; uint64_t value; @@ -606,16 +608,6 @@ union ekf_solution_status_u { uint16_t value; }; -#if defined(CONFIG_EKF2_TERRAIN) -union terrain_fusion_status_u { - struct { - bool range_finder : 1; ///< 0 - true if we are fusing range finder data - bool flow : 1; ///< 1 - true if we are fusing flow data - } flags; - uint8_t value; -}; -#endif // CONFIG_EKF2_TERRAIN - // define structure used to communicate information events union information_event_status_u { struct { diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index b3f52e18d3da..42ea84aa1f8a 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -100,8 +100,6 @@ class Ekf final : public EstimatorInterface // terrain estimate bool isTerrainEstimateValid() const; - uint8_t getTerrainEstimateSensorBitfield() const { return _hagl_sensor_status.value; } - // get the estimated terrain vertical position relative to the NED origin float getTerrainVertPos() const { return _state.terrain; }; float getHagl() const { return _state.terrain - _state.pos(2); } @@ -585,7 +583,6 @@ class Ekf final : public EstimatorInterface // Terrain height state estimation uint8_t _terrain_vpos_reset_counter{0}; ///< number of times _terrain_vpos has been reset - terrain_fusion_status_u _hagl_sensor_status{}; ///< Struct indicating type of sensor used to estimate height above ground float _last_on_ground_posD{0.0f}; ///< last vertical position when the in_air status was false (m) #endif // CONFIG_EKF2_TERRAIN diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 5ac5f5467d95..621ac87c6571 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -266,7 +266,7 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl float flow_hagl_max = _flow_max_distance; // only limit optical flow height is dependent on range finder or terrain estimate invalid (precaution) - if ((!_hagl_sensor_status.flags.flow && _hagl_sensor_status.flags.range_finder) + if ((!_control_status.flags.opt_flow_terrain && _control_status.flags.rng_terrain) || !isTerrainEstimateValid() ) { flow_hagl_min = math::max(flow_hagl_min, rangefinder_hagl_min); @@ -472,7 +472,7 @@ float Ekf::getHeightAboveGroundInnovationTestRatio() const #if defined(CONFIG_EKF2_TERRAIN) # if defined(CONFIG_EKF2_RANGE_FINDER) - if (_hagl_sensor_status.flags.range_finder) { + if (_control_status.flags.rng_terrain) { // return the terrain height innovation test ratio test_ratio = math::max(test_ratio, fabsf(_aid_src_rng_hgt.test_ratio_filtered)); } diff --git a/src/modules/ekf2/EKF/terrain_control.cpp b/src/modules/ekf2/EKF/terrain_control.cpp index c21b7b35d847..8f277abac6f9 100644 --- a/src/modules/ekf2/EKF/terrain_control.cpp +++ b/src/modules/ekf2/EKF/terrain_control.cpp @@ -64,8 +64,8 @@ void Ekf::controlTerrainFakeFusion() } if (!_control_status.flags.in_air - && !_hagl_sensor_status.flags.range_finder - && !_hagl_sensor_status.flags.flow) { + && !_control_status.flags.rng_terrain + && !_control_status.flags.opt_flow_terrain) { bool recent_terrain_aiding = false; @@ -93,7 +93,7 @@ bool Ekf::isTerrainEstimateValid() const #if defined(CONFIG_EKF2_RANGE_FINDER) // Assume that the terrain estimate is always valid when direct observations are fused - if (_hagl_sensor_status.flags.range_finder && isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)5e6)) { + if (_control_status.flags.rng_terrain && isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)5e6)) { valid = true; } diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 9c330f5f4076..62a0af99ad70 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1644,7 +1644,17 @@ void EKF2::PublishLocalPosition(const hrt_abstime ×tamp) // Distance to bottom surface (ground) in meters, must be positive lpos.dist_bottom = math::max(_ekf.getHagl(), 0.f); lpos.dist_bottom_valid = _ekf.isTerrainEstimateValid(); - lpos.dist_bottom_sensor_bitfield = _ekf.getTerrainEstimateSensorBitfield(); + + lpos.dist_bottom_sensor_bitfield = vehicle_local_position_s::DIST_BOTTOM_SENSOR_NONE; + + if (_ekf.control_status_flags().rng_terrain) { + lpos.dist_bottom_sensor_bitfield |= vehicle_local_position_s::DIST_BOTTOM_SENSOR_RANGE; + } + + if (_ekf.control_status_flags().opt_flow_terrain) { + lpos.dist_bottom_sensor_bitfield |= vehicle_local_position_s::DIST_BOTTOM_SENSOR_FLOW; + } + #endif // CONFIG_EKF2_TERRAIN _ekf.get_ekf_lpos_accuracy(&lpos.eph, &lpos.epv); @@ -1937,6 +1947,8 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_ev_yaw_fault = _ekf.control_status_flags().ev_yaw_fault; status_flags.cs_mag_heading_consistent = _ekf.control_status_flags().mag_heading_consistent; status_flags.cs_aux_gpos = _ekf.control_status_flags().aux_gpos; + status_flags.cs_rng_terrain = _ekf.control_status_flags().rng_terrain; + status_flags.cs_opt_flow_terrain = _ekf.control_status_flags().opt_flow_terrain; status_flags.fault_status_changes = _filter_fault_status_changes; status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x; diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp index 148f30cfe427..26a1dd73c605 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp @@ -242,16 +242,12 @@ bool EkfWrapper::isWindVelocityEstimated() const bool EkfWrapper::isIntendingTerrainRngFusion() const { - terrain_fusion_status_u terrain_status; - terrain_status.value = _ekf->getTerrainEstimateSensorBitfield(); - return terrain_status.flags.range_finder; + return _ekf->control_status_flags().rng_terrain; } bool EkfWrapper::isIntendingTerrainFlowFusion() const { - terrain_fusion_status_u terrain_status; - terrain_status.value = _ekf->getTerrainEstimateSensorBitfield(); - return terrain_status.flags.flow; + return _ekf->control_status_flags().opt_flow_terrain; } Eulerf EkfWrapper::getEulerAngles() const From 5d08b97fd707b6153d1f162de8dae6eb365888ab Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 28 Jun 2024 15:24:39 -0400 Subject: [PATCH 462/652] ekf2: add vehicle_local_position dist_bottom_var --- msg/VehicleLocalPosition.msg | 1 + src/modules/ekf2/EKF2.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/msg/VehicleLocalPosition.msg b/msg/VehicleLocalPosition.msg index c1a0dffe14f6..25551ab4fb70 100644 --- a/msg/VehicleLocalPosition.msg +++ b/msg/VehicleLocalPosition.msg @@ -56,6 +56,7 @@ float32 ref_alt # Reference altitude AMSL, (metres) # Distance to surface float32 dist_bottom # Distance from from bottom surface to ground, (metres) +float32 dist_bottom_var # terrain estimate variance (m^2) bool dist_bottom_valid # true if distance to bottom surface is valid uint8 dist_bottom_sensor_bitfield # bitfield indicating what type of sensor is used to estimate dist_bottom uint8 DIST_BOTTOM_SENSOR_NONE = 0 diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 62a0af99ad70..64725d2bec7f 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1643,6 +1643,7 @@ void EKF2::PublishLocalPosition(const hrt_abstime ×tamp) #if defined(CONFIG_EKF2_TERRAIN) // Distance to bottom surface (ground) in meters, must be positive lpos.dist_bottom = math::max(_ekf.getHagl(), 0.f); + lpos.dist_bottom_var = _ekf.getTerrainVariance(); lpos.dist_bottom_valid = _ekf.isTerrainEstimateValid(); lpos.dist_bottom_sensor_bitfield = vehicle_local_position_s::DIST_BOTTOM_SENSOR_NONE; From 62ff39a669b08dbec8182263928409def32de365 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 9 Jul 2024 10:16:12 -0400 Subject: [PATCH 463/652] ekf2: EV vel (body) update last fuse timestamps - these are set by the NED fuseVelocity() helper so also need to be set in the body frame velocity case --- .../ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp index c338b75ba136..62781e5081ac 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp @@ -292,6 +292,11 @@ bool Ekf::fuseEvVelocity(estimator_aid_source3d_s &aid_src, const extVisionSampl } + if (aid_src.fused) { + _time_last_hor_vel_fuse = _time_delayed_us; + _time_last_ver_vel_fuse = _time_delayed_us; + } + aid_src.timestamp_sample = current_aid_src.timestamp_sample; return !aid_src.innovation_rejected; From 419652b9fed281ca187b1f24209e4dce9016c7d5 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Tue, 9 Jul 2024 16:31:11 +0200 Subject: [PATCH 464/652] EKF2: Spoofing GPS check (#23366) * estimator gps check fail flag for spoofing * warn whenever spoofing state changes to true, use default hysteresis to completely stop fusion * dont introduce more GPS namings, GNSS instead * flash: exclude mantis for cuav_x7pro --- .../init.d/airframes/4061_atl_mantis_edu | 1 + msg/EstimatorGpsStatus.msg | 1 + msg/EstimatorStatus.msg | 1 + .../checks/estimatorCheck.cpp | 28 +++++++++++++++++++ .../checks/estimatorCheck.hpp | 2 +- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 24 +++++++++------- src/modules/ekf2/EKF/common.h | 2 ++ src/modules/ekf2/EKF2.cpp | 2 ++ src/modules/ekf2/module.yaml | 5 ++-- 9 files changed, 53 insertions(+), 13 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index 2e52f24ac1d4..e5e5e083437f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -7,6 +7,7 @@ # # @maintainer # @board px4_fmu-v2 exclude +# @board cuav_x7pro exclude # @board px4_fmu-v4pro exclude # @board px4_fmu-v5x exclude # @board px4_fmu-v6x exclude diff --git a/msg/EstimatorGpsStatus.msg b/msg/EstimatorGpsStatus.msg index 2d2462ee5c30..b2a9c883944e 100644 --- a/msg/EstimatorGpsStatus.msg +++ b/msg/EstimatorGpsStatus.msg @@ -13,6 +13,7 @@ bool check_fail_max_horz_drift # 6 : maximum allowed horizontal position drift bool check_fail_max_vert_drift # 7 : maximum allowed vertical position drift fail - requires stationary vehicle bool check_fail_max_horz_spd_err # 8 : maximum allowed horizontal speed fail - requires stationary vehicle bool check_fail_max_vert_spd_err # 9 : maximum allowed vertical velocity discrepancy fail +bool check_fail_spoofed_gps # 10 : GPS signal is spoofed float32 position_drift_rate_horizontal_m_s # Horizontal position rate magnitude (m/s) float32 position_drift_rate_vertical_m_s # Vertical position rate magnitude (m/s) diff --git a/msg/EstimatorStatus.msg b/msg/EstimatorStatus.msg index ac13b59ea7ee..a603a0f5ad86 100644 --- a/msg/EstimatorStatus.msg +++ b/msg/EstimatorStatus.msg @@ -15,6 +15,7 @@ uint8 GPS_CHECK_FAIL_MAX_HORZ_DRIFT = 6 # 6 : maximum allowed horizontal positi uint8 GPS_CHECK_FAIL_MAX_VERT_DRIFT = 7 # 7 : maximum allowed vertical position drift fail - requires stationary vehicle uint8 GPS_CHECK_FAIL_MAX_HORZ_SPD_ERR = 8 # 8 : maximum allowed horizontal speed fail - requires stationary vehicle uint8 GPS_CHECK_FAIL_MAX_VERT_SPD_ERR = 9 # 9 : maximum allowed vertical velocity discrepancy fail +uint8 GPS_CHECK_FAIL_SPOOFED = 10 # 10 : GPS signal is spoofed uint64 control_mode_flags # Bitmask to indicate EKF logic state uint8 CS_TILT_ALIGN = 0 # 0 - true if the filter tilt alignment is complete diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index c67fdfd21343..7441e76f08c2 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -318,6 +318,22 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor _gps_was_fused = ekf_gps_fusion; + if (estimator_status.gps_check_fail_flags & (1 << estimator_status_s::GPS_CHECK_FAIL_SPOOFED)) { + if (!_gnss_spoofed) { + _gnss_spoofed = true; + + if (reporter.mavlink_log_pub()) { + mavlink_log_critical(reporter.mavlink_log_pub(), "GNSS signal spoofed\t"); + } + + events::send(events::ID("check_estimator_gnss_warning_spoofing"), {events::Log::Alert, events::LogInternal::Info}, + "GNSS signal spoofed"); + } + + } else { + _gnss_spoofed = false; + } + if (!context.isArmed() && ekf_gps_check_fail) { NavModes required_groups_gps = required_groups; events::Log log_level = events::Log::Error; @@ -450,6 +466,18 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor events::ID("check_estimator_gps_vert_speed_drift_too_high"), log_level, "GPS Vertical Speed Drift too high"); + } else if (estimator_status.gps_check_fail_flags & (1 << estimator_status_s::GPS_CHECK_FAIL_SPOOFED)) { + message = "Preflight%s: GPS signal spoofed"; + /* EVENT + * @description + * + * This check can be configured via EKF2_GPS_CHECK parameter. + * + */ + reporter.armingCheckFailure(required_groups_gps, health_component_t::gps, + events::ID("check_estimator_gps_spoofed"), + log_level, "GPS signal spoofed"); + } else { if (!ekf_gps_fusion) { // Likely cause unknown diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp index 7f41a9c86dbb..c900e95b8a0d 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp @@ -64,7 +64,6 @@ class EstimatorChecks : public HealthAndArmingCheckBase void checkSensorBias(const Context &context, Report &reporter, NavModes required_groups); void checkEstimatorStatusFlags(const Context &context, Report &reporter, const estimator_status_s &estimator_status, const vehicle_local_position_s &lpos); - void checkGps(const Context &context, Report &reporter, const sensor_gps_s &vehicle_gps_position) const; void lowPositionAccuracy(const Context &context, Report &reporter, const vehicle_local_position_s &lpos) const; void setModeRequirementFlags(const Context &context, bool pre_flt_fail_innov_heading, bool pre_flt_fail_innov_vel_horiz, @@ -102,6 +101,7 @@ class EstimatorChecks : public HealthAndArmingCheckBase bool _position_reliant_on_optical_flow{false}; bool _gps_was_fused{false}; + bool _gnss_spoofed{false}; bool _nav_failure_imminent_warned{false}; 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 abdbec64fc1a..a598f1078b66 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -48,15 +48,16 @@ #include // GPS pre-flight check bit locations -#define MASK_GPS_NSATS (1<<0) -#define MASK_GPS_PDOP (1<<1) -#define MASK_GPS_HACC (1<<2) -#define MASK_GPS_VACC (1<<3) -#define MASK_GPS_SACC (1<<4) -#define MASK_GPS_HDRIFT (1<<5) -#define MASK_GPS_VDRIFT (1<<6) -#define MASK_GPS_HSPD (1<<7) -#define MASK_GPS_VSPD (1<<8) +#define MASK_GPS_NSATS (1<<0) +#define MASK_GPS_PDOP (1<<1) +#define MASK_GPS_HACC (1<<2) +#define MASK_GPS_VACC (1<<3) +#define MASK_GPS_SACC (1<<4) +#define MASK_GPS_HDRIFT (1<<5) +#define MASK_GPS_VDRIFT (1<<6) +#define MASK_GPS_HSPD (1<<7) +#define MASK_GPS_VSPD (1<<8) +#define MASK_GPS_SPOOFED (1<<9) void Ekf::collect_gps(const gnssSample &gps) { @@ -136,6 +137,8 @@ void Ekf::collect_gps(const gnssSample &gps) bool Ekf::runGnssChecks(const gnssSample &gps) { + _gps_check_fail_status.flags.spoofed = gps.spoofed; + // Check the fix type _gps_check_fail_status.flags.fix = (gps.fix_type < 3); @@ -240,7 +243,8 @@ bool Ekf::runGnssChecks(const gnssSample &gps) (_gps_check_fail_status.flags.hdrift && (_params.gps_check_mask & MASK_GPS_HDRIFT)) || (_gps_check_fail_status.flags.vdrift && (_params.gps_check_mask & MASK_GPS_VDRIFT)) || (_gps_check_fail_status.flags.hspeed && (_params.gps_check_mask & MASK_GPS_HSPD)) || - (_gps_check_fail_status.flags.vspeed && (_params.gps_check_mask & MASK_GPS_VSPD)) + (_gps_check_fail_status.flags.vspeed && (_params.gps_check_mask & MASK_GPS_VSPD)) || + (_gps_check_fail_status.flags.spoofed && (_params.gps_check_mask & MASK_GPS_SPOOFED)) ) { _last_gps_fail_us = _time_delayed_us; return false; diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 3a1648b3d80a..b8e7664bf94c 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -183,6 +183,7 @@ struct gnssSample { float yaw{}; ///< yaw angle. NaN if not set (used for dual antenna GPS), (rad, [-PI, PI]) float yaw_acc{}; ///< 1-std yaw error (rad) float yaw_offset{}; ///< Heading/Yaw offset for dual antenna GPS - refer to description for GPS_YAW_OFFSET + bool spoofed{}; ///< true if GNSS data is spoofed }; struct magSample { @@ -536,6 +537,7 @@ union gps_check_fail_status_u { uint16_t vdrift : 1; ///< 7 - true if vertical drift is excessive (can only be used when stationary on ground) uint16_t hspeed : 1; ///< 8 - true if horizontal speed is excessive (can only be used when stationary on ground) uint16_t vspeed : 1; ///< 9 - true if vertical speed error is excessive + uint16_t spoofed: 1; ///< 10 - true if the GNSS data is spoofed } flags; uint16_t value; }; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 64725d2bec7f..4fa40399b369 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1253,6 +1253,7 @@ void EKF2::PublishGpsStatus(const hrt_abstime ×tamp) estimator_gps_status.check_fail_max_vert_drift = _ekf.gps_check_fail_status_flags().vdrift; estimator_gps_status.check_fail_max_horz_spd_err = _ekf.gps_check_fail_status_flags().hspeed; estimator_gps_status.check_fail_max_vert_spd_err = _ekf.gps_check_fail_status_flags().vspeed; + estimator_gps_status.check_fail_spoofed_gps = _ekf.gps_check_fail_status_flags().spoofed; estimator_gps_status.timestamp = _replay_mode ? timestamp : hrt_absolute_time(); _estimator_gps_status_pub.publish(estimator_gps_status); @@ -2460,6 +2461,7 @@ void EKF2::UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps) .yaw = vehicle_gps_position.heading, //TODO: move to different message .yaw_acc = vehicle_gps_position.heading_accuracy, .yaw_offset = vehicle_gps_position.heading_offset, + .spoofed = vehicle_gps_position.spoofing_state == sensor_gps_s::SPOOFING_STATE_MULTIPLE, }; _ekf.setGpsData(gnss_sample); diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index be11bd97b353..848ca02a9bf6 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -136,7 +136,7 @@ parameters: run when the vehicle is on ground and stationary. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. 8 : Maximum allowed vertical velocity discrepancy - set by EKF2_REQ_VDRIFT' + set by EKF2_REQ_VDRIFT. 9: Fails if GPS driver detects consistent spoofing' type: bitmask bit: 0: Min sat count (EKF2_REQ_NSATS) @@ -148,9 +148,10 @@ parameters: 6: Max vertical position rate (EKF2_REQ_VDRIFT) 7: Max horizontal speed (EKF2_REQ_HDRIFT) 8: Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) + 9: Spoofing check default: 245 min: 0 - max: 511 + max: 1023 EKF2_REQ_EPH: description: short: Required EPH to use GPS From 223397c20e4d72c5485669b9a221d974540ed9bd Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 28 Jun 2024 17:21:06 -0400 Subject: [PATCH 465/652] ekf2: always add accel/gyro bias process noise - continue adding accel/gyro bias process noise even if inhibited --- src/modules/ekf2/EKF/covariance.cpp | 8 +- .../test/change_indication/ekf_gsf_reset.csv | 178 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 76 ++++---- 3 files changed, 131 insertions(+), 131 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 60a865d2dea2..519cbbcfa28f 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -138,7 +138,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) // Construct the process noise variance diagonal for those states with a stationary process model // These are kinematic states and their error growth is controlled separately by the IMU noise variances - // gyro bias: add process noise unless state is inhibited + // gyro bias: add process noise { const float gyro_bias_sig = dt * math::constrain(_params.gyro_bias_p_noise, 0.f, 1.f); const float gyro_bias_process_noise = sq(gyro_bias_sig); @@ -146,13 +146,13 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) for (unsigned index = 0; index < State::gyro_bias.dof; index++) { const unsigned i = State::gyro_bias.idx + index; - if (!_gyro_bias_inhibit[index]) { + if (P(i, i) < gyro_var) { P(i, i) += gyro_bias_process_noise; } } } - // accel bias: add process noise unless state is inhibited + // accel bias: add process noise { const float accel_bias_sig = dt * math::constrain(_params.accel_bias_p_noise, 0.f, 1.f); const float accel_bias_process_noise = sq(accel_bias_sig); @@ -160,7 +160,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) for (unsigned index = 0; index < State::accel_bias.dof; index++) { const unsigned i = State::accel_bias.idx + index; - if (!_accel_bias_inhibit[index]) { + if (P(i, i) < accel_var(index)) { P(i, i) += accel_bias_process_noise; } } 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 50f65f6fa51c..4c928c8ca1ad 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -75,14 +75,14 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.098,-0.14,-0.3,-0.082,-3.7e+02,5.3e-05,-0.011,-0.00022,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1,1.9 7390000,0.78,-0.024,0.0068,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,7.4e-05,-0.011,-0.00022,-0.0017,-0.00046,8.6e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1,1.9 7490000,0.78,-0.024,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00021,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 -7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 +7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00052,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00029,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1,2 7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0061,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1,2 -7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 +7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.0004,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.00044,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1,2.1 8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 -8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 +8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.2e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 8390000,0.78,-0.024,0.007,-0.63,-0.18,-0.036,-0.17,-0.48,-0.15,-3.7e+02,0.00055,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 8490000,0.78,-0.024,0.007,-0.63,-0.2,-0.04,-0.17,-0.49,-0.15,-3.7e+02,0.00056,-0.0099,-0.0002,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 8590000,0.78,-0.023,0.0072,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 @@ -92,41 +92,41 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 8990000,0.78,-0.023,0.0068,-0.63,-0.27,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00045,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0026,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 9090000,0.78,-0.022,0.0068,-0.63,-0.29,-0.054,-0.14,-0.58,-0.17,-3.7e+02,0.00037,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 9190000,0.78,-0.022,0.0061,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00038,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.3 -9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.5e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 +9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.6e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 9390000,0.78,-0.022,0.0057,-0.63,-0.33,-0.082,-0.13,-0.65,-0.19,-3.7e+02,0.00043,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 9490000,0.78,-0.022,0.0052,-0.63,-0.33,-0.095,-0.13,-0.67,-0.21,-3.7e+02,0.00046,-0.0082,-0.00015,-0.0018,0.00038,-0.067,-0.11,-0.025,0.5,-0.0032,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 -9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 +9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00066,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 9690000,0.78,-0.022,0.0051,-0.63,-0.36,-0.092,-0.12,-0.73,-0.22,-3.7e+02,0.00022,-0.008,-0.00014,-0.0021,0.0009,-0.075,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 9790000,0.78,-0.022,0.0047,-0.63,-0.37,-0.1,-0.11,-0.75,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 9890000,0.78,-0.021,0.0045,-0.63,-0.37,-0.11,-0.11,-0.78,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,2.9e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 9990000,0.78,-0.021,0.0045,-0.63,-0.39,-0.11,-0.1,-0.81,-0.25,-3.7e+02,9.8e-05,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.0031,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.5 -10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.1e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 +10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.2e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 10190000,0.78,-0.021,0.0045,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-4.1e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 10290000,0.78,-0.021,0.0047,-0.63,-0.44,-0.1,-0.083,-0.92,-0.27,-3.7e+02,-6.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 10390000,0.78,-0.021,0.0045,-0.63,-0.0085,-0.022,0.0097,8e-05,-0.0019,-3.7e+02,-5.8e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 10490000,0.78,-0.021,0.0046,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-8e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 10590000,0.78,-0.02,0.0043,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00026,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 10690000,0.78,-0.02,0.0042,-0.63,-0.043,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 -10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00016,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 -10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.0001,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 +10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00015,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 +10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-9.7e-05,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.011,0.015,0.00017,-0.0012,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0036,-0.00085,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.069,0,0,-3.6e+02,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 11090000,0.78,-0.02,0.0026,-0.63,-0.06,-0.015,0.02,-0.0047,-0.0027,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0037,-0.00042,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 11190000,0.78,-0.019,0.0021,-0.63,-0.053,-0.011,0.0082,0.00075,-0.00057,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.0082,-0.0036,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 11290000,0.78,-0.019,0.0022,-0.63,-0.069,-0.013,0.008,-0.0056,-0.0018,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0083,-0.0038,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 11390000,0.78,-0.019,0.0018,-0.63,-0.064,-0.011,0.0024,0.00037,-0.00044,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 -11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0015,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 +11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0014,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 11590000,0.78,-0.019,0.0015,-0.63,-0.069,-0.012,-0.0027,-0.0021,-0.00084,-3.7e+02,-0.00061,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,-3.6e+02,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 11690000,0.78,-0.019,0.0016,-0.63,-0.08,-0.016,-0.0071,-0.0097,-0.0025,-3.7e+02,-0.00057,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,-3.6e+02,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 11790000,0.78,-0.019,0.001,-0.63,-0.072,-0.011,-0.0089,-0.0061,-0.00025,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 11890000,0.78,-0.019,0.0011,-0.63,-0.083,-0.012,-0.0098,-0.014,-0.0014,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 -11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0069,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3 -12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.3e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1 +11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0068,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3 +12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.2e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1 12190000,0.78,-0.018,-0.00031,-0.62,-0.064,-0.011,-0.016,-0.0085,-0.0004,-3.7e+02,-0.00082,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 12290000,0.78,-0.019,-0.00032,-0.62,-0.07,-0.014,-0.015,-0.015,-0.0021,-3.7e+02,-0.00079,-0.0064,-8.3e-05,0.033,-0.021,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 12390000,0.78,-0.018,-0.00073,-0.62,-0.057,-0.012,-0.013,-0.0083,-0.001,-3.7e+02,-0.00086,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 12490000,0.78,-0.018,-0.00059,-0.62,-0.064,-0.013,-0.016,-0.015,-0.0022,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.038,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.2 12590000,0.78,-0.018,-0.00079,-0.62,-0.06,-0.011,-0.022,-0.013,-0.001,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.039,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 -12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0014,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 +12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0013,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 12790000,0.78,-0.018,-0.001,-0.62,-0.061,-0.0098,-0.029,-0.017,-0.0012,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.04,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 12890000,0.78,-0.018,-0.00099,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0027,-3.7e+02,-0.00093,-0.0063,-8.2e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 12990000,0.78,-0.018,-0.0015,-0.62,-0.055,-0.01,-0.028,-0.018,-0.0026,-3.7e+02,-0.00097,-0.0062,-8e-05,0.045,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 @@ -139,25 +139,25 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 13690000,0.78,-0.018,-0.0023,-0.62,-0.041,-0.015,-0.023,-0.018,-0.006,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.035,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 13790000,0.78,-0.018,-0.0024,-0.62,-0.029,-0.013,-0.024,-0.0067,-0.0046,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 13890000,0.78,-0.018,-0.0025,-0.62,-0.033,-0.015,-0.029,-0.01,-0.0066,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 +13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.038,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0071,-3.7e+02,-0.0011,-0.0061,-7.6e-05,0.056,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00023,-0.005,-3.7e+02,-0.0011,-0.0061,-7.5e-05,0.058,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 14290000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.015,-0.03,-0.0022,-0.0063,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.057,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.005,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 +14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.0049,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 14490000,0.78,-0.017,-0.0031,-0.62,-0.019,-0.018,-0.035,-0.00044,-0.0069,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0065,-3.7e+02,-0.001,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 14690000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.017,-0.032,-0.0034,-0.0085,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.064,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 +14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 14890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.019,-0.031,-0.006,-0.0098,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 14990000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.016,-0.027,-0.0046,-0.0077,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 15090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0093,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 15190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0075,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0043,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 15290000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.025,-0.0081,-0.0092,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.067,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.9 15390000,0.78,-0.017,-0.0031,-0.62,-0.025,-0.018,-0.023,-0.0075,-0.0094,-3.7e+02,-0.001,-0.006,-7e-05,0.067,-0.035,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 +15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0097,-0.01,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.012,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 +15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 15890000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 15990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.018,-0.0078,-0.01,-3.7e+02,-0.0011,-0.006,-7e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 16090000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0099,-0.012,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 @@ -177,11 +177,11 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 17490000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0094,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 17590000,0.78,-0.017,-0.003,-0.62,-0.024,-0.018,0.003,-0.013,-0.009,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.001,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0011,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 +17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0023,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 18090000,0.78,-0.017,-0.003,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 +18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.3e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 18290000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0072,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 18390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.063,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 18490000,0.78,-0.017,-0.003,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.7e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 @@ -200,8 +200,8 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 19790000,0.78,-0.016,-0.0032,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.6e-05,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 19890000,0.78,-0.016,-0.0032,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.3e-05,0.061,-0.031,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-3.8e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,1e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,7e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,9.8e-07,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 +20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,6.9e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 20290000,0.78,-0.016,-0.0034,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,8.7e-06,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 20390000,0.78,-0.016,-0.0033,-0.62,-0.0084,-0.016,0.017,-0.009,-0.017,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 20490000,0.78,-0.016,-0.0034,-0.62,-0.0087,-0.017,0.017,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 @@ -222,12 +222,12 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 21990000,0.78,-0.016,-0.0034,-0.62,-0.0057,-0.0035,0.017,-0.008,-0.0069,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01 22090000,0.78,-0.016,-0.0034,-0.62,-0.0054,-0.0051,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01 22190000,0.78,-0.016,-0.0034,-0.62,-0.0041,-0.0056,0.015,-0.007,-0.0066,-3.7e+02,-0.0013,-0.0059,5.9e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22290000,0.78,-0.016,-0.0034,-0.62,-0.0036,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22390000,0.78,-0.016,-0.0034,-0.62,-0.0011,-0.0052,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22490000,0.78,-0.016,-0.0034,-0.62,1.2e-05,-0.0059,0.018,-0.0053,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22490000,0.78,-0.016,-0.0034,-0.62,1.4e-05,-0.0059,0.018,-0.0053,-0.0067,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22590000,0.78,-0.016,-0.0034,-0.62,0.0019,-0.0048,0.017,-0.0036,-0.0061,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22690000,0.78,-0.016,-0.0035,-0.62,0.0034,-0.0061,0.019,-0.0029,-0.0072,-3.7e+02,-0.0014,-0.0059,7e-05,0.06,-0.027,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22790000,0.78,-0.016,-0.0034,-0.62,0.0044,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +22790000,0.78,-0.016,-0.0034,-0.62,0.0045,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22890000,0.78,-0.016,-0.0034,-0.62,0.0051,-0.0063,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0065,0.022,-0.0026,-0.0074,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0062,0.023,-0.0023,-0.0071,-3.7e+02,-0.0014,-0.0059,6.4e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 @@ -238,7 +238,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00011,-0.043,-0.0094,-0.0059,-3.7e+02,-0.0013,-0.0059,7.7e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 23690000,0.78,0.0011,-0.0087,-0.62,0.043,0.014,-0.093,-0.007,-0.0057,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 23790000,0.78,-0.0026,-0.0062,-0.62,0.064,0.031,-0.15,-0.007,-0.0037,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.2e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 +23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.3e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 23990000,0.78,-0.014,-0.0035,-0.62,0.072,0.043,-0.25,-0.005,-0.0014,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.002,-3.7e+02,-0.0013,-0.0059,8.8e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 24190000,0.78,-0.01,-0.0055,-0.62,0.07,0.041,-0.35,-0.0058,-0.00021,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.065,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 @@ -259,7 +259,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,3e-05,0.08,-0.029,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,-3.7e+02,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01 25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0015,0.042,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0036,-0.083,-0.067,0,0,-3.7e+02,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.041,0.065,-3.7e+02,-0.00099,-0.0058,5.7e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0042,-0.081,-0.066,0,0,-3.7e+02,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 -25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01 +25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.03,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01 26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.4e-05,0.08,-0.03,-0.13,-0.12,-0.029,0.5,-0.0047,-0.079,-0.065,0,0,-3.7e+02,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1,0.01 26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.03,-0.13,-0.13,-0.03,0.5,-0.0055,-0.075,-0.063,0,0,-3.7e+02,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1,0.01 26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.8e-05,0.081,-0.03,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,-3.7e+02,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1,0.01 @@ -285,7 +285,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.3e-05,0.084,-0.023,-0.13,-0.17,-0.04,0.46,-0.0049,-0.029,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1,0.01 28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,7.9e-05,0.084,-0.022,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 28490000,0.78,0.0015,-0.006,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 -28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.3e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 +28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 28690000,0.78,-0.0031,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,6.8e-05,0.083,-0.021,-0.12,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 28790000,0.78,-0.0035,-0.0038,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.4e-05,0.083,-0.02,-0.12,-0.17,-0.041,0.46,-0.0043,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1,0.01 28890000,0.78,-0.0032,-0.0038,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6e-05,0.082,-0.02,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1,0.01 @@ -302,90 +302,90 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 29990000,0.78,0.0036,-0.0058,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.4e-05,0.079,-0.013,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1,0.01 30090000,0.78,0.0035,-0.0058,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1e-05,0.079,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1,0.01 30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.1e-05,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1,0.01 -30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.4e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01 +30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.3e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01 30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,4.2e-06,0.077,-0.011,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 -30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3.1e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 -30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.9e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01 +30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 +30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.7e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01 30690000,0.78,0.0018,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-2.3e-06,0.077,-0.0087,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 30790000,0.78,0.0014,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-5.4e-06,0.076,-0.0085,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 -30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.3e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01 +30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.4e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01 30990000,0.78,0.00035,-0.0051,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1.2e-05,0.075,-0.0069,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1,0.01 31090000,0.78,-0.00019,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.6e-05,0.075,-0.0062,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 31190000,0.78,-0.00061,-0.0048,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.9e-05,0.075,-0.0054,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.075,-0.0047,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 -31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.004,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 +31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.0041,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 31490000,0.78,-0.0025,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-3e-05,0.074,-0.0033,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 31590000,0.78,-0.0029,-0.0043,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3.1e-05,0.073,-0.0026,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1,0.01 31690000,0.78,-0.0037,-0.0041,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.073,-0.0019,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 31790000,0.78,-0.0044,-0.0039,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.6e-05,0.072,-0.001,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00016,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00077,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00017,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 +31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00076,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.96,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-4.9e-05,0.071,0.0015,-0.11,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.8,-3.7e+02,-0.0012,-0.0057,-5.8e-05,0.07,0.0024,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.07,0.0034,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.069,0.0041,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01 +32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01 32590000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.9e-05,0.069,0.0052,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.068,0.0058,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0062,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.024,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.067,0.0067,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 -32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.7e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 +32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 33090000,0.79,-0.0091,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.066,0.0075,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1,0.01 33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1,0.01 33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.065,0.0071,-0.11,-0.18,-0.041,0.46,-0.00098,-0.027,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8.1e-05,0.00032,0.00039,1,1,0.01 -33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0072,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01 -33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0072,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01 -33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0072,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01 -33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01 -33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01 +33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0071,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01 +33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0071,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01 +33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0071,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01 +33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01 +33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01 33990000,0.86,-0.015,0.0071,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0069,-0.11,-0.2,-0.046,0.46,0.0005,-0.0039,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1,0.01 -34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01 -34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01 -34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01 -34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.4e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01 -34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01 -34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.3e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01 -34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-4.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01 +34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.9e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01 +34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01 +34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01 +34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.3e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01 +34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01 +34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.4e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01 +34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-5.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01 34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0051,-0.11,-0.2,-0.047,0.46,0.00012,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1,0.01 -34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01 +34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01 34990000,0.64,-0.0062,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00018,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1,0.01 35090000,0.64,-0.0063,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1,0.01 -35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01 -35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01 -35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01 -35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01 -35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 -35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 -35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 -35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 -35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 -36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 -36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 -36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 -36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 -36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 -36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 -36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 -36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 -36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0052,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 -36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 -37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 -37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 -37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 -37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 -37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 -37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 -37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 -37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 -37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 -37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 -38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 -38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 -38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 -38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 -38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 -38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 -38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 -38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.87,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 -38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 +35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01 +35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01 +35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01 +35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01 +35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 +35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0048,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 +35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 +35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 +35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 +36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 +36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 +36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 +36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 +36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 +36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 +36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 +36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 +36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0051,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 +36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 +37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 +37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 +37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 +37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 +37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 +37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 +37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 +37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 +37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0066,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 +37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 +38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 +38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 +38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 +38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 +38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 +38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 +38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 +38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 +38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index f205da08db4c..7204af4ab9c8 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -67,8 +67,8 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6590000,1,-0.0089,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6690000,1,-0.0088,-0.011,0.0005,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.00047,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,8.1e-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.00039,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,8.1e-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 +6790000,1,-0.0089,-0.011,0.00047,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.00039,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.29,0.024,-0.0061,0.96,-0.2,-0.032,-0.037,-0.11,-0.019,-0.055,-0.00077,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.095,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1,1.8 7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.048,-0.038,-0.15,-0.027,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.095,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1,1.8 7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1,1.8 @@ -93,20 +93,20 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 9090000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0099,-0.72,-0.24,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00029,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 9190000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0095,-0.73,-0.24,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00042,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.095,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.3 9290000,-0.29,0.02,-0.006,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00048,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0076,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 +9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 9490000,-0.29,0.019,-0.0059,0.96,-0.46,-0.17,-0.0055,-0.78,-0.29,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00055,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00086,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4 +9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4 9690000,-0.29,0.019,-0.0058,0.96,-0.46,-0.2,-0.0026,-0.83,-0.37,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00041,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00076,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00052,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 +9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 9990000,-0.29,0.019,-0.0057,0.96,-0.48,-0.23,-0.002,-0.92,-0.47,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.5 -10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00044,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 10190000,-0.29,0.019,-0.0055,0.96,-0.49,-0.27,5.1e-05,-0.97,-0.6,-0.031,-0.00028,-0.007,-0.00015,-0.00027,0.00012,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 10290000,-0.29,0.019,-0.0055,0.96,-0.48,-0.27,-0.0011,-0.97,-0.61,-0.03,-0.00034,-0.0069,-0.00014,-0.00015,0.00018,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,3.7e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00014,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00011,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,9.3e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 +10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 +10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00015,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 10790000,-0.29,0.019,-0.005,0.96,-0.033,-0.015,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,5.9e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 10890000,-0.29,0.019,-0.0049,0.96,-0.043,-0.02,0.01,-0.0036,-0.0035,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.8 10990000,-0.29,0.019,-0.005,0.96,-0.039,-0.022,0.016,-0.0014,-0.0019,-0.012,-0.00058,-0.0064,-0.00012,0.0058,0.00072,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 @@ -149,18 +149,18 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 14690000,-0.29,0.015,-0.0049,0.96,-0.016,-0.0041,0.018,-0.00088,-0.0058,0.01,-0.0007,-0.0059,-0.00011,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 14790000,-0.29,0.015,-0.005,0.96,-0.019,-0.0015,0.018,-0.00058,-0.0013,0.013,-0.00073,-0.0058,-0.00011,0.065,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.00041,0.022,-0.0027,-0.0017,0.014,-0.00074,-0.0058,-0.00011,0.065,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0015,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 +14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0016,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 15090000,-0.29,0.015,-0.0048,0.96,-0.021,-0.0027,0.029,-0.0043,-0.0031,0.018,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00079,0.029,-0.0034,-0.0024,0.02,-0.00073,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 15290000,-0.29,0.016,-0.005,0.96,-0.024,-0.00091,0.029,-0.0058,-0.0029,0.017,-0.00075,-0.0057,-0.00011,0.067,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 +15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 15490000,-0.29,0.016,-0.0051,0.96,-0.025,-0.00034,0.028,-0.007,-0.0026,0.018,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0047,0.028,-0.0032,-0.0058,0.017,-0.00079,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 15690000,-0.29,0.016,-0.005,0.96,-0.024,-0.0026,0.028,-0.0048,-0.0062,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 15790000,-0.29,0.015,-0.005,0.96,-0.021,-0.0013,0.028,-0.0035,-0.0053,0.019,-0.00087,-0.0058,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 15890000,-0.29,0.016,-0.0051,0.96,-0.021,-0.0026,0.029,-0.0059,-0.0053,0.019,-0.00084,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0021,0.026,-0.0049,-0.0045,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00082,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 +16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00083,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00061,0.023,-0.0071,-0.0037,0.015,-0.0008,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 16290000,-0.29,0.015,-0.005,0.96,-0.022,0.00033,0.022,-0.009,-0.0038,0.017,-0.00081,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 16390000,-0.29,0.016,-0.0049,0.96,-0.023,-0.00021,0.023,-0.007,-0.0037,0.017,-0.00083,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 @@ -192,7 +192,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 18990000,-0.29,0.015,-0.0048,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 19090000,-0.29,0.015,-0.0048,0.96,-0.028,0.013,0.024,-0.016,0.0063,0.024,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 19190000,-0.29,0.015,-0.0048,0.96,-0.026,0.014,0.023,-0.014,0.0062,0.023,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 +19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0074,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 19390000,-0.29,0.015,-0.0049,0.96,-0.026,0.012,0.025,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 @@ -219,7 +219,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 21690000,-0.29,0.012,-0.0018,0.96,-0.0024,-0.019,-1.1,-0.014,0.0039,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.39,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 21790000,-0.29,0.012,-0.0021,0.96,-0.0082,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.51,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0073,-1.4,-0.016,0.0096,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.65,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00089,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 +21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00088,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 22090000,-0.29,0.013,-0.0038,0.96,-0.023,0.0041,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.93,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 22190000,-0.29,0.013,-0.0042,0.96,-0.03,0.011,-1.4,-0.027,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.1,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 22290000,-0.29,0.014,-0.0049,0.96,-0.038,0.015,-1.4,-0.031,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.2,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 @@ -247,7 +247,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 24490000,-0.29,0.018,-0.0065,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 24590000,-0.29,0.018,-0.0071,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 24690000,-0.29,0.018,-0.0076,0.96,-0.045,0.044,0.075,-0.046,0.036,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 24890000,-0.29,0.017,-0.0076,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 25090000,-0.29,0.016,-0.0077,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 @@ -265,11 +265,11 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 26290000,-0.3,0.015,-0.0073,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 26390000,-0.3,0.015,-0.0067,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 26490000,-0.3,0.015,-0.0065,0.96,0.043,0.0088,0.028,0.024,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 26690000,-0.3,0.015,-0.0058,0.95,0.044,-0.0048,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 26790000,-0.3,0.014,-0.0056,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 +26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.064,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 27090000,-0.3,0.015,-0.0042,0.95,0.056,-0.026,0.025,0.028,-0.066,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.019,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 27290000,-0.3,0.016,-0.0043,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 @@ -314,38 +314,38 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 31190000,-0.29,0.016,-0.0028,0.96,0.043,-0.0042,0.8,0.094,-0.039,-0.74,-0.0012,-0.0058,-2.7e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.64,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31290000,-0.29,0.016,-0.003,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.57,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31390000,-0.29,0.015,-0.0028,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.49,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31490000,-0.29,0.016,-0.0025,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31490000,-0.29,0.016,-0.0025,0.96,0.036,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31590000,-0.29,0.016,-0.0023,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.35,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.28,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-9.9e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-1e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31890000,-0.29,0.017,-0.0022,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.4e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.14,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31990000,-0.29,0.016,-0.0025,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,5.2e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.068,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,9.3e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 +32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,8.8e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 32190000,-0.29,0.016,-0.0032,0.96,0.028,0.028,0.8,0.094,-0.0046,-0.028,-0.0012,-0.0058,3.2e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.072,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 32290000,-0.29,0.016,-0.003,0.96,0.027,0.03,0.79,0.098,-0.0019,0.042,-0.0012,-0.0058,7e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.14,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 32390000,-0.29,0.016,-0.0032,0.96,0.024,0.032,0.79,0.094,0.0018,0.12,-0.0012,-0.0058,5.2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0094,0.12,-0.0012,-0.0058,2.9e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 32590000,-0.29,0.015,-0.0063,0.96,-0.014,0.084,-0.081,0.093,0.0025,0.1,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.2,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.19,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.0059,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 +33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 +33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 33490000,-0.3,0.015,-0.0058,0.96,0.02,0.097,-0.078,0.097,0.004,-0.00072,-0.0013,-0.0058,-2.1e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 -33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 -33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.9e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 +33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 +33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.7e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.071,0.094,-0.013,-0.028,-0.0013,-0.0058,-3.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 -33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 -33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 -34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 -34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.8e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 -34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 -34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 +33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 +33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 +34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 +34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.7e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 +34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 +34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 34490000,-0.3,0.015,-0.0051,0.95,0.045,0.1,-0.055,0.097,-0.0068,-0.061,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 -34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4.1e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 -34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 +34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 +34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38 34890000,-0.3,0.014,-0.005,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41 From 03ff837c50ac186b83eab3f3507f28d34846b21e Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Fri, 28 Jun 2024 11:56:51 +0200 Subject: [PATCH 466/652] ackermann: new features and improvements added return mode support, slew rates for actuators, new ackermann specific message, improved cornering slow down effect and fixed logging issue. --- .../init.d/rc.rover_ackermann_apps | 3 - msg/CMakeLists.txt | 1 + msg/RoverAckermannGuidanceStatus.msg | 11 +- msg/RoverAckermannStatus.msg | 7 + src/modules/logger/logged_topics.cpp | 3 +- src/modules/rover_ackermann/CMakeLists.txt | 1 + .../rover_ackermann/RoverAckermann.cpp | 126 +++++++++++++----- .../rover_ackermann/RoverAckermann.hpp | 17 ++- .../RoverAckermannGuidance.cpp | 91 ++++++++++--- .../RoverAckermannGuidance.hpp | 16 ++- src/modules/rover_ackermann/module.yaml | 77 ++++++++--- 11 files changed, 267 insertions(+), 86 deletions(-) create mode 100644 msg/RoverAckermannStatus.msg diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps index 0c77ab9aa6d0..5273d6aec068 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps @@ -1,9 +1,6 @@ #!/bin/sh # Standard apps for a ackermann drive rover. -# Start the attitude and position estimator. -ekf2 start & - # Start rover ackermann drive controller. rover_ackermann start diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index a3df406a9cae..65ec54d8b01e 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -180,6 +180,7 @@ set(msg_files RegisterExtComponentReply.msg RegisterExtComponentRequest.msg RoverAckermannGuidanceStatus.msg + RoverAckermannStatus.msg Rpm.msg RtlStatus.msg RtlTimeEstimate.msg diff --git a/msg/RoverAckermannGuidanceStatus.msg b/msg/RoverAckermannGuidanceStatus.msg index 3c34b63c63f2..69dec269420f 100644 --- a/msg/RoverAckermannGuidanceStatus.msg +++ b/msg/RoverAckermannGuidanceStatus.msg @@ -1,10 +1,9 @@ uint64 timestamp # time since system start (microseconds) -float32 actual_speed # [m/s] Rover ground speed -float32 desired_speed # [m/s] Rover desired ground speed -float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller -float32 heading_error # [deg] Heading error of the pure pursuit controller -float32 pid_throttle_integral # [-1, 1] Integral of the PID for the normalized throttle to control the rover speed during missions -float32 crosstrack_error # [m] Shortest distance from the vehicle to the path +float32 desired_speed # [m/s] Rover desired ground speed +float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller +float32 heading_error # [deg] Heading error of the pure pursuit controller +float32 pid_throttle_integral # [-1, 1] Integral of the PID for the normalized throttle to control the rover speed during missions +float32 crosstrack_error # [m] Shortest distance from the vehicle to the path # TOPICS rover_ackermann_guidance_status diff --git a/msg/RoverAckermannStatus.msg b/msg/RoverAckermannStatus.msg new file mode 100644 index 000000000000..bf0556b9453d --- /dev/null +++ b/msg/RoverAckermannStatus.msg @@ -0,0 +1,7 @@ +uint64 timestamp # time since system start (microseconds) + +float32 throttle_setpoint # [-1, 1] Normalized throttle setpoint +float32 steering_setpoint # [-1, 1] Normalized steering setpoint +float32 actual_speed # [m/s] Rover ground speed + +# TOPICS rover_ackermann_status diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 7dd0a43e9401..fc187a954d0e 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -103,7 +103,8 @@ void LoggedTopics::add_default_topics() add_topic("position_setpoint_triplet", 200); add_optional_topic("px4io_status"); add_topic("radio_status"); - add_topic("rover_ackermann_guidance_status", 100); + add_optional_topic("rover_ackermann_guidance_status", 100); + add_optional_topic("rover_ackermann_status", 100); add_topic("rtl_time_estimate", 1000); add_topic("rtl_status", 2000); add_optional_topic("sensor_airflow", 100); diff --git a/src/modules/rover_ackermann/CMakeLists.txt b/src/modules/rover_ackermann/CMakeLists.txt index 249a4748768d..805e20b73f7b 100644 --- a/src/modules/rover_ackermann/CMakeLists.txt +++ b/src/modules/rover_ackermann/CMakeLists.txt @@ -42,6 +42,7 @@ px4_add_module( DEPENDS RoverAckermannGuidance px4_work_queue + SlewRate MODULE_CONFIG module.yaml ) diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index 2c6b8c30d478..e65eb11442e8 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -40,6 +40,7 @@ RoverAckermann::RoverAckermann() : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) { + _rover_ackermann_status_pub.advertise(); updateParams(); } @@ -52,6 +53,16 @@ bool RoverAckermann::init() void RoverAckermann::updateParams() { ModuleParams::updateParams(); + + // Update slew rates + if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_speed.get() > FLT_EPSILON) { + _throttle_with_accel_limit.setSlewRate(_param_ra_max_accel.get() / _param_ra_max_speed.get()); + } + + if (_param_ra_max_steering_rate.get() > FLT_EPSILON && _param_ra_max_steer_angle.get() > FLT_EPSILON) { + _steering_with_rate_limit.setSlewRate((M_DEG_TO_RAD_F * _param_ra_max_steering_rate.get()) / + _param_ra_max_steer_angle.get()); + } } void RoverAckermann::Run() @@ -59,6 +70,7 @@ void RoverAckermann::Run() if (should_exit()) { ScheduleClear(); exit_and_cleanup(); + return; } // uORB subscriber updates @@ -70,44 +82,98 @@ void RoverAckermann::Run() vehicle_status_s vehicle_status; _vehicle_status_sub.copy(&vehicle_status); _nav_state = vehicle_status.nav_state; + _armed = vehicle_status.arming_state == 2; } - // Navigation modes - switch (_nav_state) { - case vehicle_status_s::NAVIGATION_STATE_MANUAL: { - manual_control_setpoint_s manual_control_setpoint{}; + if (_local_position_sub.updated()) { + vehicle_local_position_s local_position{}; + _local_position_sub.copy(&local_position); + const Vector3f rover_velocity = {local_position.vx, local_position.vy, local_position.vz}; + _actual_speed = rover_velocity.norm(); + } - if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - _motor_setpoint.steering = manual_control_setpoint.roll; - _motor_setpoint.throttle = manual_control_setpoint.throttle; - } + // Timestamps + hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + + if (_armed) { + // 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)) { + _motor_setpoint.steering = manual_control_setpoint.roll; + _motor_setpoint.throttle = manual_control_setpoint.throttle; + } + + } break; + + case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: + case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: + _motor_setpoint = _ackermann_guidance.purePursuit(_nav_state); + break; + + default: // Unimplemented nav states will stop the rover + _motor_setpoint.steering = 0.f; + _motor_setpoint.throttle = 0.f; + break; + } - } break; + // Sanitize actuator commands + if (!PX4_ISFINITE(_motor_setpoint.steering)) { + _motor_setpoint.steering = 0.f; + } - case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: - _motor_setpoint = _ackermann_guidance.purePursuit(); - break; + if (!PX4_ISFINITE(_motor_setpoint.throttle)) { + _motor_setpoint.throttle = 0.f; + } - default: // Unimplemented nav states will stop the rover - _motor_setpoint.steering = 0.f; - _motor_setpoint.throttle = 0.f; - break; - } + // Acceleration slew rate + if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_speed.get() > FLT_EPSILON + && fabsf(_motor_setpoint.throttle) > fabsf(_throttle_with_accel_limit.getState())) { + _throttle_with_accel_limit.update(_motor_setpoint.throttle, dt); + + } else { + _throttle_with_accel_limit.setForcedValue(_motor_setpoint.throttle); + } - hrt_abstime now = hrt_absolute_time(); + // Steering slew rate + if (_param_ra_max_steering_rate.get() > FLT_EPSILON && _param_ra_max_steer_angle.get() > FLT_EPSILON) { + _steering_with_rate_limit.update(_motor_setpoint.steering, dt); - // Publish to wheel motors - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); - actuator_motors.control[0] = _motor_setpoint.throttle; - actuator_motors.timestamp = now; - _actuator_motors_pub.publish(actuator_motors); + } else { + _steering_with_rate_limit.setForcedValue(_motor_setpoint.steering); + } - // Publish to servo - actuator_servos_s actuator_servos{}; - actuator_servos.control[0] = _motor_setpoint.steering; - actuator_servos.timestamp = now; - _actuator_servos_pub.publish(actuator_servos); + // Publish rover ackermann status (logging) + rover_ackermann_status_s rover_ackermann_status{}; + rover_ackermann_status.timestamp = _timestamp; + rover_ackermann_status.throttle_setpoint = _motor_setpoint.throttle; + rover_ackermann_status.steering_setpoint = _motor_setpoint.steering; + rover_ackermann_status.actual_speed = _actual_speed; + _rover_ackermann_status_pub.publish(rover_ackermann_status); + + // Publish to motor + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + actuator_motors.control[0] = math::constrain(_throttle_with_accel_limit.getState(), -1.f, 1.f); + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + + // Publish to servo + actuator_servos_s actuator_servos{}; + actuator_servos.control[0] = math::constrain(_steering_with_rate_limit.getState(), -1.f, 1.f); + actuator_servos.timestamp = _timestamp; + _actuator_servos_pub.publish(actuator_servos); + + } else { // Reset on disarm + _motor_setpoint.steering = 0.f; + _motor_setpoint.throttle = 0.f; + _throttle_with_accel_limit.setForcedValue(0.f); + _steering_with_rate_limit.setForcedValue(0.f); + } } int RoverAckermann::task_spawn(int argc, char *argv[]) @@ -147,7 +213,7 @@ int RoverAckermann::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description -Rover state machine. +Rover ackermann module. )DESCR_STR"); PRINT_MODULE_USAGE_NAME("rover_ackermann", "controller"); diff --git a/src/modules/rover_ackermann/RoverAckermann.hpp b/src/modules/rover_ackermann/RoverAckermann.hpp index 101647dd4e20..cea9300a1b3d 100644 --- a/src/modules/rover_ackermann/RoverAckermann.hpp +++ b/src/modules/rover_ackermann/RoverAckermann.hpp @@ -39,6 +39,7 @@ #include #include #include +#include // uORB includes #include @@ -49,6 +50,9 @@ #include #include #include +#include +#include + // Standard library includes #include @@ -89,10 +93,12 @@ class RoverAckermann : public ModuleBase, public ModuleParams, uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::Subscription _local_position_sub{ORB_ID(vehicle_local_position)}; // uORB publications uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; uORB::Publication _actuator_servos_pub{ORB_ID(actuator_servos)}; + uORB::Publication _rover_ackermann_status_pub{ORB_ID(rover_ackermann_status)}; // Instances RoverAckermannGuidance _ackermann_guidance{this}; @@ -100,9 +106,18 @@ class RoverAckermann : public ModuleBase, public ModuleParams, // Variables int _nav_state{0}; RoverAckermannGuidance::motor_setpoint _motor_setpoint; + hrt_abstime _timestamp{0}; + float _actual_speed{0.f}; + SlewRate _steering_with_rate_limit{0.f}; + SlewRate _throttle_with_accel_limit{0.f}; + bool _armed{false}; // Parameters DEFINE_PARAMETERS( - (ParamInt) _param_r_rev + (ParamInt) _param_r_rev, + (ParamFloat) _param_ra_max_steer_angle, + (ParamFloat) _param_ra_max_speed, + (ParamFloat) _param_ra_max_accel, + (ParamFloat) _param_ra_max_steering_rate ) }; diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index d718df0ad49e..19cdf5cf1aa5 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -40,6 +40,7 @@ using namespace time_literals; RoverAckermannGuidance::RoverAckermannGuidance(ModuleParams *parent) : ModuleParams(parent) { + _rover_ackermann_guidance_status_pub.advertise(); updateParams(); pid_init(&_pid_throttle, PID_MODE_DERIVATIV_NONE, 0.001f); } @@ -55,13 +56,14 @@ void RoverAckermannGuidance::updateParams() 1); // Output limit } -RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit() +RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit(const int nav_state) { // Initializations float desired_speed{0.f}; float desired_steering{0.f}; float vehicle_yaw{0.f}; float actual_speed{0.f}; + bool mission_finished{false}; // uORB subscriber updates if (_vehicle_global_position_sub.updated()) { @@ -84,6 +86,12 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit() actual_speed = rover_velocity.norm(); } + 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); + } + if (_position_setpoint_triplet_sub.updated()) { updateWaypoints(); } @@ -98,21 +106,58 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit() if (_mission_result_sub.updated()) { mission_result_s mission_result{}; _mission_result_sub.copy(&mission_result); - _mission_finished = mission_result.finished; + mission_finished = mission_result.finished; + } + + if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL + && get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), _next_wp(0), + _next_wp(1)) < _acceptance_radius) { // Return to launch + mission_finished = true; } // Guidance logic - if (!_mission_finished) { + if (!mission_finished) { // Calculate desired speed const float distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), _prev_wp(0), _prev_wp(1)); + const float distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _curr_wp(0), + _curr_wp(1)); + + if (_param_ra_miss_vel_min.get() > 0.f && _param_ra_miss_vel_min.get() < _param_ra_miss_vel_def.get() + && _param_ra_miss_vel_gain.get() > FLT_EPSILON) { // Cornering slow down effect + if (distance_to_prev_wp <= _prev_acceptance_radius && _prev_acceptance_radius > FLT_EPSILON) { + const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acceptance_radius; + desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); + + } else if (distance_to_curr_wp <= _acceptance_radius && _acceptance_radius > FLT_EPSILON) { + const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; + desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); + + } else { // Straight line speed + if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_jerk.get() > FLT_EPSILON + && _acceptance_radius > FLT_EPSILON) { + float max_velocity{0.f}; + + if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { + max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), + _param_ra_max_accel.get(), distance_to_curr_wp, 0.f); + + } else { + const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; + max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), + _param_ra_max_accel.get(), distance_to_curr_wp - _acceptance_radius, cornering_speed); + } + + desired_speed = math::constrain(max_velocity, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); + + } else { + desired_speed = _param_ra_miss_vel_def.get(); + } + } - if (distance_to_prev_wp <= _prev_acc_rad) { // Cornering speed - const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acc_rad; - desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); - - } else { // Default mission speed + } else { desired_speed = _param_ra_miss_vel_def.get(); } @@ -124,9 +169,9 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit() } // Throttle PID - hrt_abstime now = hrt_absolute_time(); - const float dt = math::min((now - _time_stamp_last), 5000_ms) / 1e6f; - _time_stamp_last = now; + hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; float throttle = 0.f; if (desired_speed < FLT_EPSILON) { @@ -144,8 +189,7 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit() } // Publish ackermann controller status (logging) - _rover_ackermann_guidance_status.timestamp = now; - _rover_ackermann_guidance_status.actual_speed = actual_speed; + _rover_ackermann_guidance_status.timestamp = _timestamp; _rover_ackermann_guidance_status.desired_speed = desired_speed; _rover_ackermann_guidance_status.pid_throttle_integral = _pid_throttle.integral; _rover_ackermann_guidance_status_pub.publish(_rover_ackermann_guidance_status); @@ -165,7 +209,12 @@ void RoverAckermannGuidance::updateWaypoints() _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); // Global waypoint coordinates - _curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon); + if (position_setpoint_triplet.current.valid) { + _curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon); + + } else { + _curr_wp = Vector2d(0, 0); + } if (position_setpoint_triplet.previous.valid) { _prev_wp = Vector2d(position_setpoint_triplet.previous.lat, position_setpoint_triplet.previous.lon); @@ -178,7 +227,7 @@ void RoverAckermannGuidance::updateWaypoints() _next_wp = Vector2d(position_setpoint_triplet.next.lat, position_setpoint_triplet.next.lon); } else { - _next_wp = _curr_wp; + _next_wp = _home_position; // Enables corner slow down with RTL } // Local waypoint coordinates @@ -187,9 +236,15 @@ void RoverAckermannGuidance::updateWaypoints() _next_wp_local = _global_local_proj_ref.project(_next_wp(0), _next_wp(1)); // Update acceptance radius - _prev_acc_rad = _acceptance_radius; - _acceptance_radius = updateAcceptanceRadius(_curr_wp_local, _prev_wp_local, _next_wp_local, _param_ra_acc_rad_def.get(), - _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_steer_angle.get()); + _prev_acceptance_radius = _acceptance_radius; + + if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) { + _acceptance_radius = updateAcceptanceRadius(_curr_wp_local, _prev_wp_local, _next_wp_local, _param_nav_acc_rad.get(), + _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_steer_angle.get()); + + } else { + _acceptance_radius = _param_nav_acc_rad.get(); + } } float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index f6446cdacb8a..a618f830e593 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -43,10 +43,11 @@ #include #include #include -#include #include +#include #include #include +#include // Standard library includes #include @@ -78,8 +79,9 @@ class RoverAckermannGuidance : public ModuleParams /** * @brief Compute guidance for ackermann rover and return motor_setpoint for throttle and steering. + * @param nav_state Vehicle navigation state */ - motor_setpoint purePursuit(); + motor_setpoint purePursuit(const int nav_state); /** * @brief Update global/local waypoint coordinates and acceptance radius @@ -143,6 +145,7 @@ class RoverAckermannGuidance : public ModuleParams uORB::Subscription _local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _mission_result_sub{ORB_ID(mission_result)}; + uORB::Subscription _home_position_sub{ORB_ID(home_position)}; // uORB publications uORB::Publication _rover_ackermann_guidance_status_pub{ORB_ID(rover_ackermann_guidance_status)}; @@ -156,18 +159,18 @@ class RoverAckermannGuidance : public ModuleParams Vector2d _curr_pos{}; Vector2f _curr_pos_local{}; PID_t _pid_throttle; - hrt_abstime _time_stamp_last{0}; + hrt_abstime _timestamp{0}; // Waypoint variables Vector2d _curr_wp{}; Vector2d _next_wp{}; Vector2d _prev_wp{}; + Vector2d _home_position{}; Vector2f _curr_wp_local{}; Vector2f _prev_wp_local{}; Vector2f _next_wp_local{}; float _acceptance_radius{0.5f}; - float _prev_acc_rad{0.f}; - bool _mission_finished{false}; + float _prev_acceptance_radius{0.5f}; // Parameters DEFINE_PARAMETERS( @@ -177,7 +180,6 @@ class RoverAckermannGuidance : public ModuleParams (ParamFloat) _param_ra_lookahd_max, (ParamFloat) _param_ra_lookahd_min, (ParamFloat) _param_ra_acc_rad_max, - (ParamFloat) _param_ra_acc_rad_def, (ParamFloat) _param_ra_acc_rad_gain, (ParamFloat) _param_ra_miss_vel_def, (ParamFloat) _param_ra_miss_vel_min, @@ -185,6 +187,8 @@ class RoverAckermannGuidance : public ModuleParams (ParamFloat) _param_ra_p_speed, (ParamFloat) _param_ra_i_speed, (ParamFloat) _param_ra_max_speed, + (ParamFloat) _param_ra_max_jerk, + (ParamFloat) _param_ra_max_accel, (ParamFloat) _param_nav_acc_rad ) }; diff --git a/src/modules/rover_ackermann/module.yaml b/src/modules/rover_ackermann/module.yaml index a3152b9e77be..d8cb88831676 100644 --- a/src/modules/rover_ackermann/module.yaml +++ b/src/modules/rover_ackermann/module.yaml @@ -66,31 +66,20 @@ parameters: RA_ACC_RAD_MAX: description: - short: Maximum acceptance radius + short: Maximum acceptance radius for the waypoints long: | The controller scales the acceptance radius based on the angle between - the previous, current and next waypoint. Used as tuning parameter. + the previous, current and next waypoint. Higher value -> smoother trajectory at the cost of how close the rover gets - to the waypoint (Set equal to RA_ACC_RAD_DEF to disable corner cutting). + to the waypoint (Set to -1 to disable corner cutting). type: float unit: m - min: 0.1 + min: -1 max: 100 increment: 0.01 decimal: 2 default: 3 - RA_ACC_RAD_DEF: - description: - short: Default acceptance radius - type: float - unit: m - min: 0.1 - max: 100 - increment: 0.01 - decimal: 2 - default: 0.5 - RA_ACC_RAD_GAIN: description: short: Tuning parameter for corner cutting @@ -110,21 +99,21 @@ parameters: short: Default rover velocity during a mission type: float unit: m/s - min: 0.1 + min: 0 max: 100 increment: 0.01 decimal: 2 - default: 3 + default: 2 RA_MISS_VEL_MIN: description: short: Minimum rover velocity during a mission long: | The velocity off the rover is reduced based on the corner it has to take - to smooth the trajectory (To disable this feature set it equal to RA_MISSION_VEL_DEF) + to smooth the trajectory (Set to -1 to disable) type: float unit: m/s - min: 0.1 + min: -1 max: 100 increment: 0.01 decimal: 2 @@ -133,9 +122,12 @@ parameters: RA_MISS_VEL_GAIN: description: short: Tuning parameter for the velocity reduction during cornering - long: Lower value -> More velocity reduction during cornering + long: | + The cornering speed is equal to the inverse of the acceptance radius + of the WP multiplied with this factor. + Lower value -> More velocity reduction during cornering. type: float - min: 0.1 + min: 0.05 max: 100 increment: 0.01 decimal: 2 @@ -175,3 +167,46 @@ parameters: increment: 0.01 decimal: 2 default: -1 + + RA_MAX_ACCEL: + description: + short: Maximum acceleration for the rover + long: | + This is used for the acceleration slew rate, the feed-forward term + for the speed controller during missions and the corner slow down effect. + Note: For the corner slow down effect RA_MAX_JERK, RA_MISS_VEL_GAIN and + RA_MISS_VEL_MIN also have to be set. + type: float + unit: m/s^2 + min: -1 + max: 100 + increment: 0.01 + decimal: 2 + default: -1 + + RA_MAX_JERK: + description: + short: Maximum jerk + long: | + Limit for forwards acc/deceleration change. + This is used for the corner slow down effect. + Note: RA_MAX_ACCEL, RA_MISS_VEL_GAIN and RA_MISS_VEL_MIN also have to be set + for this to be enabled. + type: float + unit: m/s^3 + min: -1 + max: 100 + increment: 0.01 + decimal: 2 + default: -1 + + RA_MAX_STR_RATE: + description: + short: Maximum steering rate for the rover + type: float + unit: deg/s + min: -1 + max: 1000 + increment: 0.01 + decimal: 2 + default: -1 From 3fe609f7692fa924f153de25fcf0c264712fe6ba Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Wed, 10 Jul 2024 11:02:22 +0200 Subject: [PATCH 467/652] exclude 4017 from v5x to save flash --- ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames index 03adea0bee67..2cc60c5217e8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames +++ b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames @@ -6,6 +6,7 @@ # @class Copter # # @board px4_fmu-v2 exclude +# @board px4_fmu-v5x exclude # @board bitcraze_crazyflie exclude # # @maintainer Iain Galloway From c29b4ff87ed9e68990975687ab93ae226db2a1df Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 10 Jul 2024 10:40:29 -0400 Subject: [PATCH 468/652] ekf2: apply astyle formatting and enforce --- Tools/astyle/files_to_check_code_style.sh | 3 +- .../aid_sources/airspeed/airspeed_fusion.cpp | 15 +- .../aux_global_position.cpp | 12 +- .../aux_global_position.hpp | 4 +- .../EKF/aid_sources/auxvel/auxvel_fusion.cpp | 12 +- .../ekf2/EKF/aid_sources/drag/drag_fusion.cpp | 12 +- .../external_vision/ev_control.cpp | 6 +- .../external_vision/ev_height_control.cpp | 2 + .../external_vision/ev_pos_control.cpp | 18 +- .../external_vision/ev_yaw_control.cpp | 14 +- .../ekf2/EKF/aid_sources/fake_pos_control.cpp | 18 +- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 4 +- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 24 +-- .../EKF/aid_sources/gnss/gps_yaw_fusion.cpp | 12 +- .../aid_sources/gravity/gravity_fusion.cpp | 24 +-- .../aid_sources/magnetometer/mag_control.cpp | 47 ++--- .../aid_sources/magnetometer/mag_fusion.cpp | 12 +- .../optical_flow/optical_flow_fusion.cpp | 3 +- .../range_finder/range_height_control.cpp | 18 +- .../range_finder/sensor_range_finder.hpp | 3 +- .../aid_sources/sideslip/sideslip_fusion.cpp | 12 +- .../zero_innovation_heading_update.cpp | 5 +- src/modules/ekf2/EKF/common.h | 163 +++++++++++------- src/modules/ekf2/EKF/covariance.cpp | 18 +- src/modules/ekf2/EKF/ekf.cpp | 37 ++-- src/modules/ekf2/EKF/ekf.h | 73 +++++--- src/modules/ekf2/EKF/ekf_helper.cpp | 148 +++++++++++----- src/modules/ekf2/EKF/estimator_interface.cpp | 32 ++-- src/modules/ekf2/EKF/estimator_interface.h | 26 +-- src/modules/ekf2/EKF/height_control.cpp | 8 + .../EKF/output_predictor/output_predictor.cpp | 6 +- .../EKF/output_predictor/output_predictor.h | 3 +- src/modules/ekf2/EKF/position_fusion.cpp | 15 +- src/modules/ekf2/EKF/velocity_fusion.cpp | 15 +- .../ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp | 3 +- src/modules/ekf2/EKF/yaw_fusion.cpp | 2 + 36 files changed, 527 insertions(+), 302 deletions(-) diff --git a/Tools/astyle/files_to_check_code_style.sh b/Tools/astyle/files_to_check_code_style.sh index 97a2d8c6fc86..c94132867ee1 100755 --- a/Tools/astyle/files_to_check_code_style.sh +++ b/Tools/astyle/files_to_check_code_style.sh @@ -18,7 +18,8 @@ exec find boards msg src platforms test \ -path src/lib/events/libevents -prune -o \ -path src/lib/parameters/uthash -prune -o \ -path src/lib/wind_estimator/python/generated -prune -o \ - -path src/modules/ekf2/EKF -prune -o \ + -path src/modules/ekf2/EKF/python/ekf_derivation/generated -prune -o \ + -path src/modules/ekf2/EKF/yaw_estimator/derivation/generated -prune -o \ -path src/modules/gyro_fft/CMSIS_5 -prune -o \ -path src/modules/mavlink/mavlink -prune -o \ -path test/mavsdk_tests/catch2 -prune -o \ diff --git a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp index 69895181b1ed..c9822d4829bf 100644 --- a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp @@ -89,7 +89,8 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) updateAirspeed(airspeed_sample, _aid_src_airspeed); - _innov_check_fail_status.flags.reject_airspeed = _aid_src_airspeed.innovation_rejected; // TODO: remove this redundant flag + _innov_check_fail_status.flags.reject_airspeed = + _aid_src_airspeed.innovation_rejected; // TODO: remove this redundant flag const bool continuing_conditions_passing = _control_status.flags.in_air && _control_status.flags.fixed_wing @@ -155,12 +156,12 @@ void Ekf::updateAirspeed(const airspeedSample &airspeed_sample, estimator_aid_so &innov, &innov_var); updateAidSourceStatus(aid_src, - airspeed_sample.time_us, // sample timestamp - airspeed_sample.true_airspeed, // observation - R, // observation variance - innov, // innovation - innov_var, // innovation variance - math::max(_params.tas_innov_gate, 1.f)); // innovation gate + airspeed_sample.time_us, // sample timestamp + airspeed_sample.true_airspeed, // observation + R, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.tas_innov_gate, 1.f)); // innovation gate } void Ekf::fuseAirspeed(const airspeedSample &airspeed_sample, estimator_aid_source1d_s &aid_src) 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 fe313315b597..6efd4fabe66b 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 @@ -85,12 +85,12 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed const Vector2f pos_obs_var(pos_var, pos_var); ekf.updateAidSourceStatus(aid_src, - sample.time_us, // sample timestamp - position, // observation - pos_obs_var, // observation variance - Vector2f(ekf.state().pos) - position, // innovation - Vector2f(ekf.getPositionVariance()) + pos_obs_var, // innovation variance - math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate + sample.time_us, // sample timestamp + position, // observation + pos_obs_var, // observation variance + Vector2f(ekf.state().pos) - position, // innovation + Vector2f(ekf.getPositionVariance()) + pos_obs_var, // innovation variance + math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate } const bool starting_conditions = PX4_ISFINITE(sample.latitude) && PX4_ISFINITE(sample.longitude) diff --git a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp index bd63f7245605..e5bc78026a68 100644 --- a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp +++ b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.hpp @@ -96,8 +96,8 @@ class AuxGlobalPosition : public ModuleParams uint64_t _time_last_buffer_push{0}; enum class Ctrl : uint8_t { - HPOS = (1<<0), - VPOS = (1<<1) + HPOS = (1 << 0), + VPOS = (1 << 1) }; enum class State { diff --git a/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp index 132aaa10559b..14d333f3642d 100644 --- a/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp @@ -41,12 +41,12 @@ void Ekf::controlAuxVelFusion() if (_auxvel_buffer->pop_first_older_than(_time_delayed_us, &sample)) { updateAidSourceStatus(_aid_src_aux_vel, - sample.time_us, // sample timestamp - sample.vel, // observation - sample.velVar, // observation variance - Vector2f(_state.vel.xy()) - sample.vel, // innovation - Vector2f(getStateVariance()) + sample.velVar, // innovation variance - math::max(_params.auxvel_gate, 1.f)); // innovation gate + sample.time_us, // sample timestamp + sample.vel, // observation + sample.velVar, // observation variance + Vector2f(_state.vel.xy()) - sample.vel, // innovation + Vector2f(getStateVariance()) + sample.velVar, // innovation variance + math::max(_params.auxvel_gate, 1.f)); // innovation gate if (isHorizontalAidingActive()) { fuseHorizontalVelocity(_aid_src_aux_vel); diff --git a/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp index c55ed14aaf4d..439cbdb44651 100644 --- a/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp @@ -169,12 +169,12 @@ void Ekf::fuseDrag(const dragSample &drag_sample) } updateAidSourceStatus(_aid_src_drag, - drag_sample.time_us, // sample timestamp - observation, // observation - observation_variance, // observation variance - innovation, // innovation - innovation_variance, // innovation variance - innov_gate); // innovation gate + drag_sample.time_us, // sample timestamp + observation, // observation + observation_variance, // observation variance + innovation, // innovation + innovation_variance, // innovation variance + innov_gate); // innovation gate if (fused[0] && fused[1]) { _aid_src_drag.fused = true; diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp index f757b59a788e..43f61a79d057 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp @@ -55,8 +55,10 @@ void Ekf::controlExternalVisionFusion() const bool starting_conditions_passing = quality_sufficient && ((ev_sample.time_us - _ev_sample_prev.time_us) < EV_MAX_INTERVAL) - && ((_params.ev_quality_minimum <= 0) || (_ev_sample_prev.quality >= _params.ev_quality_minimum)) // previous quality sufficient - && ((_params.ev_quality_minimum <= 0) || (_ext_vision_buffer->get_newest().quality >= _params.ev_quality_minimum)) // newest quality sufficient + && ((_params.ev_quality_minimum <= 0) + || (_ev_sample_prev.quality >= _params.ev_quality_minimum)) // previous quality sufficient + && ((_params.ev_quality_minimum <= 0) + || (_ext_vision_buffer->get_newest().quality >= _params.ev_quality_minimum)) // newest quality sufficient && isNewestSampleRecent(_time_last_ext_vision_buffer_push, EV_MAX_INTERVAL); updateEvAttitudeErrorFilter(ev_sample, ev_reset); diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp index e4308c4fcf76..a69906eef489 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp @@ -77,10 +77,12 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com float measurement_var = math::max(pos_cov(2, 2), sq(_params.ev_pos_noise), sq(0.01f)); #if defined(CONFIG_EKF2_GNSS) + // increase minimum variance if GPS active if (_control_status.flags.gps_hgt) { measurement_var = math::max(measurement_var, sq(_params.gps_pos_noise)); } + #endif // CONFIG_EKF2_GNSS const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp index 1e6e7904ddce..53ee21e09b8c 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp @@ -161,12 +161,12 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common const Vector2f pos_obs_var = measurement_var + _ev_pos_b_est.getBiasVar(); updateAidSourceStatus(aid_src, - ev_sample.time_us, // sample timestamp - position, // observation - pos_obs_var, // observation variance - Vector2f(_state.pos) - position, // innovation - Vector2f(getStateVariance()) + pos_obs_var, // innovation variance - math::max(_params.ev_pos_innov_gate, 1.f)); // innovation gate + ev_sample.time_us, // sample timestamp + position, // observation + pos_obs_var, // observation variance + Vector2f(_state.pos) - position, // innovation + Vector2f(getStateVariance()) + pos_obs_var, // innovation variance + math::max(_params.ev_pos_innov_gate, 1.f)); // innovation gate // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation @@ -205,7 +205,8 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common } } -void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, estimator_aid_source2d_s &aid_src) +void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, + estimator_aid_source2d_s &aid_src) { // activate fusion // TODO: (_params.position_sensor_ref == PositionSensor::EV) @@ -229,7 +230,8 @@ void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurem _control_status.flags.ev_pos = true; } -void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, bool reset, estimator_aid_source2d_s &aid_src) +void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, + bool reset, estimator_aid_source2d_s &aid_src) { if (reset) { diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp index d974a5e87b81..a285d3e4556a 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp @@ -53,12 +53,12 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common computeYawInnovVarAndH(obs_var, innov_var, H_YAW); updateAidSourceStatus(aid_src, - ev_sample.time_us, // sample timestamp - obs, // observation - obs_var, // observation variance - innov, // innovation - innov_var, // innovation variance - math::max(_params.heading_innov_gate, 1.f)); // innovation gate + ev_sample.time_us, // sample timestamp + obs, // observation + obs_var, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.heading_innov_gate, 1.f)); // innovation gate if (ev_reset) { _control_status.flags.ev_yaw_fault = false; @@ -191,9 +191,11 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common void Ekf::stopEvYawFusion() { #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_yaw) { _control_status.flags.ev_yaw = false; } + #endif // CONFIG_EKF2_EXTERNAL_VISION } diff --git a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp index 9ea6485e64fd..1ba1dd309b02 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp @@ -68,17 +68,17 @@ void Ekf::controlFakePosFusion() const float innov_gate = 3.f; updateAidSourceStatus(aid_src, - _time_delayed_us, - position, // observation - obs_var, // observation variance - Vector2f(_state.pos) - position, // innovation - Vector2f(getStateVariance()) + obs_var, // innovation variance - innov_gate); // innovation gate + _time_delayed_us, + position, // observation + obs_var, // observation variance + Vector2f(_state.pos) - position, // innovation + Vector2f(getStateVariance()) + obs_var, // innovation variance + innov_gate); // innovation gate const bool enable_conditions_passing = !isHorizontalAidingActive() - && ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest) - && (!(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest) - && _horizontal_deadreckon_time_exceeded; + && ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest) + && (!(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest) + && _horizontal_deadreckon_time_exceeded; if (_control_status.flags.fake_pos) { if (enable_conditions_passing) { 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 a598f1078b66..652069caf574 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -126,6 +126,7 @@ void Ekf::collect_gps(const gnssSample &gps) _wmm_gps_time_last_set = _time_delayed_us; } } + #endif // CONFIG_EKF2_MAGNETOMETER _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); @@ -157,7 +158,8 @@ bool Ekf::runGnssChecks(const gnssSample &gps) // Calculate time lapsed since last update, limit to prevent numerical errors and calculate a lowpass filter coefficient constexpr float filt_time_const = 10.0f; - const float dt = math::constrain(float(int64_t(gps.time_us) - int64_t(_gps_pos_prev.getProjectionReferenceTimestamp())) * 1e-6f, 0.001f, filt_time_const); + const float dt = math::constrain(float(int64_t(gps.time_us) - int64_t(_gps_pos_prev.getProjectionReferenceTimestamp())) + * 1e-6f, 0.001f, filt_time_const); const float filter_coef = dt / filt_time_const; // The following checks are only valid when the vehicle is at rest diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index afff48dcb7da..0c8c98ab26b6 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -190,12 +190,12 @@ void Ekf::updateGnssVel(const gnssSample &gnss_sample, estimator_aid_source3d_s const float innovation_gate = math::max(_params.gps_vel_innov_gate, 1.f); updateAidSourceStatus(aid_src, - gnss_sample.time_us, // sample timestamp - velocity, // observation - vel_obs_var, // observation variance - _state.vel - velocity, // innovation - getVelocityVariance() + vel_obs_var, // innovation variance - innovation_gate); // innovation gate + gnss_sample.time_us, // sample timestamp + velocity, // observation + vel_obs_var, // observation variance + _state.vel - velocity, // innovation + getVelocityVariance() + vel_obs_var, // innovation variance + innovation_gate); // innovation gate // vz special case if there is bad vertical acceleration data, then don't reject measurement if GNSS reports velocity accuracy is acceptable, // but limit innovation to prevent spikes that could destabilise the filter @@ -228,12 +228,12 @@ void Ekf::updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s const Vector2f pos_obs_var(pos_var, pos_var); updateAidSourceStatus(aid_src, - gnss_sample.time_us, // sample timestamp - position, // observation - pos_obs_var, // observation variance - Vector2f(_state.pos) - position, // innovation - Vector2f(getStateVariance()) + pos_obs_var, // innovation variance - math::max(_params.gps_pos_innov_gate, 1.f)); // innovation gate + gnss_sample.time_us, // sample timestamp + position, // observation + pos_obs_var, // observation variance + Vector2f(_state.pos) - position, // innovation + Vector2f(getStateVariance()) + pos_obs_var, // innovation variance + math::max(_params.gps_pos_innov_gate, 1.f)); // innovation gate } void Ekf::controlGnssYawEstimator(estimator_aid_source3d_s &aid_src_vel) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp index 2e135f357f20..d66fbac7c6f3 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp @@ -62,12 +62,12 @@ void Ekf::updateGpsYaw(const gnssSample &gps_sample) &heading_pred, &heading_innov_var, &H); updateAidSourceStatus(_aid_src_gnss_yaw, - gps_sample.time_us, // sample timestamp - measured_hdg, // observation - R_YAW, // observation variance - wrap_pi(heading_pred - measured_hdg), // innovation - heading_innov_var, // innovation variance - math::max(_params.heading_innov_gate, 1.f)); // innovation gate + gps_sample.time_us, // sample timestamp + measured_hdg, // observation + R_YAW, // observation variance + wrap_pi(heading_pred - measured_hdg), // innovation + heading_innov_var, // innovation variance + math::max(_params.heading_innov_gate, 1.f)); // innovation gate } void Ekf::fuseGpsYaw(float antenna_yaw_offset) diff --git a/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp index 40127a37548e..e6961ed17c31 100644 --- a/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp @@ -54,7 +54,8 @@ void Ekf::controlGravityFusion(const imuSample &imu) const float upper_accel_limit = CONSTANTS_ONE_G * 1.1f; const float lower_accel_limit = CONSTANTS_ONE_G * 0.9f; - const bool accel_lpf_norm_good = (_accel_magnitude_filt > lower_accel_limit) && (_accel_magnitude_filt < upper_accel_limit); + const bool accel_lpf_norm_good = (_accel_magnitude_filt > lower_accel_limit) + && (_accel_magnitude_filt < upper_accel_limit); // fuse gravity observation if our overall acceleration isn't too big _control_status.flags.gravity_vector = (_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) @@ -70,12 +71,12 @@ void Ekf::controlGravityFusion(const imuSample &imu) // fill estimator aid source status updateAidSourceStatus(_aid_src_gravity, - imu.time_us, // sample timestamp - measurement, // observation - Vector3f{measurement_var, measurement_var, measurement_var}, // observation variance - innovation, // innovation - innovation_variance, // innovation variance - 0.25f); // innovation gate + imu.time_us, // sample timestamp + measurement, // observation + Vector3f{measurement_var, measurement_var, measurement_var}, // observation variance + innovation, // innovation + innovation_variance, // innovation variance + 0.25f); // innovation gate bool fused[3] {false, false, false}; @@ -90,14 +91,16 @@ void Ekf::controlGravityFusion(const imuSample &imu) sym::ComputeGravityYInnovVarAndH(state_vector, P, measurement_var, &_aid_src_gravity.innovation_variance[index], &H); // recalculate innovation using the updated state - _aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f, -1.f))(index) - measurement(index); + _aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f, + -1.f))(index) - measurement(index); } else if (index == 2) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) sym::ComputeGravityZInnovVarAndH(state_vector, P, measurement_var, &_aid_src_gravity.innovation_variance[index], &H); // recalculate innovation using the updated state - _aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f, -1.f))(index) - measurement(index); + _aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f, + -1.f))(index) - measurement(index); } VectorState K = P * H / _aid_src_gravity.innovation_variance[index]; @@ -105,7 +108,8 @@ void Ekf::controlGravityFusion(const imuSample &imu) const bool accel_clipping = imu.delta_vel_clipping[0] || imu.delta_vel_clipping[1] || imu.delta_vel_clipping[2]; if (_control_status.flags.gravity_vector && !_aid_src_gravity.innovation_rejected && !accel_clipping) { - fused[index] = measurementUpdate(K, H, _aid_src_gravity.observation_variance[index], _aid_src_gravity.innovation[index]); + fused[index] = measurementUpdate(K, H, _aid_src_gravity.observation_variance[index], + _aid_src_gravity.innovation[index]); } } 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 74d017add5f9..979807f116a5 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -109,12 +109,12 @@ void Ekf::controlMagFusion() sym::ComputeMagInnovInnovVarAndHx(_state.vector(), P, mag_sample.mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); updateAidSourceStatus(aid_src, - mag_sample.time_us, // sample timestamp - mag_sample.mag, // observation - Vector3f(R_MAG, R_MAG, R_MAG), // observation variance - mag_innov, // innovation - innov_var, // innovation variance - math::max(_params.mag_innov_gate, 1.f)); // innovation gate + mag_sample.time_us, // sample timestamp + mag_sample.mag, // observation + Vector3f(R_MAG, R_MAG, R_MAG), // observation variance + mag_innov, // innovation + innov_var, // innovation variance + math::max(_params.mag_innov_gate, 1.f)); // innovation gate // Perform an innovation consistency check and report the result _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); @@ -134,7 +134,8 @@ void Ekf::controlMagFusion() && checkMagField(mag_sample.mag) && (_mag_counter > 3) // wait until we have more than a few samples through the filter && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame - && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset + && (_state_reset_status.reset_count.quat == + _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); checkMagHeadingConsistency(mag_sample); @@ -145,22 +146,22 @@ void Ekf::controlMagFusion() { - const bool mag_consistent_or_no_ne_aiding = _control_status.flags.mag_heading_consistent || !using_ne_aiding; - const bool common_conditions_passing = _control_status.flags.mag - && ((_control_status.flags.yaw_align && mag_consistent_or_no_ne_aiding) - || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && !_control_status.flags.mag_fault - && !_control_status.flags.mag_field_disturbed - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; - - _control_status.flags.mag_3D = common_conditions_passing - && (_params.mag_fusion_type == MagFuseType::AUTO) - && _control_status.flags.mag_aligned_in_flight; - - _control_status.flags.mag_hdg = common_conditions_passing - && ((_params.mag_fusion_type == MagFuseType::HEADING) - || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)); + const bool mag_consistent_or_no_ne_aiding = _control_status.flags.mag_heading_consistent || !using_ne_aiding; + const bool common_conditions_passing = _control_status.flags.mag + && ((_control_status.flags.yaw_align && mag_consistent_or_no_ne_aiding) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && !_control_status.flags.mag_fault + && !_control_status.flags.mag_field_disturbed + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + _control_status.flags.mag_3D = common_conditions_passing + && (_params.mag_fusion_type == MagFuseType::AUTO) + && _control_status.flags.mag_aligned_in_flight; + + _control_status.flags.mag_hdg = common_conditions_passing + && ((_params.mag_fusion_type == MagFuseType::HEADING) + || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)); } // TODO: allow clearing mag_fault if mag_3d is good? 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 474e654ec60d..acd16578c54f 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -50,7 +50,8 @@ #include -bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt) +bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, + bool update_all_states, bool update_tilt) { // if any axis failed, abort the mag fusion if (aid_src.innovation_rejected) { @@ -72,7 +73,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); + aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag( + index); } else if (index == 2) { // we do not fuse synthesized magnetomter measurements when doing 3D fusion @@ -85,7 +87,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); + aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag( + index); } if (aid_src.innovation_variance[index] < R_MAG) { @@ -171,7 +174,8 @@ bool Ekf::fuseDeclination(float decl_sigma) float decl_pred; float innovation_variance; - sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, &decl_pred, &innovation_variance, &H); + sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, &decl_pred, &innovation_variance, + &H); const float innovation = wrap_pi(decl_pred - decl_measurement); diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 91efdace2e79..531a7b56d09e 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -85,7 +85,8 @@ bool Ekf::fuseOptFlow(VectorState &H, const bool update_terrain) Kfusion(State::terrain.idx) = 0.f; } - if (measurementUpdate(Kfusion, H, _aid_src_optical_flow.observation_variance[index], _aid_src_optical_flow.innovation[index])) { + if (measurementUpdate(Kfusion, H, _aid_src_optical_flow.observation_variance[index], + _aid_src_optical_flow.innovation[index])) { fused[index] = true; } } 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 2bc07e7b22c7..1b7db97e3020 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 @@ -101,11 +101,11 @@ void Ekf::controlRangeHaglFusion() const bool measurement_valid = PX4_ISFINITE(aid_src.observation) && PX4_ISFINITE(aid_src.observation_variance); const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast(RngCtrl::ENABLED)) - || (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL))) - && _control_status.flags.tilt_align - && measurement_valid - && _range_sensor.isDataHealthy() - && _rng_consistency_check.isKinematicallyConsistent(); + || (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL))) + && _control_status.flags.tilt_align + && measurement_valid + && _range_sensor.isDataHealthy() + && _rng_consistency_check.isKinematicallyConsistent(); const bool starting_conditions_passing = continuing_conditions_passing && isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL) @@ -260,10 +260,10 @@ void Ekf::updateRangeHagl(estimator_aid_source1d_s &aid_src) float Ekf::getRngVar() const { return fmaxf( - P(State::pos.idx + 2, State::pos.idx + 2) - + sq(_params.range_noise) - + sq(_params.range_noise_scaler * _range_sensor.getRange()), - 0.f); + P(State::pos.idx + 2, State::pos.idx + 2) + + sq(_params.range_noise) + + sq(_params.range_noise_scaler * _range_sensor.getRange()), + 0.f); } void Ekf::resetTerrainToRng(estimator_aid_source1d_s &aid_src) 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 dbfbd96b1006..f3c59be54135 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 @@ -56,7 +56,8 @@ struct rangeSample { int8_t quality{}; ///< Signal quality in percent (0...100%), where 0 = invalid signal, 100 = perfect signal, and -1 = unknown signal quality. }; -static constexpr uint64_t RNG_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between range finder measurements (uSec) +static constexpr uint64_t RNG_MAX_INTERVAL = + 200e3; ///< Maximum allowable time interval between range finder measurements (uSec) class SensorRangeFinder : public Sensor { diff --git a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp index 997b474793b5..6a9ab3442220 100644 --- a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp @@ -88,12 +88,12 @@ void Ekf::updateSideslip(estimator_aid_source1d_s &aid_src) const sym::ComputeSideslipInnovAndInnovVar(_state.vector(), P, R, FLT_EPSILON, &innov, &innov_var); updateAidSourceStatus(aid_src, - _time_delayed_us, // sample timestamp - observation, // observation - R, // observation variance - innov, // innovation - innov_var, // innovation variance - math::max(_params.beta_innov_gate, 1.f)); // innovation gate + _time_delayed_us, // sample timestamp + observation, // observation + R, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.beta_innov_gate, 1.f)); // innovation gate } void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) diff --git a/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp b/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp index 1bae77c7c8b7..3c0a2c1d6cf7 100644 --- a/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp +++ b/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp @@ -44,7 +44,7 @@ void Ekf::controlZeroInnovationHeadingUpdate() || _control_status.flags.ev_yaw || _control_status.flags.gps_yaw; // fuse zero innovation at a limited rate if the yaw variance is too large - if(!yaw_aiding + if (!yaw_aiding && isTimedOut(_time_last_heading_fuse, (uint64_t)200'000)) { // Use an observation variance larger than usual but small enough @@ -60,7 +60,8 @@ void Ekf::controlZeroInnovationHeadingUpdate() computeYawInnovVarAndH(obs_var, aid_src_status.innovation_variance, H_YAW); - if (!_control_status.flags.tilt_align || (aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) { + if (!_control_status.flags.tilt_align + || (aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) { // The yaw variance is too large, fuse fake measurement fuseYaw(aid_src_status, H_YAW); } diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index b8e7664bf94c..7a008783fe1b 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -66,18 +66,26 @@ using math::Utilities::sq; using math::Utilities::updateYawInRotMat; // maximum sensor intervals in usec -static constexpr uint64_t BARO_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between pressure altitude measurements (uSec) -static constexpr uint64_t EV_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between external vision system measurements (uSec) -static constexpr uint64_t GNSS_MAX_INTERVAL = 500e3; ///< Maximum allowable time interval between GNSS measurements (uSec) -static constexpr uint64_t GNSS_YAW_MAX_INTERVAL = 1500e3; ///< Maximum allowable time interval between GNSS yaw measurements (uSec) -static constexpr uint64_t MAG_MAX_INTERVAL = 500e3; ///< Maximum allowable time interval between magnetic field measurements (uSec) +static constexpr uint64_t BARO_MAX_INTERVAL = + 200e3; ///< Maximum allowable time interval between pressure altitude measurements (uSec) +static constexpr uint64_t EV_MAX_INTERVAL = + 200e3; ///< Maximum allowable time interval between external vision system measurements (uSec) +static constexpr uint64_t GNSS_MAX_INTERVAL = + 500e3; ///< Maximum allowable time interval between GNSS measurements (uSec) +static constexpr uint64_t GNSS_YAW_MAX_INTERVAL = + 1500e3; ///< Maximum allowable time interval between GNSS yaw measurements (uSec) +static constexpr uint64_t MAG_MAX_INTERVAL = + 500e3; ///< Maximum allowable time interval between magnetic field measurements (uSec) // bad accelerometer detection and mitigation -static constexpr uint64_t BADACC_PROBATION = 10e6; ///< Period of time that accel data declared bad must continuously pass checks to be declared good again (uSec) -static constexpr float BADACC_BIAS_PNOISE = 4.9f; ///< The delta velocity process noise is set to this when accel data is declared bad (m/sec**2) +static constexpr uint64_t BADACC_PROBATION = + 10e6; ///< Period of time that accel data declared bad must continuously pass checks to be declared good again (uSec) +static constexpr float BADACC_BIAS_PNOISE = + 4.9f; ///< The delta velocity process noise is set to this when accel data is declared bad (m/sec**2) // ground effect compensation -static constexpr uint64_t GNDEFFECT_TIMEOUT = 10e6; ///< Maximum period of time that ground effect protection will be active after it was last turned on (uSec) +static constexpr uint64_t GNDEFFECT_TIMEOUT = + 10e6; ///< Maximum period of time that ground effect protection will be active after it was last turned on (uSec) enum class PositionFrame : uint8_t { LOCAL_FRAME_NED = 0, @@ -93,8 +101,8 @@ enum class VelocityFrame : uint8_t { #if defined(CONFIG_EKF2_MAGNETOMETER) enum GeoDeclinationMask : uint8_t { // Bit locations for mag_declination_source - USE_GEO_DECL = (1<<0), ///< set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value - SAVE_GEO_DECL = (1<<1) ///< set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library + USE_GEO_DECL = (1 << 0), ///< set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value + SAVE_GEO_DECL = (1 << 1) ///< set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library }; enum MagFuseType : uint8_t { @@ -128,16 +136,16 @@ enum class PositionSensor : uint8_t { }; enum class ImuCtrl : uint8_t { - GyroBias = (1<<0), - AccelBias = (1<<1), - GravityVector = (1<<2), + GyroBias = (1 << 0), + AccelBias = (1 << 1), + GravityVector = (1 << 2), }; enum class GnssCtrl : uint8_t { - HPOS = (1<<0), - VPOS = (1<<1), - VEL = (1<<2), - YAW = (1<<3) + HPOS = (1 << 0), + VPOS = (1 << 1), + VEL = (1 << 2), + YAW = (1 << 3) }; enum class RngCtrl : uint8_t { @@ -147,10 +155,10 @@ enum class RngCtrl : uint8_t { }; enum class EvCtrl : uint8_t { - HPOS = (1<<0), - VPOS = (1<<1), - VEL = (1<<2), - YAW = (1<<3) + HPOS = (1 << 0), + VPOS = (1 << 1), + VEL = (1 << 2), + YAW = (1 << 3) }; enum class MagCheckMask : uint8_t { @@ -271,7 +279,7 @@ struct parameters { float accel_bias_p_noise{1.0e-2f}; ///< process noise for IMU accelerometer bias prediction (m/sec**3) #if defined(CONFIG_EKF2_WIND) - const float initial_wind_uncertainty{1.0f}; ///< 1-sigma initial uncertainty in wind velocity (m/sec) + const float initial_wind_uncertainty {1.0f}; ///< 1-sigma initial uncertainty in wind velocity (m/sec) float wind_vel_nsd{1.0e-2f}; ///< process noise spectral density for wind velocity prediction (m/sec**2/sqrt(Hz)) const float wind_vel_nsd_scaler{0.5f}; ///< scaling of wind process noise with vertical velocity #endif // CONFIG_EKF2_WIND @@ -282,7 +290,7 @@ struct parameters { float initial_tilt_err{0.1f}; ///< 1-sigma tilt error after initial alignment using gravity vector (rad) #if defined(CONFIG_EKF2_BAROMETER) - int32_t baro_ctrl{1}; + int32_t baro_ctrl {1}; float baro_delay_ms{0.0f}; ///< barometer height measurement delay relative to the IMU (mSec) float baro_noise{2.0f}; ///< observation noise for barometric height fusion (m) float baro_bias_nsd{0.13f}; ///< process noise for barometric height bias estimation (m/s/sqrt(Hz)) @@ -305,7 +313,7 @@ struct parameters { #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_GNSS) - int32_t gnss_ctrl{static_cast(GnssCtrl::HPOS) | static_cast(GnssCtrl::VEL)}; + int32_t gnss_ctrl {static_cast(GnssCtrl::HPOS) | static_cast(GnssCtrl::VEL)}; float gps_delay_ms{110.0f}; ///< GPS measurement delay relative to the IMU (mSec) Vector3f gps_pos_body{}; ///< xyz position of the GPS antenna in body frame (m) @@ -346,7 +354,7 @@ struct parameters { float mag_heading_noise{3.0e-1f}; ///< measurement noise used for simple heading fusion (rad) #if defined(CONFIG_EKF2_MAGNETOMETER) - float mag_delay_ms{0.0f}; ///< magnetometer measurement delay relative to the IMU (mSec) + float mag_delay_ms {0.0f}; ///< magnetometer measurement delay relative to the IMU (mSec) float mage_p_noise{1.0e-3f}; ///< process noise for earth magnetic field prediction (Gauss/sec) float magb_p_noise{1.0e-4f}; ///< process noise for body magnetic field prediction (Gauss/sec) @@ -383,13 +391,13 @@ struct parameters { #endif // CONFIG_EKF2_SIDESLIP #if defined(CONFIG_EKF2_TERRAIN) - float terrain_p_noise{5.0f}; ///< process noise for terrain offset (m/sec) + float terrain_p_noise {5.0f}; ///< process noise for terrain offset (m/sec) float terrain_gradient{0.5f}; ///< gradient of terrain used to estimate process noise due to changing position (m/m) const float terrain_timeout{10.f}; ///< maximum time for invalid bottom distance measurements before resetting terrain estimate (s) #endif // CONFIG_EKF2_TERRAIN #if defined(CONFIG_EKF2_TERRAIN) || defined(CONFIG_EKF2_OPTICAL_FLOW) || defined(CONFIG_EKF2_RANGE_FINDER) - float rng_gnd_clearance{0.1f}; ///< minimum valid value for range when on ground (m) + float rng_gnd_clearance {0.1f}; ///< minimum valid value for range when on ground (m) #endif // CONFIG_EKF2_TERRAIN || CONFIG_EKF2_OPTICAL_FLOW || CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_RANGE_FINDER) @@ -433,7 +441,7 @@ struct parameters { #endif // CONFIG_EKF2_GRAVITY_FUSION #if defined(CONFIG_EKF2_OPTICAL_FLOW) - int32_t flow_ctrl{0}; + int32_t flow_ctrl {0}; float flow_delay_ms{5.0f}; ///< optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval // optical flow fusion @@ -494,7 +502,8 @@ union fault_status_u { bool bad_hdg : 1; ///< 3 - true if the fusion of the heading angle has encountered a numerical error bool bad_mag_decl : 1; ///< 4 - true if the fusion of the magnetic declination has encountered a numerical error bool bad_airspeed : 1; ///< 5 - true if fusion of the airspeed has encountered a numerical error - bool bad_sideslip : 1; ///< 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error +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 @@ -555,7 +564,8 @@ union filter_control_status_u { uint64_t in_air : 1; ///< 7 - true when the vehicle is airborne uint64_t wind : 1; ///< 8 - true when wind velocity is being estimated uint64_t baro_hgt : 1; ///< 9 - true when baro height is being fused as a primary height reference - uint64_t rng_hgt : 1; ///< 10 - true when range finder height is being fused as a primary height reference +uint64_t rng_hgt : + 1; ///< 10 - true when range finder height is being fused as a primary height reference uint64_t gps_hgt : 1; ///< 11 - true when GPS height is being fused as a primary height reference uint64_t ev_pos : 1; ///< 12 - true when local position data fusion from external vision is intended uint64_t ev_yaw : 1; ///< 13 - true when yaw data from external vision measurements fusion is intended @@ -563,26 +573,38 @@ union filter_control_status_u { uint64_t fuse_beta : 1; ///< 15 - true when synthetic sideslip measurements are being fused uint64_t mag_field_disturbed : 1; ///< 16 - true when the mag field does not match the expected strength uint64_t fixed_wing : 1; ///< 17 - true when the vehicle is operating as a fixed wing vehicle - uint64_t mag_fault : 1; ///< 18 - true when the magnetometer has been declared faulty and is no longer being used +uint64_t mag_fault : + 1; ///< 18 - true when the magnetometer has been declared faulty and is no longer being used uint64_t fuse_aspd : 1; ///< 19 - true when airspeed measurements are being fused - uint64_t gnd_effect : 1; ///< 20 - true when protection from ground effect induced static pressure rise is active - uint64_t rng_stuck : 1; ///< 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough - uint64_t gps_yaw : 1; ///< 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended +uint64_t gnd_effect : + 1; ///< 20 - true when protection from ground effect induced static pressure rise is active +uint64_t rng_stuck : + 1; ///< 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough +uint64_t gps_yaw : + 1; ///< 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended uint64_t mag_aligned_in_flight : 1; ///< 23 - true when the in-flight mag field alignment has been completed - uint64_t ev_vel : 1; ///< 24 - true when local frame velocity data fusion from external vision measurements is intended - uint64_t synthetic_mag_z : 1; ///< 25 - true when we are using a synthesized measurement for the magnetometer Z component +uint64_t ev_vel : + 1; ///< 24 - true when local frame velocity data fusion from external vision measurements is intended +uint64_t synthetic_mag_z : + 1; ///< 25 - true when we are using a synthesized measurement for the magnetometer Z component uint64_t vehicle_at_rest : 1; ///< 26 - true when the vehicle is at rest - uint64_t gps_yaw_fault : 1; ///< 27 - true when the GNSS heading has been declared faulty and is no longer being used - uint64_t rng_fault : 1; ///< 28 - true when the range finder has been declared faulty and is no longer being used - uint64_t inertial_dead_reckoning : 1; ///< 29 - true if we are no longer fusing measurements that constrain horizontal velocity drift +uint64_t gps_yaw_fault : + 1; ///< 27 - true when the GNSS heading has been declared faulty and is no longer being used +uint64_t rng_fault : + 1; ///< 28 - true when the range finder has been declared faulty and is no longer being used +uint64_t inertial_dead_reckoning : + 1; ///< 29 - true if we are no longer fusing measurements that constrain horizontal velocity drift uint64_t wind_dead_reckoning : 1; ///< 30 - true if we are navigationg reliant on wind relative measurements uint64_t rng_kin_consistent : 1; ///< 31 - true when the range finder kinematic consistency check is passing uint64_t fake_pos : 1; ///< 32 - true when fake position measurements are being fused uint64_t fake_hgt : 1; ///< 33 - true when fake height measurements are being fused uint64_t gravity_vector : 1; ///< 34 - true when gravity vector measurements are being fused - uint64_t mag : 1; ///< 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended - uint64_t ev_yaw_fault : 1; ///< 36 - true when the EV heading has been declared faulty and is no longer being used - uint64_t mag_heading_consistent : 1; ///< 37 - true when the heading obtained from mag data is declared consistent with the filter +uint64_t mag : + 1; ///< 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended +uint64_t ev_yaw_fault : + 1; ///< 36 - true when the EV heading has been declared faulty and is no longer being used +uint64_t mag_heading_consistent : + 1; ///< 37 - true when the heading obtained from mag data is declared consistent with the filter uint64_t aux_gpos : 1; ///< 38 - true if auxiliary global position measurement fusion is intended uint64_t rng_terrain : 1; ///< 39 - true if we are fusing range finder data for terrain uint64_t opt_flow_terrain : 1; ///< 40 - true if we are fusing flow data for terrain @@ -601,9 +623,12 @@ union ekf_solution_status_u { uint16_t pos_horiz_abs : 1; ///< 4 - True if the horizontal position (absolute) estimate is good uint16_t pos_vert_abs : 1; ///< 5 - True if the vertical position (absolute) estimate is good uint16_t pos_vert_agl : 1; ///< 6 - True if the vertical position (above ground) estimate is good - uint16_t const_pos_mode : 1; ///< 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) - uint16_t pred_pos_horiz_rel : 1; ///< 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate - uint16_t pred_pos_horiz_abs : 1; ///< 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate +uint16_t const_pos_mode : + 1; ///< 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) +uint16_t pred_pos_horiz_rel : + 1; ///< 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate +uint16_t pred_pos_horiz_abs : + 1; ///< 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate uint16_t gps_glitch : 1; ///< 10 - True if the EKF has detected a GPS glitch uint16_t accel_error : 1; ///< 11 - True if the EKF has detected bad accelerometer data } flags; @@ -621,16 +646,22 @@ union information_event_status_u { bool reset_pos_to_last_known : 1; ///< 5 - true when the position states are reset to the last known position bool reset_pos_to_gps : 1; ///< 6 - true when the position states are reset to the gps measurement bool reset_pos_to_vision : 1; ///< 7 - true when the position states are reset to the vision system measurement - bool starting_gps_fusion : 1; ///< 8 - true when the filter starts using gps measurements to correct the state estimates - bool starting_vision_pos_fusion : 1; ///< 9 - true when the filter starts using vision system position measurements to correct the state estimates - bool starting_vision_vel_fusion : 1; ///< 10 - true when the filter starts using vision system velocity measurements to correct the state estimates - bool starting_vision_yaw_fusion : 1; ///< 11 - true when the filter starts using vision system yaw measurements to correct the state estimates - bool yaw_aligned_to_imu_gps : 1; ///< 12 - true when the filter resets the yaw to an estimate derived from IMU and GPS data +bool starting_gps_fusion : + 1; ///< 8 - true when the filter starts using gps measurements to correct the state estimates +bool starting_vision_pos_fusion : + 1; ///< 9 - true when the filter starts using vision system position measurements to correct the state estimates +bool starting_vision_vel_fusion : + 1; ///< 10 - true when the filter starts using vision system velocity measurements to correct the state estimates +bool starting_vision_yaw_fusion : + 1; ///< 11 - true when the filter starts using vision system yaw measurements to correct the state estimates +bool yaw_aligned_to_imu_gps : + 1; ///< 12 - true when the filter resets the yaw to an estimate derived from IMU and GPS data bool reset_hgt_to_baro : 1; ///< 13 - true when the vertical position state is reset to the baro measurement bool reset_hgt_to_gps : 1; ///< 14 - true when the vertical position state is reset to the gps measurement bool reset_hgt_to_rng : 1; ///< 15 - true when the vertical position state is reset to the rng measurement bool reset_hgt_to_ev : 1; ///< 16 - true when the vertical position state is reset to the ev measurement - bool reset_pos_to_ext_obs : 1; ///< 17 - true when horizontal position was reset to an external observation while deadreckoning +bool reset_pos_to_ext_obs : + 1; ///< 17 - true when horizontal position was reset to an external observation while deadreckoning } flags; uint32_t value; }; @@ -639,17 +670,27 @@ union information_event_status_u { union warning_event_status_u { struct { bool gps_quality_poor : 1; ///< 0 - true when the gps is failing quality checks - bool gps_fusion_timout : 1; ///< 1 - true when the gps data has not been used to correct the state estimates for a significant time period +bool gps_fusion_timout : + 1; ///< 1 - true when the gps data has not been used to correct the state estimates for a significant time period bool gps_data_stopped : 1; ///< 2 - true when the gps data has stopped for a significant time period - bool gps_data_stopped_using_alternate : 1; ///< 3 - true when the gps data has stopped for a significant time period but the filter is able to use other sources of data to maintain navigation - bool height_sensor_timeout : 1; ///< 4 - true when the height sensor has not been used to correct the state estimates for a significant time period - bool stopping_navigation : 1; ///< 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation - bool invalid_accel_bias_cov_reset : 1; ///< 6 - true when the filter has detected bad acceerometer bias state estimates and has reset the corresponding covariance matrix elements - bool bad_yaw_using_gps_course : 1; ///< 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course - bool stopping_mag_use : 1; ///< 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetometer data - bool vision_data_stopped : 1; ///< 9 - true when the vision system data has stopped for a significant time period - bool emergency_yaw_reset_mag_stopped : 1; ///< 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetometer data - bool emergency_yaw_reset_gps_yaw_stopped: 1; ///< 11 - true when the filter has detected bad GNSS yaw data, has reset the yaw to anothter source of data and has stopped further use of the GNSS yaw data +bool gps_data_stopped_using_alternate : + 1; ///< 3 - true when the gps data has stopped for a significant time period but the filter is able to use other sources of data to maintain navigation +bool height_sensor_timeout : + 1; ///< 4 - true when the height sensor has not been used to correct the state estimates for a significant time period +bool stopping_navigation : + 1; ///< 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation +bool invalid_accel_bias_cov_reset : + 1; ///< 6 - true when the filter has detected bad acceerometer bias state estimates and has reset the corresponding covariance matrix elements +bool bad_yaw_using_gps_course : + 1; ///< 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course +bool stopping_mag_use : + 1; ///< 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetometer data +bool vision_data_stopped : + 1; ///< 9 - true when the vision system data has stopped for a significant time period +bool emergency_yaw_reset_mag_stopped : + 1; ///< 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetometer data +bool emergency_yaw_reset_gps_yaw_stopped: + 1; ///< 11 - true when the filter has detected bad GNSS yaw data, has reset the yaw to anothter source of data and has stopped further use of the GNSS yaw data } flags; uint32_t value; }; diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 519cbbcfa28f..8108d26c1381 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -76,14 +76,17 @@ void Ekf::initialiseCovariance() if (_control_status.flags.gps_hgt) { z_pos_var = sq(fmaxf(1.5f * _params.gps_pos_noise, 0.01f)); } + #else const float xy_pos_var = sq(fmaxf(_params.pos_noaid_noise, 0.01f)); #endif #if defined(CONFIG_EKF2_RANGE_FINDER) + if (_control_status.flags.rng_hgt) { z_pos_var = sq(fmaxf(_params.range_noise, 0.01f)); } + #endif // CONFIG_EKF2_RANGE_FINDER P.uncorrelateCovarianceSetVariance(State::pos.idx, Vector3f(xy_pos_var, xy_pos_var, z_pos_var)); @@ -191,13 +194,16 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) P(i, i) += mag_B_process_noise; } } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) + if (_control_status.flags.wind) { // wind vel: add process noise - float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); + float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, + 1.f) * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt; for (unsigned index = 0; index < State::wind_vel.dof; index++) { @@ -205,18 +211,22 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) P(i, i) += wind_vel_process_noise; } } + #endif // CONFIG_EKF2_WIND #if defined(CONFIG_EKF2_TERRAIN) + if (_height_sensor_ref != HeightSensor::RANGE) { // predict the state variance growth where the state is the vertical position of the terrain underneath the vehicle // process noise due to errors in vehicle height estimate float terrain_process_noise = sq(imu_delayed.delta_vel_dt * _params.terrain_p_noise); // process noise due to terrain gradient - terrain_process_noise += sq(imu_delayed.delta_vel_dt * _params.terrain_gradient) * (sq(_state.vel(0)) + sq(_state.vel(1))); + terrain_process_noise += sq(imu_delayed.delta_vel_dt * _params.terrain_gradient) * (sq(_state.vel(0)) + sq(_state.vel( + 1))); P(State::terrain.idx, State::terrain.idx) += terrain_process_noise; } + #endif // CONFIG_EKF2_TERRAIN // covariance matrix is symmetrical, so copy upper half to lower half @@ -244,16 +254,20 @@ void Ekf::constrainStateVariances() constrainStateVarLimitRatio(State::accel_bias, kAccelBiasVarianceMin, 1.f); #if defined(CONFIG_EKF2_MAGNETOMETER) + if (_control_status.flags.mag) { constrainStateVarLimitRatio(State::mag_I, kMagVarianceMin, 1.f); constrainStateVarLimitRatio(State::mag_B, kMagVarianceMin, 1.f); } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) + if (_control_status.flags.wind) { constrainStateVarLimitRatio(State::wind_vel, 1e-6f, 1e6f); } + #endif // CONFIG_EKF2_WIND #if defined(CONFIG_EKF2_TERRAIN) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index ac410b4d8d64..4479dc37b8ea 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -168,7 +168,8 @@ bool Ekf::update() // control fusion of observation data controlFusionModes(imu_sample_delayed); - _output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, _state.gyro_bias, _state.accel_bias); + _output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, + _state.gyro_bias, _state.accel_bias); return true; } @@ -281,7 +282,8 @@ 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(double lat_deg, double lon_deg, float accuracy, + uint64_t timestamp_observation) { if (!_pos_ref.isInitialized()) { ECL_WARN("unable to reset global position, position reference not initialized"); @@ -315,7 +317,7 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl 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))}; + sq(innov(1)) / (sq_gate * innov_var(1))}; const bool innov_rejected = (test_ratio.max() > 1.f); @@ -331,8 +333,8 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl } 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) - ) { + && fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1) + ) { ECL_INFO("fused external observation as position measurement"); _time_last_hor_pos_fuse = _time_delayed_us; _last_known_pos.xy() = _state.pos.xy(); @@ -366,40 +368,49 @@ void Ekf::print_status() printf("\nStates: (%.4f seconds ago)\n", (_time_latest_us - _time_delayed_us) * 1e-6); printf("Orientation (%d-%d): [%.3f, %.3f, %.3f, %.3f] (Euler [%.1f, %.1f, %.1f] deg) var: [%.1e, %.1e, %.1e]\n", State::quat_nominal.idx, State::quat_nominal.idx + State::quat_nominal.dof - 1, - (double)_state.quat_nominal(0), (double)_state.quat_nominal(1), (double)_state.quat_nominal(2), (double)_state.quat_nominal(3), - (double)math::degrees(matrix::Eulerf(_state.quat_nominal).phi()), (double)math::degrees(matrix::Eulerf(_state.quat_nominal).theta()), (double)math::degrees(matrix::Eulerf(_state.quat_nominal).psi()), - (double)getStateVariance()(0), (double)getStateVariance()(1), (double)getStateVariance()(2) + (double)_state.quat_nominal(0), (double)_state.quat_nominal(1), (double)_state.quat_nominal(2), + (double)_state.quat_nominal(3), + (double)math::degrees(matrix::Eulerf(_state.quat_nominal).phi()), + (double)math::degrees(matrix::Eulerf(_state.quat_nominal).theta()), + (double)math::degrees(matrix::Eulerf(_state.quat_nominal).psi()), + (double)getStateVariance()(0), (double)getStateVariance()(1), + (double)getStateVariance()(2) ); printf("Velocity (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n", State::vel.idx, State::vel.idx + State::vel.dof - 1, (double)_state.vel(0), (double)_state.vel(1), (double)_state.vel(2), - (double)getStateVariance()(0), (double)getStateVariance()(1), (double)getStateVariance()(2) + (double)getStateVariance()(0), (double)getStateVariance()(1), + (double)getStateVariance()(2) ); printf("Position (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n", State::pos.idx, State::pos.idx + State::pos.dof - 1, (double)_state.pos(0), (double)_state.pos(1), (double)_state.pos(2), - (double)getStateVariance()(0), (double)getStateVariance()(1), (double)getStateVariance()(2) + (double)getStateVariance()(0), (double)getStateVariance()(1), + (double)getStateVariance()(2) ); printf("Gyro Bias (%d-%d): [%.6f, %.6f, %.6f] var: [%.1e, %.1e, %.1e]\n", State::gyro_bias.idx, State::gyro_bias.idx + State::gyro_bias.dof - 1, (double)_state.gyro_bias(0), (double)_state.gyro_bias(1), (double)_state.gyro_bias(2), - (double)getStateVariance()(0), (double)getStateVariance()(1), (double)getStateVariance()(2) + (double)getStateVariance()(0), (double)getStateVariance()(1), + (double)getStateVariance()(2) ); printf("Accel Bias (%d-%d): [%.6f, %.6f, %.6f] var: [%.1e, %.1e, %.1e]\n", State::accel_bias.idx, State::accel_bias.idx + State::accel_bias.dof - 1, (double)_state.accel_bias(0), (double)_state.accel_bias(1), (double)_state.accel_bias(2), - (double)getStateVariance()(0), (double)getStateVariance()(1), (double)getStateVariance()(2) + (double)getStateVariance()(0), (double)getStateVariance()(1), + (double)getStateVariance()(2) ); #if defined(CONFIG_EKF2_MAGNETOMETER) printf("Magnetic Field (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n", State::mag_I.idx, State::mag_I.idx + State::mag_I.dof - 1, (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2), - (double)getStateVariance()(0), (double)getStateVariance()(1), (double)getStateVariance()(2) + (double)getStateVariance()(0), (double)getStateVariance()(1), + (double)getStateVariance()(2) ); printf("Magnetic Bias (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n", diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 42ea84aa1f8a..1b20c433e2a6 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -138,21 +138,27 @@ class Ekf final : public EstimatorInterface float getHeadingInnov() const { #if defined(CONFIG_EKF2_MAGNETOMETER) + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { return Vector3f(_aid_src_mag.innovation).max(); } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_GNSS_YAW) + if (_control_status.flags.gps_yaw) { return _aid_src_gnss_yaw.innovation; } + #endif // CONFIG_EKF2_GNSS_YAW #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_yaw) { return _aid_src_ev_yaw.innovation; } + #endif // CONFIG_EKF2_EXTERNAL_VISION return 0.f; @@ -161,21 +167,27 @@ class Ekf final : public EstimatorInterface float getHeadingInnovVar() const { #if defined(CONFIG_EKF2_MAGNETOMETER) + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { return Vector3f(_aid_src_mag.innovation_variance).max(); } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_GNSS_YAW) + if (_control_status.flags.gps_yaw) { return _aid_src_gnss_yaw.innovation_variance; } + #endif // CONFIG_EKF2_GNSS_YAW #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_yaw) { return _aid_src_ev_yaw.innovation_variance; } + #endif // CONFIG_EKF2_EXTERNAL_VISION return 0.f; @@ -184,21 +196,27 @@ class Ekf final : public EstimatorInterface float getHeadingInnovRatio() const { #if defined(CONFIG_EKF2_MAGNETOMETER) + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { return Vector3f(_aid_src_mag.test_ratio).max(); } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_GNSS_YAW) + if (_control_status.flags.gps_yaw) { return _aid_src_gnss_yaw.test_ratio; } + #endif // CONFIG_EKF2_GNSS_YAW #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_yaw) { return _aid_src_ev_yaw.test_ratio; } + #endif // CONFIG_EKF2_EXTERNAL_VISION return 0.f; @@ -490,6 +508,7 @@ class Ekf final : public EstimatorInterface P(j, i) = P(i, j); } } + #endif constrainStateVariances(); @@ -499,7 +518,8 @@ class Ekf final : public EstimatorInterface return true; } - bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation); + bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, + uint64_t timestamp_observation); void updateParameters(); @@ -576,7 +596,7 @@ class Ekf final : public EstimatorInterface SquareMatrixState P{}; ///< state covariance matrix #if defined(CONFIG_EKF2_DRAG_FUSION) - estimator_aid_source2d_s _aid_src_drag{}; + estimator_aid_source2d_s _aid_src_drag {}; #endif // CONFIG_EKF2_DRAG_FUSION #if defined(CONFIG_EKF2_TERRAIN) @@ -587,11 +607,11 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_TERRAIN #if defined(CONFIG_EKF2_RANGE_FINDER) - estimator_aid_source1d_s _aid_src_rng_hgt{}; + estimator_aid_source1d_s _aid_src_rng_hgt {}; #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_OPTICAL_FLOW) - estimator_aid_source2d_s _aid_src_optical_flow{}; + estimator_aid_source2d_s _aid_src_optical_flow {}; // optical flow processing Vector3f _flow_gyro_bias{}; ///< bias errors in optical flow sensor rate gyro outputs (rad/sec) @@ -603,17 +623,17 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_OPTICAL_FLOW #if defined(CONFIG_EKF2_AIRSPEED) - estimator_aid_source1d_s _aid_src_airspeed{}; + estimator_aid_source1d_s _aid_src_airspeed {}; #endif // CONFIG_EKF2_AIRSPEED #if defined(CONFIG_EKF2_SIDESLIP) - estimator_aid_source1d_s _aid_src_sideslip{}; + estimator_aid_source1d_s _aid_src_sideslip {}; #endif // CONFIG_EKF2_SIDESLIP estimator_aid_source2d_s _aid_src_fake_pos{}; estimator_aid_source1d_s _aid_src_fake_hgt{}; #if defined(CONFIG_EKF2_EXTERNAL_VISION) - estimator_aid_source1d_s _aid_src_ev_hgt{}; + estimator_aid_source1d_s _aid_src_ev_hgt {}; estimator_aid_source2d_s _aid_src_ev_pos{}; estimator_aid_source3d_s _aid_src_ev_vel{}; estimator_aid_source1d_s _aid_src_ev_yaw{}; @@ -624,7 +644,7 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_GNSS) - bool _gps_data_ready{false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused + bool _gps_data_ready {false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused // variables used for the GPS quality checks Vector3f _gps_pos_deriv_filt{}; ///< GPS NED position derivative (m/sec) @@ -647,16 +667,16 @@ class Ekf final : public EstimatorInterface estimator_aid_source3d_s _aid_src_gnss_vel{}; # if defined(CONFIG_EKF2_GNSS_YAW) - estimator_aid_source1d_s _aid_src_gnss_yaw{}; + estimator_aid_source1d_s _aid_src_gnss_yaw {}; # endif // CONFIG_EKF2_GNSS_YAW #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_GRAVITY_FUSION) - estimator_aid_source3d_s _aid_src_gravity{}; + estimator_aid_source3d_s _aid_src_gravity {}; #endif // CONFIG_EKF2_GRAVITY_FUSION #if defined(CONFIG_EKF2_AUXVEL) - estimator_aid_source2d_s _aid_src_aux_vel{}; + estimator_aid_source2d_s _aid_src_aux_vel {}; #endif // CONFIG_EKF2_AUXVEL // Variables used by the initial filter alignment @@ -665,7 +685,7 @@ class Ekf final : public EstimatorInterface AlphaFilter _gyro_lpf{0.1f}; ///< filtered gyro measurement used for alignment excessive movement check (rad/sec) #if defined(CONFIG_EKF2_BAROMETER) - estimator_aid_source1d_s _aid_src_baro_hgt{}; + estimator_aid_source1d_s _aid_src_baro_hgt {}; // Variables used to perform in flight resets and switch between height sources AlphaFilter _baro_lpf{0.1f}; ///< filtered barometric height measurement (m) @@ -729,7 +749,8 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // ekf sequential fusion of magnetometer measurements - bool fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = false, bool update_tilt = false); + bool fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, + bool update_all_states = false, bool update_tilt = false); // fuse magnetometer declination measurement // argument passed in is the declination uncertainty in radians @@ -790,7 +811,8 @@ class Ekf final : public EstimatorInterface void resetVerticalVelocityToZero(); // horizontal and vertical position aid source - void updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, const float observation, const float observation_variance, const float innovation_gate = 1.f) const; + void updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, + const float observation, const float observation_variance, const float innovation_gate = 1.f) const; // horizontal and vertical position fusion bool fuseHorizontalPosition(estimator_aid_source2d_s &pos_aid_src); @@ -870,6 +892,7 @@ class Ekf final : public EstimatorInterface } #if defined(CONFIG_EKF2_MAGNETOMETER) + if (!_control_status.flags.mag) { for (unsigned i = 0; i < State::mag_I.dof; i++) { K(State::mag_I.idx + i) = 0.f; @@ -881,14 +904,17 @@ class Ekf final : public EstimatorInterface K(State::mag_B.idx + i) = 0.f; } } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) + if (!_control_status.flags.wind) { for (unsigned i = 0; i < State::wind_vel.dof; i++) { K(State::wind_vel.idx + i) = 0.f; } } + #endif // CONFIG_EKF2_WIND } @@ -912,15 +938,20 @@ class Ekf final : public EstimatorInterface // control fusion of external vision observations void controlExternalVisionFusion(); void updateEvAttitudeErrorFilter(extVisionSample &ev_sample, bool ev_reset); - void controlEvHeightFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src); - void controlEvPosFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source2d_s &aid_src); - void controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src); - void controlEvYawFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src); + void controlEvHeightFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, + const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src); + void controlEvPosFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, + const bool ev_reset, const bool quality_sufficient, estimator_aid_source2d_s &aid_src); + void controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, + const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src); + void controlEvYawFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, + const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src); void resetVelocityToEV(const Vector3f &measurement, const Vector3f &measurement_var, const VelocityFrame &vel_frame); Vector3f rotateVarianceToEkf(const Vector3f &measurement_var); void startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, estimator_aid_source2d_s &aid_src); - void updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, bool reset, estimator_aid_source2d_s &aid_src); + void updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, + bool reset, estimator_aid_source2d_s &aid_src); void stopEvPosFusion(); void stopEvHgtFusion(); void stopEvVelFusion(); @@ -1091,7 +1122,7 @@ class Ekf final : public EstimatorInterface PositionSensor _position_sensor_ref{PositionSensor::GNSS}; #if defined(CONFIG_EKF2_EXTERNAL_VISION) - HeightBiasEstimator _ev_hgt_b_est{HeightSensor::EV, _height_sensor_ref}; + HeightBiasEstimator _ev_hgt_b_est {HeightSensor::EV, _height_sensor_ref}; PositionBiasEstimator _ev_pos_b_est{PositionSensor::EV, _position_sensor_ref}; AlphaFilter _ev_q_error_filt{0.001f}; bool _ev_q_error_initialized{false}; @@ -1297,7 +1328,7 @@ class Ekf final : public EstimatorInterface ZeroVelocityUpdate _zero_velocity_update{}; #if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME) - AuxGlobalPosition _aux_global_position{}; + AuxGlobalPosition _aux_global_position {}; #endif // CONFIG_EKF2_AUX_GLOBAL_POSITION }; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 621ac87c6571..e44d6c0bf61b 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -72,13 +72,14 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo return _NED_origin_initialised; } -bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float eph, const float epv) +bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float 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) - ) { + && 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); @@ -107,6 +108,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons _wmm_gps_time_last_set = _time_delayed_us; } + #endif // CONFIG_EKF2_MAGNETOMETER _gpos_origin_eph = eph; @@ -176,15 +178,19 @@ void Ekf::get_ekf_lpos_accuracy(float *ekf_eph, float *ekf_epv) const // and using state variances for accuracy reporting is overly optimistic in these situations if (_horizontal_deadreckon_time_exceeded) { #if defined(CONFIG_EKF2_GNSS) + if (_control_status.flags.gps) { hpos_err = math::max(hpos_err, Vector2f(_aid_src_gnss_pos.innovation).norm()); } + #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_pos) { hpos_err = math::max(hpos_err, Vector2f(_aid_src_ev_pos.innovation).norm()); } + #endif // CONFIG_EKF2_EXTERNAL_VISION } @@ -203,19 +209,24 @@ void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const float vel_err_conservative = 0.0f; #if defined(CONFIG_EKF2_OPTICAL_FLOW) + if (_control_status.flags.opt_flow) { float gndclearance = math::max(_params.rng_gnd_clearance, 0.1f); vel_err_conservative = math::max(getHagl(), gndclearance) * Vector2f(_aid_src_optical_flow.innovation).norm(); } + #endif // CONFIG_EKF2_OPTICAL_FLOW #if defined(CONFIG_EKF2_GNSS) + if (_control_status.flags.gps) { vel_err_conservative = math::max(vel_err_conservative, Vector2f(_aid_src_gnss_pos.innovation).norm()); } + #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_pos) { vel_err_conservative = math::max(vel_err_conservative, Vector2f(_aid_src_ev_pos.innovation).norm()); } @@ -223,6 +234,7 @@ void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const if (_control_status.flags.ev_vel) { vel_err_conservative = math::max(vel_err_conservative, Vector2f(_aid_src_ev_vel.innovation).norm()); } + #endif // CONFIG_EKF2_EXTERNAL_VISION hvel_err = math::max(hvel_err, vel_err_conservative); @@ -282,6 +294,7 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl *hagl_min = flow_hagl_min; *hagl_max = flow_hagl_max; } + # endif // CONFIG_EKF2_OPTICAL_FLOW #endif // CONFIG_EKF2_RANGE_FINDER @@ -309,23 +322,29 @@ float Ekf::getHeadingInnovationTestRatio() const float test_ratio = 0.f; #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) { + + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { for (auto &test_ratio_filtered : _aid_src_mag.test_ratio_filtered) { test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); } } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_GNSS_YAW) + if (_control_status.flags.gps_yaw) { test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_yaw.test_ratio_filtered)); } + #endif // CONFIG_EKF2_GNSS_YAW #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_yaw) { test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_yaw.test_ratio_filtered)); } + #endif // CONFIG_EKF2_EXTERNAL_VISION return sqrtf(test_ratio); @@ -337,27 +356,33 @@ float Ekf::getVelocityInnovationTestRatio() const float test_ratio = -1.f; #if defined(CONFIG_EKF2_GNSS) + if (_control_status.flags.gps) { for (int i = 0; i < 3; i++) { test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_vel.test_ratio_filtered[i])); } } + #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_vel) { for (int i = 0; i < 3; i++) { test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_vel.test_ratio_filtered[i])); } } + #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_OPTICAL_FLOW) + if (isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)) { for (auto &test_ratio_filtered : _aid_src_optical_flow.test_ratio_filtered) { test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); } } + #endif // CONFIG_EKF2_OPTICAL_FLOW if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { @@ -373,25 +398,31 @@ float Ekf::getHorizontalPositionInnovationTestRatio() const float test_ratio = -1.f; #if defined(CONFIG_EKF2_GNSS) + if (_control_status.flags.gps) { for (auto &test_ratio_filtered : _aid_src_gnss_pos.test_ratio_filtered) { test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); } } + #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_pos) { for (auto &test_ratio_filtered : _aid_src_ev_pos.test_ratio_filtered) { test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered)); } } + #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME) + if (_control_status.flags.aux_gpos) { test_ratio = math::max(test_ratio, fabsf(_aux_global_position.test_ratio_filtered())); } + #endif // CONFIG_EKF2_AUX_GLOBAL_POSITION if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { @@ -408,31 +439,39 @@ float Ekf::getVerticalPositionInnovationTestRatio() const int n_hgt_sources = 0; #if defined(CONFIG_EKF2_BAROMETER) + if (_control_status.flags.baro_hgt) { hgt_sum += sqrtf(fabsf(_aid_src_baro_hgt.test_ratio_filtered)); n_hgt_sources++; } + #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_GNSS) + if (_control_status.flags.gps_hgt) { hgt_sum += sqrtf(fabsf(_aid_src_gnss_hgt.test_ratio_filtered)); n_hgt_sources++; } + #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_RANGE_FINDER) + if (_control_status.flags.rng_hgt) { hgt_sum += sqrtf(fabsf(_aid_src_rng_hgt.test_ratio_filtered)); n_hgt_sources++; } + #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_hgt) { hgt_sum += sqrtf(fabsf(_aid_src_ev_hgt.test_ratio_filtered)); n_hgt_sources++; } + #endif // CONFIG_EKF2_EXTERNAL_VISION if (n_hgt_sources > 0) { @@ -445,10 +484,12 @@ float Ekf::getVerticalPositionInnovationTestRatio() const float Ekf::getAirspeedInnovationTestRatio() const { #if defined(CONFIG_EKF2_AIRSPEED) + if (_control_status.flags.fuse_aspd) { // return the airspeed fusion innovation test ratio return sqrtf(fabsf(_aid_src_airspeed.test_ratio_filtered)); } + #endif // CONFIG_EKF2_AIRSPEED return NAN; @@ -457,10 +498,12 @@ float Ekf::getAirspeedInnovationTestRatio() const float Ekf::getSyntheticSideslipInnovationTestRatio() const { #if defined(CONFIG_EKF2_SIDESLIP) + if (_control_status.flags.fuse_beta) { // return the synthetic sideslip innovation test ratio return sqrtf(fabsf(_aid_src_sideslip.test_ratio_filtered)); } + #endif // CONFIG_EKF2_SIDESLIP return NAN; @@ -472,10 +515,12 @@ float Ekf::getHeightAboveGroundInnovationTestRatio() const #if defined(CONFIG_EKF2_TERRAIN) # if defined(CONFIG_EKF2_RANGE_FINDER) + if (_control_status.flags.rng_terrain) { // return the terrain height innovation test ratio test_ratio = math::max(test_ratio, fabsf(_aid_src_rng_hgt.test_ratio_filtered)); } + # endif // CONFIG_EKF2_RANGE_FINDER #endif // CONFIG_EKF2_TERRAIN @@ -491,10 +536,14 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const ekf_solution_status_u soln_status{}; // TODO: Is this accurate enough? soln_status.flags.attitude = attitude_valid(); - soln_status.flags.velocity_horiz = (isHorizontalAidingActive() || (_control_status.flags.fuse_beta && _control_status.flags.fuse_aspd)) && (_fault_status.value == 0); - soln_status.flags.velocity_vert = (_control_status.flags.baro_hgt || _control_status.flags.ev_hgt || _control_status.flags.gps_hgt || _control_status.flags.rng_hgt) && (_fault_status.value == 0); - soln_status.flags.pos_horiz_rel = (_control_status.flags.gps || _control_status.flags.ev_pos || _control_status.flags.opt_flow) && (_fault_status.value == 0); - soln_status.flags.pos_horiz_abs = (_control_status.flags.gps || _control_status.flags.ev_pos) && (_fault_status.value == 0); + soln_status.flags.velocity_horiz = (isHorizontalAidingActive() || (_control_status.flags.fuse_beta + && _control_status.flags.fuse_aspd)) && (_fault_status.value == 0); + soln_status.flags.velocity_vert = (_control_status.flags.baro_hgt || _control_status.flags.ev_hgt + || _control_status.flags.gps_hgt || _control_status.flags.rng_hgt) && (_fault_status.value == 0); + soln_status.flags.pos_horiz_rel = (_control_status.flags.gps || _control_status.flags.ev_pos + || _control_status.flags.opt_flow) && (_fault_status.value == 0); + soln_status.flags.pos_horiz_abs = (_control_status.flags.gps || _control_status.flags.ev_pos) + && (_fault_status.value == 0); soln_status.flags.pos_vert_abs = soln_status.flags.velocity_vert; #if defined(CONFIG_EKF2_TERRAIN) soln_status.flags.pos_vert_agl = isTerrainEstimateValid(); @@ -506,11 +555,13 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const bool mag_innov_good = true; #if defined(CONFIG_EKF2_MAGNETOMETER) - if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) { + + if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { if (Vector3f(_aid_src_mag.test_ratio).max() < 1.f) { mag_innov_good = false; } } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_GNSS) @@ -529,7 +580,8 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const void Ekf::fuse(const VectorState &K, float innovation) { // quat_nominal - Quatf delta_quat(matrix::AxisAnglef(K.slice(State::quat_nominal.idx, 0) * (-1.f * innovation))); + Quatf delta_quat(matrix::AxisAnglef(K.slice(State::quat_nominal.idx, + 0) * (-1.f * innovation))); _state.quat_nominal = delta_quat * _state.quat_nominal; _state.quat_nominal.normalize(); _R_to_earth = Dcmf(_state.quat_nominal); @@ -541,26 +593,35 @@ void Ekf::fuse(const VectorState &K, float innovation) _state.pos = matrix::constrain(_state.pos - K.slice(State::pos.idx, 0) * innovation, -1.e6f, 1.e6f); // gyro_bias - _state.gyro_bias = matrix::constrain(_state.gyro_bias - K.slice(State::gyro_bias.idx, 0) * innovation, - -getGyroBiasLimit(), getGyroBiasLimit()); + _state.gyro_bias = matrix::constrain(_state.gyro_bias - K.slice(State::gyro_bias.idx, + 0) * innovation, + -getGyroBiasLimit(), getGyroBiasLimit()); // accel_bias - _state.accel_bias = matrix::constrain(_state.accel_bias - K.slice(State::accel_bias.idx, 0) * innovation, - -getAccelBiasLimit(), getAccelBiasLimit()); + _state.accel_bias = matrix::constrain(_state.accel_bias - K.slice(State::accel_bias.idx, + 0) * innovation, + -getAccelBiasLimit(), getAccelBiasLimit()); #if defined(CONFIG_EKF2_MAGNETOMETER) + // mag_I, mag_B if (_control_status.flags.mag) { - _state.mag_I = matrix::constrain(_state.mag_I - K.slice(State::mag_I.idx, 0) * innovation, -1.f, 1.f); - _state.mag_B = matrix::constrain(_state.mag_B - K.slice(State::mag_B.idx, 0) * innovation, -getMagBiasLimit(), getMagBiasLimit()); + _state.mag_I = matrix::constrain(_state.mag_I - K.slice(State::mag_I.idx, 0) * innovation, -1.f, + 1.f); + _state.mag_B = matrix::constrain(_state.mag_B - K.slice(State::mag_B.idx, 0) * innovation, + -getMagBiasLimit(), getMagBiasLimit()); } + #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) + // wind_vel if (_control_status.flags.wind) { - _state.wind_vel = matrix::constrain(_state.wind_vel - K.slice(State::wind_vel.idx, 0) * innovation, -1.e2f, 1.e2f); + _state.wind_vel = matrix::constrain(_state.wind_vel - K.slice(State::wind_vel.idx, + 0) * innovation, -1.e2f, 1.e2f); } + #endif // CONFIG_EKF2_WIND #if defined(CONFIG_EKF2_TERRAIN) @@ -581,40 +642,43 @@ void Ekf::updateHorizontalDeadReckoningstatus() // velocity aiding active if ((_control_status.flags.gps || _control_status.flags.ev_vel) - && isRecent(_time_last_hor_vel_fuse, _params.no_aid_timeout_max) - ) { + && isRecent(_time_last_hor_vel_fuse, _params.no_aid_timeout_max) + ) { inertial_dead_reckoning = false; } // position aiding active if ((_control_status.flags.gps || _control_status.flags.ev_pos || _control_status.flags.aux_gpos) - && isRecent(_time_last_hor_pos_fuse, _params.no_aid_timeout_max) - ) { + && isRecent(_time_last_hor_pos_fuse, _params.no_aid_timeout_max) + ) { inertial_dead_reckoning = false; } #if defined(CONFIG_EKF2_OPTICAL_FLOW) + // optical flow active if (_control_status.flags.opt_flow - && isRecent(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max) - ) { + && isRecent(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max) + ) { inertial_dead_reckoning = false; } else { if (!_control_status.flags.in_air && (_params.flow_ctrl == 1) - && isRecent(_aid_src_optical_flow.timestamp_sample, _params.no_aid_timeout_max) - ) { + && isRecent(_aid_src_optical_flow.timestamp_sample, _params.no_aid_timeout_max) + ) { // currently landed, but optical flow aiding should be possible once in air aiding_expected_in_air = true; } } + #endif // CONFIG_EKF2_OPTICAL_FLOW #if defined(CONFIG_EKF2_AIRSPEED) + // air data aiding active if ((_control_status.flags.fuse_aspd && isRecent(_aid_src_airspeed.time_last_fuse, _params.no_aid_timeout_max)) - && (_control_status.flags.fuse_beta && isRecent(_aid_src_sideslip.time_last_fuse, _params.no_aid_timeout_max)) - ) { + && (_control_status.flags.fuse_beta && isRecent(_aid_src_sideslip.time_last_fuse, _params.no_aid_timeout_max)) + ) { // wind_dead_reckoning: no other aiding but air data _control_status.flags.wind_dead_reckoning = inertial_dead_reckoning; @@ -625,13 +689,14 @@ void Ekf::updateHorizontalDeadReckoningstatus() _control_status.flags.wind_dead_reckoning = false; if (!_control_status.flags.in_air && _control_status.flags.fixed_wing - && (_params.beta_fusion_enabled == 1) - && (_params.arsp_thr > 0.f) && isRecent(_aid_src_airspeed.timestamp_sample, _params.no_aid_timeout_max) - ) { + && (_params.beta_fusion_enabled == 1) + && (_params.arsp_thr > 0.f) && isRecent(_aid_src_airspeed.timestamp_sample, _params.no_aid_timeout_max) + ) { // currently landed, but air data aiding should be possible once in air aiding_expected_in_air = true; } } + #endif // CONFIG_EKF2_AIRSPEED // zero velocity update @@ -712,6 +777,7 @@ void Ekf::updateGroundEffect() { if (_control_status.flags.in_air && !_control_status.flags.fixed_wing) { #if defined(CONFIG_EKF2_TERRAIN) + if (isTerrainEstimateValid()) { // automatically set ground effect if terrain is valid float height = getHagl(); @@ -719,12 +785,12 @@ void Ekf::updateGroundEffect() } else #endif // CONFIG_EKF2_TERRAIN - if (_control_status.flags.gnd_effect) { - // Turn off ground effect compensation if it times out - if (isTimedOut(_time_last_gnd_effect_on, GNDEFFECT_TIMEOUT)) { - _control_status.flags.gnd_effect = false; + if (_control_status.flags.gnd_effect) { + // Turn off ground effect compensation if it times out + if (isTimedOut(_time_last_gnd_effect_on, GNDEFFECT_TIMEOUT)) { + _control_status.flags.gnd_effect = false; + } } - } } else { _control_status.flags.gnd_effect = false; @@ -736,10 +802,12 @@ void Ekf::updateGroundEffect() void Ekf::resetWind() { #if defined(CONFIG_EKF2_AIRSPEED) + if (_control_status.flags.fuse_aspd && isRecent(_airspeed_sample_delayed.time_us, 1e6)) { resetWindUsingAirspeed(_airspeed_sample_delayed); return; } + #endif // CONFIG_EKF2_AIRSPEED resetWindToZero(); @@ -764,7 +832,8 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed) { const float alpha = math::constrain((imu_delayed.delta_ang_dt / _params.acc_bias_learn_tc), 0.f, 1.f); const float beta = 1.f - alpha; - _ang_rate_magnitude_filt = fmaxf(imu_delayed.delta_ang.norm() / imu_delayed.delta_ang_dt, beta * _ang_rate_magnitude_filt); + _ang_rate_magnitude_filt = fmaxf(imu_delayed.delta_ang.norm() / imu_delayed.delta_ang_dt, + beta * _ang_rate_magnitude_filt); } { @@ -789,8 +858,8 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed) // accel bias inhibit const bool do_inhibit_all_accel_axes = !(_params.imu_ctrl & static_cast(ImuCtrl::AccelBias)) - || is_manoeuvre_level_high - || _fault_status.flags.bad_acc_vertical; + || is_manoeuvre_level_high + || _fault_status.flags.bad_acc_vertical; for (unsigned index = 0; index < State::accel_bias.dof; index++) { bool is_bias_observable = true; @@ -861,6 +930,7 @@ bool Ekf::fuseDirectStateMeasurement(const float innov, const float innov_var, c P(j, i) = P(i, j); } } + #endif constrainStateVariances(); diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index 8bc021feedc3..bce6ec88637f 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -86,7 +86,8 @@ void EstimatorInterface::setIMUData(const imuSample &imu_sample) _time_latest_us = imu_sample.time_us; // the output observer always runs - _output_predictor.calculateOutputStates(imu_sample.time_us, imu_sample.delta_ang, imu_sample.delta_ang_dt, imu_sample.delta_vel, imu_sample.delta_vel_dt); + _output_predictor.calculateOutputStates(imu_sample.time_us, imu_sample.delta_ang, imu_sample.delta_ang_dt, + imu_sample.delta_vel, imu_sample.delta_vel_dt); // accumulate and down-sample imu data and push to the buffer when new downsampled data becomes available if (_imu_down_sampler.update(imu_sample)) { @@ -141,7 +142,8 @@ void EstimatorInterface::setMagData(const magSample &mag_sample) _time_last_mag_buffer_push = _time_latest_us; } else { - ECL_WARN("mag data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _mag_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("mag data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _mag_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_MAGNETOMETER @@ -179,13 +181,16 @@ void EstimatorInterface::setGpsData(const gnssSample &gnss_sample) _time_last_gps_buffer_push = _time_latest_us; #if defined(CONFIG_EKF2_GNSS_YAW) + if (PX4_ISFINITE(gnss_sample.yaw)) { _time_last_gps_yaw_buffer_push = _time_latest_us; } + #endif // CONFIG_EKF2_GNSS_YAW } else { - ECL_WARN("GPS data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _gps_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("GPS data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _gps_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_GNSS @@ -223,7 +228,8 @@ void EstimatorInterface::setBaroData(const baroSample &baro_sample) _time_last_baro_buffer_push = _time_latest_us; } else { - ECL_WARN("baro data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _baro_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("baro data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _baro_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_BAROMETER @@ -260,7 +266,8 @@ void EstimatorInterface::setAirspeedData(const airspeedSample &airspeed_sample) _airspeed_buffer->push(airspeed_sample_new); } else { - ECL_WARN("airspeed data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _airspeed_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("airspeed data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _airspeed_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_AIRSPEED @@ -298,7 +305,8 @@ void EstimatorInterface::setRangeData(const sensor::rangeSample &range_sample) _time_last_range_buffer_push = _time_latest_us; } else { - ECL_WARN("range data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _range_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("range data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _range_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_RANGE_FINDER @@ -335,7 +343,8 @@ void EstimatorInterface::setOpticalFlowData(const flowSample &flow) _flow_buffer->push(optflow_sample_new); } else { - ECL_WARN("optical flow data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _flow_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("optical flow data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _flow_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_OPTICAL_FLOW @@ -374,7 +383,8 @@ void EstimatorInterface::setExtVisionData(const extVisionSample &evdata) _time_last_ext_vision_buffer_push = _time_latest_us; } else { - ECL_WARN("EV data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _ext_vision_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("EV data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _ext_vision_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_EXTERNAL_VISION @@ -411,7 +421,8 @@ void EstimatorInterface::setAuxVelData(const auxVelSample &auxvel_sample) _auxvel_buffer->push(auxvel_sample_new); } else { - ECL_WARN("aux velocity data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _auxvel_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_WARN("aux velocity data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _auxvel_buffer->get_newest().time_us, + _min_obs_interval_us); } } #endif // CONFIG_EKF2_AUXVEL @@ -446,7 +457,8 @@ void EstimatorInterface::setSystemFlagData(const systemFlagUpdate &system_flags) _system_flag_buffer->push(system_flags_new); } else { - ECL_DEBUG("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _system_flag_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_DEBUG("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, + _system_flag_buffer->get_newest().time_us, _min_obs_interval_us); } } diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index e390f41ea1b1..e7bef6bb0931 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -348,15 +348,15 @@ class EstimatorInterface OutputPredictor _output_predictor{}; #if defined(CONFIG_EKF2_AIRSPEED) - airspeedSample _airspeed_sample_delayed{}; + airspeedSample _airspeed_sample_delayed {}; #endif // CONFIG_EKF2_AIRSPEED #if defined(CONFIG_EKF2_EXTERNAL_VISION) - extVisionSample _ev_sample_prev{}; + extVisionSample _ev_sample_prev {}; #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_RANGE_FINDER) - RingBuffer *_range_buffer{nullptr}; + RingBuffer *_range_buffer {nullptr}; uint64_t _time_last_range_buffer_push{0}; sensor::SensorRangeFinder _range_sensor{}; @@ -364,7 +364,7 @@ class EstimatorInterface #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_OPTICAL_FLOW) - RingBuffer *_flow_buffer{nullptr}; + RingBuffer *_flow_buffer {nullptr}; flowSample _flow_sample_delayed{}; @@ -387,7 +387,7 @@ class EstimatorInterface float _gpos_origin_epv{0.0f}; // vertical position uncertainty of the global origin #if defined(CONFIG_EKF2_GNSS) - RingBuffer *_gps_buffer{nullptr}; + RingBuffer *_gps_buffer {nullptr}; uint64_t _time_last_gps_buffer_push{0}; gnssSample _gps_sample_delayed{}; @@ -406,7 +406,7 @@ class EstimatorInterface #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_DRAG_FUSION) - RingBuffer *_drag_buffer{nullptr}; + RingBuffer *_drag_buffer {nullptr}; dragSample _drag_down_sampled{}; // down sampled drag specific force data (filter prediction rate -> observation rate) #endif // CONFIG_EKF2_DRAG_FUSION @@ -424,25 +424,25 @@ class EstimatorInterface RingBuffer _imu_buffer{kBufferLengthDefault}; #if defined(CONFIG_EKF2_MAGNETOMETER) - RingBuffer *_mag_buffer{nullptr}; + RingBuffer *_mag_buffer {nullptr}; uint64_t _time_last_mag_buffer_push{0}; #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_AIRSPEED) - RingBuffer *_airspeed_buffer{nullptr}; + RingBuffer *_airspeed_buffer {nullptr}; #endif // CONFIG_EKF2_AIRSPEED #if defined(CONFIG_EKF2_EXTERNAL_VISION) - RingBuffer *_ext_vision_buffer{nullptr}; + RingBuffer *_ext_vision_buffer {nullptr}; uint64_t _time_last_ext_vision_buffer_push{0}; #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_AUXVEL) - RingBuffer *_auxvel_buffer{nullptr}; + RingBuffer *_auxvel_buffer {nullptr}; #endif // CONFIG_EKF2_AUXVEL - RingBuffer *_system_flag_buffer{nullptr}; + RingBuffer *_system_flag_buffer {nullptr}; #if defined(CONFIG_EKF2_BAROMETER) - RingBuffer *_baro_buffer{nullptr}; + RingBuffer *_baro_buffer {nullptr}; uint64_t _time_last_baro_buffer_push{0}; #endif // CONFIG_EKF2_BAROMETER @@ -457,7 +457,7 @@ class EstimatorInterface 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_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) diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index 51da34e343a5..a7e0b00f541d 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -294,12 +294,15 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const } checks[6] {}; #if defined(CONFIG_EKF2_BAROMETER) + if (_control_status.flags.baro_hgt) { checks[0] = {ReferenceType::PRESSURE, _aid_src_baro_hgt.innovation, _aid_src_baro_hgt.innovation_variance}; } + #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_GNSS) + if (_control_status.flags.gps_hgt) { checks[1] = {ReferenceType::GNSS, _aid_src_gnss_hgt.innovation, _aid_src_gnss_hgt.innovation_variance}; } @@ -307,16 +310,20 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const if (_control_status.flags.gps) { checks[2] = {ReferenceType::GNSS, _aid_src_gnss_vel.innovation[2], _aid_src_gnss_vel.innovation_variance[2]}; } + #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_RANGE_FINDER) + if (_control_status.flags.rng_hgt) { // Range is a distance to ground measurement, not a direct height observation and has an opposite sign checks[3] = {ReferenceType::GROUND, -_aid_src_rng_hgt.innovation, _aid_src_rng_hgt.innovation_variance}; } + #endif // CONFIG_EKF2_RANGE_FINDER #if defined(CONFIG_EKF2_EXTERNAL_VISION) + if (_control_status.flags.ev_hgt) { checks[4] = {ReferenceType::GROUND, _aid_src_ev_hgt.innovation, _aid_src_ev_hgt.innovation_variance}; } @@ -324,6 +331,7 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const if (_control_status.flags.ev_vel) { checks[5] = {ReferenceType::GROUND, _aid_src_ev_vel.innovation[2], _aid_src_ev_vel.innovation_variance[2]}; } + #endif // CONFIG_EKF2_EXTERNAL_VISION // Compute the check based on innovation ratio for all the sources diff --git a/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp index 826717d7b82e..d16e20a79095 100644 --- a/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp @@ -261,7 +261,8 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector } void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, - const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias) + const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state, const matrix::Vector3f &gyro_bias, + const matrix::Vector3f &accel_bias) { // calculate an average filter update time if (_time_last_correct_states_us != 0) { @@ -365,7 +366,8 @@ void OutputPredictor::applyCorrectionToVerticalOutputBuffer(float vert_vel_corre next_state.vert_vel += vert_vel_correction; // position is propagated forward using the corrected velocity and a trapezoidal integrator - next_state.vert_vel_integ = current_state.vert_vel_integ + (current_state.vert_vel + next_state.vert_vel) * 0.5f * next_state.dt; + next_state.vert_vel_integ = current_state.vert_vel_integ + (current_state.vert_vel + next_state.vert_vel) * 0.5f * + next_state.dt; // advance the index index = (index + 1) % size; diff --git a/src/modules/ekf2/EKF/output_predictor/output_predictor.h b/src/modules/ekf2/EKF/output_predictor/output_predictor.h index fee4fdff644c..07248f3dce72 100644 --- a/src/modules/ekf2/EKF/output_predictor/output_predictor.h +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.h @@ -67,7 +67,8 @@ class OutputPredictor const matrix::Vector3f &delta_velocity, const float delta_velocity_dt); void correctOutputStates(const uint64_t time_delayed_us, - const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias); + const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state, + const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias); void resetQuaternion(const matrix::Quatf &quat_change); diff --git a/src/modules/ekf2/EKF/position_fusion.cpp b/src/modules/ekf2/EKF/position_fusion.cpp index 3ae92a6b6dd5..6cc503de7323 100644 --- a/src/modules/ekf2/EKF/position_fusion.cpp +++ b/src/modules/ekf2/EKF/position_fusion.cpp @@ -40,9 +40,9 @@ void Ekf::updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, con float innovation_variance = getStateVariance()(2) + observation_variance; updateAidSourceStatus(aid_src, time_us, - observation, observation_variance, - innovation, innovation_variance, - innovation_gate); + observation, observation_variance, + innovation, innovation_variance, + innovation_gate); // z special case if there is bad vertical acceleration data, then don't reject measurement, // but limit innovation to prevent spikes that could destabilise the filter @@ -57,8 +57,10 @@ bool Ekf::fuseHorizontalPosition(estimator_aid_source2d_s &aid_src) { // x & y if (!aid_src.innovation_rejected - && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], State::pos.idx + 0) - && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], State::pos.idx + 1) + && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], + State::pos.idx + 0) + && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], + State::pos.idx + 1) ) { aid_src.fused = true; aid_src.time_last_fuse = _time_delayed_us; @@ -76,7 +78,8 @@ bool Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src) { // z if (!aid_src.innovation_rejected - && fuseDirectStateMeasurement(aid_src.innovation, aid_src.innovation_variance, aid_src.observation_variance, State::pos.idx + 2) + && fuseDirectStateMeasurement(aid_src.innovation, aid_src.innovation_variance, aid_src.observation_variance, + State::pos.idx + 2) ) { aid_src.fused = true; aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/velocity_fusion.cpp b/src/modules/ekf2/EKF/velocity_fusion.cpp index 07e590c2111a..349a40092fd4 100644 --- a/src/modules/ekf2/EKF/velocity_fusion.cpp +++ b/src/modules/ekf2/EKF/velocity_fusion.cpp @@ -37,8 +37,10 @@ bool Ekf::fuseHorizontalVelocity(estimator_aid_source2d_s &aid_src) { // vx, vy if (!aid_src.innovation_rejected - && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], State::vel.idx + 0) - && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], State::vel.idx + 1) + && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], + State::vel.idx + 0) + && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], + State::vel.idx + 1) ) { aid_src.fused = true; aid_src.time_last_fuse = _time_delayed_us; @@ -56,9 +58,12 @@ bool Ekf::fuseVelocity(estimator_aid_source3d_s &aid_src) { // vx, vy, vz if (!aid_src.innovation_rejected - && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], State::vel.idx + 0) - && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], State::vel.idx + 1) - && fuseDirectStateMeasurement(aid_src.innovation[2], aid_src.innovation_variance[2], aid_src.observation_variance[2], State::vel.idx + 2) + && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], + State::vel.idx + 0) + && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], + State::vel.idx + 1) + && fuseDirectStateMeasurement(aid_src.innovation[2], aid_src.innovation_variance[2], aid_src.observation_variance[2], + State::vel.idx + 2) ) { aid_src.fused = true; aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp b/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp index b9e0afd9c38e..7aad6620cee5 100644 --- a/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp +++ b/src/modules/ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp @@ -301,7 +301,8 @@ void EKFGSF_yaw::predictEKF(const uint8_t model_index, const Vector3f &delta_ang // Use fixed values for delta angle process noise variances const float d_ang_var = sq(_gyro_noise * delta_ang_dt); - _ekf_gsf[model_index].P = sym::YawEstPredictCovariance(_ekf_gsf[model_index].X, _ekf_gsf[model_index].P, Vector2f(dvx, dvy), d_vel_var, daz, d_ang_var); + _ekf_gsf[model_index].P = sym::YawEstPredictCovariance(_ekf_gsf[model_index].X, _ekf_gsf[model_index].P, Vector2f(dvx, + dvy), d_vel_var, daz, d_ang_var); // covariance matrix is symmetrical, so copy upper half to lower half _ekf_gsf[model_index].P(1, 0) = _ekf_gsf[model_index].P(0, 1); diff --git a/src/modules/ekf2/EKF/yaw_fusion.cpp b/src/modules/ekf2/EKF/yaw_fusion.cpp index 7714170a62e0..f87dcb8e41c2 100644 --- a/src/modules/ekf2/EKF/yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/yaw_fusion.cpp @@ -145,11 +145,13 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) _output_predictor.resetQuaternion(q_error); #if defined(CONFIG_EKF2_EXTERNAL_VISION) + // update EV attitude error filter if (_ev_q_error_initialized) { const Quatf ev_q_error_updated = (q_error * _ev_q_error_filt.getState()).normalized(); _ev_q_error_filt.reset(ev_q_error_updated); } + #endif // CONFIG_EKF2_EXTERNAL_VISION // record the state change From 75bb339d94325e0603a7730a343529ba227a72cf Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 5 Jul 2024 15:33:34 -0400 Subject: [PATCH 469/652] ekf2: remove warning events logging - some of these warning flags aren't even being used, and most of the rest we can figure out from other sources --- msg/EstimatorEventFlags.msg | 15 ---------- .../external_vision/ev_control.cpp | 1 - .../ekf2/EKF/aid_sources/fake_pos_control.cpp | 1 - .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 4 --- src/modules/ekf2/EKF/common.h | 29 ------------------- src/modules/ekf2/EKF/estimator_interface.h | 5 ---- src/modules/ekf2/EKF/height_control.cpp | 1 - src/modules/ekf2/EKF2.cpp | 29 ++----------------- src/modules/ekf2/EKF2.hpp | 1 - 9 files changed, 2 insertions(+), 84 deletions(-) diff --git a/msg/EstimatorEventFlags.msg b/msg/EstimatorEventFlags.msg index 1a47e676a5a4..7d5cf7ca343c 100644 --- a/msg/EstimatorEventFlags.msg +++ b/msg/EstimatorEventFlags.msg @@ -20,18 +20,3 @@ bool reset_hgt_to_baro # 13 - true when the vertical position s bool reset_hgt_to_gps # 14 - true when the vertical position state is reset to the gps measurement bool reset_hgt_to_rng # 15 - true when the vertical position state is reset to the rng measurement bool reset_hgt_to_ev # 16 - true when the vertical position state is reset to the ev measurement - -# warning events -uint32 warning_event_changes # number of warning event changes -bool gps_quality_poor # 0 - true when the gps is failing quality checks -bool gps_fusion_timout # 1 - true when the gps data has not been used to correct the state estimates for a significant time period -bool gps_data_stopped # 2 - true when the gps data has stopped for a significant time period -bool gps_data_stopped_using_alternate # 3 - true when the gps data has stopped for a significant time period but the filter is able to use other sources of data to maintain navigation -bool height_sensor_timeout # 4 - true when the height sensor has not been used to correct the state estimates for a significant time period -bool stopping_navigation # 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation -bool invalid_accel_bias_cov_reset # 6 - true when the filter has detected bad acceerometer bias state esitmstes and has reset the corresponding covariance matrix elements -bool bad_yaw_using_gps_course # 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course -bool stopping_mag_use # 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetometer data -bool vision_data_stopped # 9 - true when the vision system data has stopped for a significant time period -bool emergency_yaw_reset_mag_stopped # 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetometer data -bool emergency_yaw_reset_gps_yaw_stopped # 11 - true when the filter has detected bad GNSS yaw data, has reset the yaw to anothter source of data and has stopped further use of the GNSS yaw data diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp index 43f61a79d057..78cc2bd30a11 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp @@ -83,7 +83,6 @@ void Ekf::controlExternalVisionFusion() _ev_q_error_initialized = false; - _warning_events.flags.vision_data_stopped = true; ECL_WARN("vision data stopped"); } } diff --git a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp index 1ba1dd309b02..3704434d5fde 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp @@ -109,7 +109,6 @@ void Ekf::controlFakePosFusion() if (_control_status.flags.tilt_align) { // The fake position fusion is not started for initial alignement - _warning_events.flags.stopping_navigation = true; ECL_WARN("stopping navigation"); } } diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index 0c8c98ab26b6..d5bca4f46ac3 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -78,7 +78,6 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) if (_control_status.flags.gps && isTimedOut(_last_gps_pass_us, _params.reset_timeout_max)) { stopGpsFusion(); - _warning_events.flags.gps_quality_poor = true; ECL_WARN("GPS quality poor - stopping use"); } } @@ -92,7 +91,6 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) } else if (_control_status.flags.gps) { if (!isNewestSampleRecent(_time_last_gps_buffer_push, _params.reset_timeout_max)) { stopGpsFusion(); - _warning_events.flags.gps_data_stopped = true; ECL_WARN("GPS data stopped"); } } @@ -276,14 +274,12 @@ bool Ekf::tryYawEmergencyReset() // stop using the magnetometer in the main EKF otherwise its fusion could drag the yaw around // and cause another navigation failure _control_status.flags.mag_fault = true; - _warning_events.flags.emergency_yaw_reset_mag_stopped = true; } #if defined(CONFIG_EKF2_GNSS_YAW) if (_control_status.flags.gps_yaw) { _control_status.flags.gps_yaw_fault = true; - _warning_events.flags.emergency_yaw_reset_gps_yaw_stopped = true; } #endif // CONFIG_EKF2_GNSS_YAW diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 7a008783fe1b..05610bca5858 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -666,34 +666,5 @@ bool reset_pos_to_ext_obs : uint32_t value; }; -// define structure used to communicate information events -union warning_event_status_u { - struct { - bool gps_quality_poor : 1; ///< 0 - true when the gps is failing quality checks -bool gps_fusion_timout : - 1; ///< 1 - true when the gps data has not been used to correct the state estimates for a significant time period - bool gps_data_stopped : 1; ///< 2 - true when the gps data has stopped for a significant time period -bool gps_data_stopped_using_alternate : - 1; ///< 3 - true when the gps data has stopped for a significant time period but the filter is able to use other sources of data to maintain navigation -bool height_sensor_timeout : - 1; ///< 4 - true when the height sensor has not been used to correct the state estimates for a significant time period -bool stopping_navigation : - 1; ///< 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation -bool invalid_accel_bias_cov_reset : - 1; ///< 6 - true when the filter has detected bad acceerometer bias state estimates and has reset the corresponding covariance matrix elements -bool bad_yaw_using_gps_course : - 1; ///< 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course -bool stopping_mag_use : - 1; ///< 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetometer data -bool vision_data_stopped : - 1; ///< 9 - true when the vision system data has stopped for a significant time period -bool emergency_yaw_reset_mag_stopped : - 1; ///< 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetometer data -bool emergency_yaw_reset_gps_yaw_stopped: - 1; ///< 11 - true when the filter has detected bad GNSS yaw data, has reset the yaw to anothter source of data and has stopped further use of the GNSS yaw data - } flags; - uint32_t value; -}; - } #endif // !EKF_COMMON_H diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index e7bef6bb0931..4477f17b5164 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -293,10 +293,6 @@ class EstimatorInterface const innovation_fault_status_u &innov_check_fail_status() const { return _innov_check_fail_status; } const decltype(innovation_fault_status_u::flags) &innov_check_fail_status_flags() const { return _innov_check_fail_status.flags; } - const warning_event_status_u &warning_event_status() const { return _warning_events; } - const decltype(warning_event_status_u::flags) &warning_event_flags() const { return _warning_events.flags; } - void clear_warning_events() { _warning_events.value = 0; } - const information_event_status_u &information_event_status() const { return _information_events; } const decltype(information_event_status_u::flags) &information_event_flags() const { return _information_events.flags; } void clear_information_events() { _information_events.value = 0; } @@ -473,7 +469,6 @@ class EstimatorInterface // these are used to record single frame events for external monitoring and should NOT be used for // state logic becasue they will be cleared externally after being read. - warning_event_status_u _warning_events{}; information_event_status_u _information_events{}; unsigned _min_obs_interval_us{0}; // minimum time interval between observations that will guarantee data is not lost (usec) diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index a7e0b00f541d..5ad5d7db34dd 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -216,7 +216,6 @@ void Ekf::checkVerticalAccelerationBias(const imuSample &imu_delayed) _time_acc_bias_check = imu_delayed.time_us; _fault_status.flags.bad_acc_bias = false; - _warning_events.flags.invalid_accel_bias_cov_reset = true; ECL_WARN("invalid accel bias - covariance reset"); } } diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 4fa40399b369..cee124db0c25 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1107,16 +1107,7 @@ void EKF2::PublishEventFlags(const hrt_abstime ×tamp) _filter_information_event_changes++; } - // warning events - uint32_t warning_events = _ekf.warning_event_status().value; - bool warning_event_updated = false; - - if (warning_events != 0) { - warning_event_updated = true; - _filter_warning_event_changes++; - } - - if (information_event_updated || warning_event_updated) { + if (information_event_updated) { estimator_event_flags_s event_flags{}; event_flags.timestamp_sample = _ekf.time_delayed_us(); @@ -1139,27 +1130,12 @@ void EKF2::PublishEventFlags(const hrt_abstime ×tamp) event_flags.reset_hgt_to_rng = _ekf.information_event_flags().reset_hgt_to_rng; event_flags.reset_hgt_to_ev = _ekf.information_event_flags().reset_hgt_to_ev; - event_flags.warning_event_changes = _filter_warning_event_changes; - event_flags.gps_quality_poor = _ekf.warning_event_flags().gps_quality_poor; - event_flags.gps_fusion_timout = _ekf.warning_event_flags().gps_fusion_timout; - event_flags.gps_data_stopped = _ekf.warning_event_flags().gps_data_stopped; - event_flags.gps_data_stopped_using_alternate = _ekf.warning_event_flags().gps_data_stopped_using_alternate; - event_flags.height_sensor_timeout = _ekf.warning_event_flags().height_sensor_timeout; - event_flags.stopping_navigation = _ekf.warning_event_flags().stopping_mag_use; - event_flags.invalid_accel_bias_cov_reset = _ekf.warning_event_flags().invalid_accel_bias_cov_reset; - event_flags.bad_yaw_using_gps_course = _ekf.warning_event_flags().bad_yaw_using_gps_course; - event_flags.stopping_mag_use = _ekf.warning_event_flags().stopping_mag_use; - event_flags.vision_data_stopped = _ekf.warning_event_flags().vision_data_stopped; - event_flags.emergency_yaw_reset_mag_stopped = _ekf.warning_event_flags().emergency_yaw_reset_mag_stopped; - event_flags.emergency_yaw_reset_gps_yaw_stopped = _ekf.warning_event_flags().emergency_yaw_reset_gps_yaw_stopped; - event_flags.timestamp = _replay_mode ? timestamp : hrt_absolute_time(); _estimator_event_flags_pub.update(event_flags); _last_event_flags_publish = event_flags.timestamp; _ekf.clear_information_events(); - _ekf.clear_warning_events(); } else if ((_last_event_flags_publish != 0) && (timestamp >= _last_event_flags_publish + 1_s)) { // continue publishing periodically @@ -2676,8 +2652,7 @@ void EKF2::UpdateAccelCalibration(const hrt_abstime ×tamp) && (_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 - && !_ekf.warning_event_flags().invalid_accel_bias_cov_reset; + && !_ekf.fault_status_flags().bad_acc_vertical; const bool learning_valid = bias_valid && !_ekf.accel_bias_inhibited(); diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 3bc2b99f953d..8b832d60ccd8 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -418,7 +418,6 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem uint32_t _filter_control_status_changes{0}; uint32_t _filter_fault_status_changes{0}; uint32_t _innov_check_fail_status_changes{0}; - uint32_t _filter_warning_event_changes{0}; uint32_t _filter_information_event_changes{0}; uORB::PublicationMulti _ekf2_timestamps_pub{ORB_ID(ekf2_timestamps)}; From 2c3401dc8367a860cbbabc5e77898ff206f554aa Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 10 Jul 2024 18:43:31 +0200 Subject: [PATCH 470/652] uORB: SubscriptionInterval fix timestamp wrapping when initializing less than the interval time after boot (#23384) * SubscriptionInterval: ensure _last_update is never before timer start --- platforms/common/uORB/SubscriptionInterval.hpp | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/platforms/common/uORB/SubscriptionInterval.hpp b/platforms/common/uORB/SubscriptionInterval.hpp index 31d1b0a7af12..07572f72f218 100644 --- a/platforms/common/uORB/SubscriptionInterval.hpp +++ b/platforms/common/uORB/SubscriptionInterval.hpp @@ -125,8 +125,16 @@ class SubscriptionInterval { if (_subscription.copy(dst)) { const hrt_abstime now = hrt_absolute_time(); - // shift last update time forward, but don't let it get further behind than the interval - _last_update = math::constrain(_last_update + _interval_us, now - _interval_us, now); + + // make sure we don't set a timestamp before the timer started counting (now - _interval_us would wrap because it's unsigned) + if (now > _interval_us) { + // shift last update time forward, but don't let it get further behind than the interval + _last_update = math::constrain(_last_update + _interval_us, now - _interval_us, now); + + } else { + _last_update = now; + } + return true; } @@ -160,7 +168,7 @@ class SubscriptionInterval protected: Subscription _subscription; - uint64_t _last_update{0}; // last update in microseconds + uint64_t _last_update{0}; // last subscription update in microseconds uint32_t _interval_us{0}; // maximum update interval in microseconds }; From c391509c23de4ba701fb135304865322279beaef Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Wed, 10 Jul 2024 14:15:45 +0200 Subject: [PATCH 471/652] ackermann: add SITL airframe --- .../airframes/4012_gz_rover_ackermann | 47 +++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + 2 files changed, 48 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann b/ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann new file mode 100644 index 000000000000..91c44baff3e9 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann @@ -0,0 +1,47 @@ +#!/bin/sh +# @name Rover Ackermann +# @type Rover +# @class Rover + +. ${R}etc/init.d/rc.rover_ackermann_defaults + +PX4_SIMULATOR=${PX4_SIMULATOR:=gz} +PX4_GZ_WORLD=${PX4_GZ_WORLD:=rover} +PX4_SIM_MODEL=${PX4_SIM_MODEL:=rover_ackermann} + +param set-default SIM_GZ_EN 1 # Gazebo bridge + +# Rover parameters +param set-default NAV_ACC_RAD 0.5 +param set-default RA_ACC_RAD_GAIN 2 +param set-default RA_ACC_RAD_MAX 3 +param set-default RA_LOOKAHD_GAIN 1 +param set-default RA_LOOKAHD_MAX 10 +param set-default RA_LOOKAHD_MIN 1 +param set-default RA_MAX_ACCEL 1.5 +param set-default RA_MAX_JERK 15 +param set-default RA_MAX_SPEED 3 +param set-default RA_MAX_STR_ANG 0.5236 +param set-default RA_MAX_STR_RATE 360 +param set-default RA_MISS_VEL_DEF 3 +param set-default RA_MISS_VEL_GAIN 5 +param set-default RA_MISS_VEL_MIN 1 +param set-default RA_SPEED_I 0.01 +param set-default RA_SPEED_P 2 +param set-default RA_WHEEL_BASE 0.321 + +# Simulated sensors +param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 0 +param set-default SENS_EN_MAGSIM 1 +param set-default SENS_EN_ARSPDSIM 0 + +# Wheels +param set-default SIM_GZ_WH_FUNC1 101 +param set-default SIM_GZ_WH_MIN1 0 +param set-default SIM_GZ_WH_MAX1 200 +param set-default SIM_GZ_WH_DIS1 100 + +# Steering +param set-default SIM_GZ_SV_FUNC1 201 +param set-default SIM_GZ_SV_REV 1 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 9277ad303947..33d6d857e8c2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -83,6 +83,7 @@ px4_add_romfs_files( 4009_gz_r1_rover 4010_gz_x500_mono_cam 4011_gz_lawnmower + 4012_gz_rover_ackermann 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post From e0ea91fc2764a2f67e22412501cdf46602eba39c Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Thu, 11 Jul 2024 00:39:09 +0000 Subject: [PATCH 472/652] Update submodule gz to latest Thu Jul 11 00:39:09 UTC 2024 - gz in PX4/Firmware (2c3401dc8367a860cbbabc5e77898ff206f554aa): https://github.com/PX4/PX4-gazebo-models/commit/881558c8c274d0d9f21970de24333122e050b561 - gz current upstream: https://github.com/PX4/PX4-gazebo-models/commit/312cd002ff9602644efef58eef93e447c10dcbe8 - Changes: https://github.com/PX4/PX4-gazebo-models/compare/881558c8c274d0d9f21970de24333122e050b561...312cd002ff9602644efef58eef93e447c10dcbe8 312cd00 2024-07-08 chfriedrich98 - Add rover ackermann model (#46) --- Tools/simulation/gz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/simulation/gz b/Tools/simulation/gz index 881558c8c274..312cd002ff96 160000 --- a/Tools/simulation/gz +++ b/Tools/simulation/gz @@ -1 +1 @@ -Subproject commit 881558c8c274d0d9f21970de24333122e050b561 +Subproject commit 312cd002ff9602644efef58eef93e447c10dcbe8 From 57e303b11b490e378710ec838dd0e2683fc21314 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Tue, 9 Jul 2024 14:38:06 +0200 Subject: [PATCH 473/652] bugfix for failing actions --- .github/workflows/mavros_mission_tests.yml | 2 ++ .github/workflows/mavros_offboard_tests.yml | 2 ++ 2 files changed, 4 insertions(+) diff --git a/.github/workflows/mavros_mission_tests.yml b/.github/workflows/mavros_mission_tests.yml index 7e95b1fff082..a90d51804ef5 100644 --- a/.github/workflows/mavros_mission_tests.yml +++ b/.github/workflows/mavros_mission_tests.yml @@ -11,6 +11,8 @@ on: jobs: build: runs-on: ubuntu-latest + env: + ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true strategy: fail-fast: false matrix: diff --git a/.github/workflows/mavros_offboard_tests.yml b/.github/workflows/mavros_offboard_tests.yml index 812f63fec406..020caaa2d048 100644 --- a/.github/workflows/mavros_offboard_tests.yml +++ b/.github/workflows/mavros_offboard_tests.yml @@ -11,6 +11,8 @@ on: jobs: build: runs-on: ubuntu-latest + env: + ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true strategy: fail-fast: false matrix: From 20137bea40722e202a0b81ffc893567711e6ebcc Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 9 Jul 2024 11:03:37 +1200 Subject: [PATCH 474/652] boards: add console build for Cube Orange(+) This adds a build variant which enables the serial console, and therefore disables the ADSB receiver. --- boards/cubepilot/cubeorange/console.px4board | 1 + .../cubeorange/nuttx-config/console/defconfig | 257 +++++++++++++++++ .../cubepilot/cubeorangeplus/console.px4board | 1 + .../nuttx-config/console/defconfig | 259 ++++++++++++++++++ 4 files changed, 518 insertions(+) create mode 100644 boards/cubepilot/cubeorange/console.px4board create mode 100644 boards/cubepilot/cubeorange/nuttx-config/console/defconfig create mode 100644 boards/cubepilot/cubeorangeplus/console.px4board create mode 100644 boards/cubepilot/cubeorangeplus/nuttx-config/console/defconfig diff --git a/boards/cubepilot/cubeorange/console.px4board b/boards/cubepilot/cubeorange/console.px4board new file mode 100644 index 000000000000..89afc484a172 --- /dev/null +++ b/boards/cubepilot/cubeorange/console.px4board @@ -0,0 +1 @@ +# Same as default, only defconfig is different diff --git a/boards/cubepilot/cubeorange/nuttx-config/console/defconfig b/boards/cubepilot/cubeorange/nuttx-config/console/defconfig new file mode 100644 index 000000000000..e8e0422f4386 --- /dev/null +++ b/boards/cubepilot/cubeorange/nuttx-config/console/defconfig @@ -0,0 +1,257 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cubepilot/cubeorange/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743ZI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=79954 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x1016 +CONFIG_CDCACM_PRODUCTSTR="CubeOrange" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x2DAE +CONFIG_CDCACM_VENDORSTR="CubePilot" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=3000 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/cubepilot/cubeorangeplus/console.px4board b/boards/cubepilot/cubeorangeplus/console.px4board new file mode 100644 index 000000000000..89afc484a172 --- /dev/null +++ b/boards/cubepilot/cubeorangeplus/console.px4board @@ -0,0 +1 @@ +# Same as default, only defconfig is different diff --git a/boards/cubepilot/cubeorangeplus/nuttx-config/console/defconfig b/boards/cubepilot/cubeorangeplus/nuttx-config/console/defconfig new file mode 100644 index 000000000000..bb6a7cee41b7 --- /dev/null +++ b/boards/cubepilot/cubeorangeplus/nuttx-config/console/defconfig @@ -0,0 +1,259 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cubepilot/cubeorangeplus/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H747XI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=79954 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x1058 +CONFIG_CDCACM_PRODUCTSTR="CubeOrange+" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x2DAE +CONFIG_CDCACM_VENDORSTR="CubePilot" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_PWR_DIRECT_SMPS_SUPPLY=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=3000 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y From f93dc617703d0224540403d46c3e4cda7d052a83 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 27 Jun 2024 12:23:00 -0400 Subject: [PATCH 475/652] ekf2: use bias corrected angular velocity - avoid unnecessarily storing _ang_rate_delayed_raw --- .../barometer/baro_height_control.cpp | 9 +++--- .../external_vision/ev_control.cpp | 11 +++---- .../external_vision/ev_height_control.cpp | 8 +++-- .../external_vision/ev_pos_control.cpp | 5 ++-- .../external_vision/ev_vel_control.cpp | 8 +++-- .../external_vision/ev_yaw_control.cpp | 5 ++-- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 7 +++-- src/modules/ekf2/EKF/control.cpp | 2 +- src/modules/ekf2/EKF/ekf.cpp | 9 ------ src/modules/ekf2/EKF/ekf.h | 30 ++++++++++--------- src/modules/ekf2/EKF/height_control.cpp | 2 +- 11 files changed, 49 insertions(+), 47 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index 80c51e097954..9153856009fd 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -38,7 +38,7 @@ #include "ekf.h" -void Ekf::controlBaroHeightFusion() +void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) { static constexpr const char *HGT_SRC_NAME = "baro"; @@ -52,7 +52,7 @@ void Ekf::controlBaroHeightFusion() if (_baro_buffer && _baro_buffer->pop_first_older_than(_time_delayed_us, &baro_sample)) { #if defined(CONFIG_EKF2_BARO_COMPENSATION) - const float measurement = compensateBaroForDynamicPressure(baro_sample.hgt); + const float measurement = compensateBaroForDynamicPressure(imu_sample, baro_sample.hgt); #else const float measurement = baro_sample.hgt; #endif @@ -195,7 +195,7 @@ void Ekf::stopBaroHgtFusion() } #if defined(CONFIG_EKF2_BARO_COMPENSATION) -float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const +float Ekf::compensateBaroForDynamicPressure(const imuSample &imu_sample, const float baro_alt_uncompensated) const { if (_control_status.flags.wind && local_position_is_valid()) { // calculate static pressure error = Pmeas - Ptruth @@ -203,7 +203,8 @@ float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) // negative X and Y directions. Used to correct baro data for positional errors // Calculate airspeed in body frame - const Vector3f vel_imu_rel_body_ned = _R_to_earth * (_ang_rate_delayed_raw % _params.imu_pos_body); + const Vector3f angular_velocity = (imu_sample.delta_ang / imu_sample.delta_ang_dt) - _state.gyro_bias; + const Vector3f vel_imu_rel_body_ned = _R_to_earth * (angular_velocity % _params.imu_pos_body); const Vector3f velocity_earth = _state.vel - vel_imu_rel_body_ned; const Vector3f wind_velocity_earth(_state.wind_vel(0), _state.wind_vel(1), 0.0f); diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp index 78cc2bd30a11..cac1db3f3d72 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp @@ -38,7 +38,7 @@ #include "ekf.h" -void Ekf::controlExternalVisionFusion() +void Ekf::controlExternalVisionFusion(const imuSample &imu_sample) { _ev_pos_b_est.predict(_dt_ekf_avg); _ev_hgt_b_est.predict(_dt_ekf_avg); @@ -62,10 +62,11 @@ void Ekf::controlExternalVisionFusion() && isNewestSampleRecent(_time_last_ext_vision_buffer_push, EV_MAX_INTERVAL); updateEvAttitudeErrorFilter(ev_sample, ev_reset); - controlEvYawFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_yaw); - controlEvVelFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_vel); - controlEvPosFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_pos); - controlEvHeightFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_hgt); + controlEvYawFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_yaw); + controlEvVelFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_vel); + controlEvPosFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_pos); + controlEvHeightFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, + _aid_src_ev_hgt); if (quality_sufficient) { _ev_sample_prev = ev_sample; diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp index a69906eef489..0684536ae587 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp @@ -38,8 +38,9 @@ #include "ekf.h" -void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src) +void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source1d_s &aid_src) { static constexpr const char *AID_SRC_NAME = "EV height"; @@ -152,7 +153,8 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com if (ev_sample.vel.isAllFinite() && (_params.ev_ctrl & static_cast(EvCtrl::VEL))) { // correct velocity for offset relative to IMU - const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body; + const Vector3f angular_velocity = (imu_sample.delta_ang / imu_sample.delta_ang_dt) - _state.gyro_bias; + const Vector3f vel_offset_body = angular_velocity % pos_offset_body; const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body; switch (ev_sample.vel_frame) { diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp index 53ee21e09b8c..590a289da394 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp @@ -41,8 +41,9 @@ static constexpr const char *EV_AID_SRC_NAME = "EV position"; -void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source2d_s &aid_src) +void Ekf::controlEvPosFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source2d_s &aid_src) { const bool yaw_alignment_changed = (!_control_status_prev.flags.ev_yaw && _control_status.flags.ev_yaw) || (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align); diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp index 62781e5081ac..a5ba562cad23 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp @@ -41,8 +41,9 @@ #include #include -void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src) +void Ekf::controlEvVelFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source3d_s &aid_src) { static constexpr const char *AID_SRC_NAME = "EV velocity"; @@ -55,8 +56,9 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common && ev_sample.vel.isAllFinite(); // correct velocity for offset relative to IMU + const Vector3f angular_velocity = imu_sample.delta_ang / imu_sample.delta_ang_dt - _state.gyro_bias; const Vector3f pos_offset_body = _params.ev_pos_body - _params.imu_pos_body; - const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body; + const Vector3f vel_offset_body = angular_velocity % pos_offset_body; const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body; // rotate measurement into correct earth frame if required diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp index a285d3e4556a..ad15c4f6bb33 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_yaw_control.cpp @@ -38,8 +38,9 @@ #include "ekf.h" -void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src) +void Ekf::controlEvYawFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source1d_s &aid_src) { static constexpr const char *AID_SRC_NAME = "EV yaw"; diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index d5bca4f46ac3..83f7ef624d64 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -86,7 +86,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) updateGnssPos(gnss_sample, _aid_src_gnss_pos); } - updateGnssVel(gnss_sample, _aid_src_gnss_vel); + updateGnssVel(imu_delayed, gnss_sample, _aid_src_gnss_vel); } else if (_control_status.flags.gps) { if (!isNewestSampleRecent(_time_last_gps_buffer_push, _params.reset_timeout_max)) { @@ -173,12 +173,13 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) } } -void Ekf::updateGnssVel(const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src) +void Ekf::updateGnssVel(const imuSample &imu_sample, const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src) { // correct velocity for offset relative to IMU const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body; - const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body; + const Vector3f angular_velocity = imu_sample.delta_ang / imu_sample.delta_ang_dt - _state.gyro_bias; + const Vector3f vel_offset_body = angular_velocity % pos_offset_body; const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body; const Vector3f velocity = gnss_sample.vel - vel_offset_earth; diff --git a/src/modules/ekf2/EKF/control.cpp b/src/modules/ekf2/EKF/control.cpp index 5215570d14c7..37d13a32e36b 100644 --- a/src/modules/ekf2/EKF/control.cpp +++ b/src/modules/ekf2/EKF/control.cpp @@ -137,7 +137,7 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_EXTERNAL_VISION) // Additional data odometry data from an external estimator can be fused. - controlExternalVisionFusion(); + controlExternalVisionFusion(imu_delayed); #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_AUXVEL) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 4479dc37b8ea..1b439c887956 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -89,8 +89,6 @@ void Ekf::reset() _control_status.flags.in_air = true; _control_status_prev.flags.in_air = true; - _ang_rate_delayed_raw.zero(); - _fault_status.value = 0; _innov_check_fail_status.value = 0; @@ -264,13 +262,6 @@ void Ekf::predictState(const imuSample &imu_delayed) _state.vel = matrix::constrain(_state.vel, -1000.f, 1000.f); _state.pos = matrix::constrain(_state.pos, -1.e6f, 1.e6f); - // some calculations elsewhere in code require a raw angular rate vector so calculate here to avoid duplication - // protect against possible small timesteps resulting from timing slip on previous frame that can drive spikes into the rate - // due to insufficient averaging - if (imu_delayed.delta_ang_dt > 0.25f * _dt_ekf_avg) { - _ang_rate_delayed_raw = imu_delayed.delta_ang / imu_delayed.delta_ang_dt; - } - // calculate a filtered horizontal acceleration with a 1 sec time constant // this are used for manoeuvre detection elsewhere diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 1b20c433e2a6..60c869c575de 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -566,8 +566,6 @@ class Ekf final : public EstimatorInterface StateResets _state_reset_status{}; ///< reset event monitoring structure containing velocity, position, height and yaw reset information StateResetCounts _state_reset_count_prev{}; - Vector3f _ang_rate_delayed_raw{}; ///< uncorrected angular rate vector at fusion time horizon (rad/sec) - StateSample _state{}; ///< state struct of the ekf running at the delayed time horizon bool _filter_initialised{false}; ///< true when the EKF sttes and covariances been initialised @@ -936,16 +934,20 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_EXTERNAL_VISION) // control fusion of external vision observations - void controlExternalVisionFusion(); + void controlExternalVisionFusion(const imuSample &imu_sample); void updateEvAttitudeErrorFilter(extVisionSample &ev_sample, bool ev_reset); - void controlEvHeightFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src); - void controlEvPosFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source2d_s &aid_src); - void controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src); - void controlEvYawFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, - const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src); + void controlEvHeightFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source1d_s &aid_src); + void controlEvPosFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source2d_s &aid_src); + void controlEvVelFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source3d_s &aid_src); + void controlEvYawFusion(const imuSample &imu_sample, const extVisionSample &ev_sample, + const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, + estimator_aid_source1d_s &aid_src); void resetVelocityToEV(const Vector3f &measurement, const Vector3f &measurement_var, const VelocityFrame &vel_frame); Vector3f rotateVarianceToEkf(const Vector3f &measurement_var); @@ -968,7 +970,7 @@ class Ekf final : public EstimatorInterface // control fusion of GPS observations void controlGpsFusion(const imuSample &imu_delayed); void stopGpsFusion(); - void updateGnssVel(const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src); + void updateGnssVel(const imuSample &imu_sample, const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src); void updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s &aid_src); void controlGnssYawEstimator(estimator_aid_source3d_s &aid_src_vel); bool tryYawEmergencyReset(); @@ -1063,13 +1065,13 @@ class Ekf final : public EstimatorInterface void checkHeightSensorRefFallback(); #if defined(CONFIG_EKF2_BAROMETER) - void controlBaroHeightFusion(); + void controlBaroHeightFusion(const imuSample &imu_sample); void stopBaroHgtFusion(); void updateGroundEffect(); # if defined(CONFIG_EKF2_BARO_COMPENSATION) - float compensateBaroForDynamicPressure(float baro_alt_uncompensated) const; + float compensateBaroForDynamicPressure(const imuSample &imu_sample, float baro_alt_uncompensated) const; # endif // CONFIG_EKF2_BARO_COMPENSATION #endif // CONFIG_EKF2_BAROMETER diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index 5ad5d7db34dd..56a667840a75 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -45,7 +45,7 @@ void Ekf::controlHeightFusion(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_BAROMETER) updateGroundEffect(); - controlBaroHeightFusion(); + controlBaroHeightFusion(imu_delayed); #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_GNSS) From ac77049c47b22087bc25d5dcc9efa3a9d1f4ae80 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 27 Jun 2024 12:33:17 -0400 Subject: [PATCH 476/652] ekf2: directly use IMU sample to find corresponding aid source sample - I think this helps make it clear we're using a sensor sample corresponding with a particular IMU sample --- .../ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp | 4 ++-- .../aid_sources/barometer/baro_height_control.cpp | 6 +++--- .../EKF/aid_sources/external_vision/ev_control.cpp | 2 +- .../EKF/aid_sources/magnetometer/mag_control.cpp | 10 +++++----- .../range_finder/range_height_control.cpp | 12 ++++++------ src/modules/ekf2/EKF/control.cpp | 4 ++-- src/modules/ekf2/EKF/ekf.h | 6 +++--- src/modules/ekf2/EKF/height_control.cpp | 2 +- 8 files changed, 23 insertions(+), 23 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp index 14d333f3642d..6531c5c65a07 100644 --- a/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/auxvel/auxvel_fusion.cpp @@ -33,12 +33,12 @@ #include "ekf.h" -void Ekf::controlAuxVelFusion() +void Ekf::controlAuxVelFusion(const imuSample &imu_sample) { if (_auxvel_buffer) { auxVelSample sample; - if (_auxvel_buffer->pop_first_older_than(_time_delayed_us, &sample)) { + if (_auxvel_buffer->pop_first_older_than(imu_sample.time_us, &sample)) { updateAidSourceStatus(_aid_src_aux_vel, sample.time_us, // sample timestamp diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index 9153856009fd..c6c6f220de70 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -49,7 +49,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) baroSample baro_sample; - if (_baro_buffer && _baro_buffer->pop_first_older_than(_time_delayed_us, &baro_sample)) { + if (_baro_buffer && _baro_buffer->pop_first_older_than(imu_sample.time_us, &baro_sample)) { #if defined(CONFIG_EKF2_BARO_COMPENSATION) const float measurement = compensateBaroForDynamicPressure(imu_sample, baro_sample.hgt); @@ -137,7 +137,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) // reset vertical velocity resetVerticalVelocityToZero(); - aid_src.time_last_fuse = _time_delayed_us; + aid_src.time_last_fuse = imu_sample.time_us; } else if (is_fusion_failing) { // Some other height source is still working @@ -166,7 +166,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) bias_est.setBias(_state.pos(2) + _baro_lpf.getState()); } - aid_src.time_last_fuse = _time_delayed_us; + aid_src.time_last_fuse = imu_sample.time_us; bias_est.setFusionActive(); _control_status.flags.baro_hgt = true; } diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp index cac1db3f3d72..68022677ba64 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_control.cpp @@ -46,7 +46,7 @@ void Ekf::controlExternalVisionFusion(const imuSample &imu_sample) // Check for new external vision data extVisionSample ev_sample; - if (_ext_vision_buffer && _ext_vision_buffer->pop_first_older_than(_time_delayed_us, &ev_sample)) { + if (_ext_vision_buffer && _ext_vision_buffer->pop_first_older_than(imu_sample.time_us, &ev_sample)) { bool ev_reset = (ev_sample.reset_counter != _ev_sample_prev.reset_counter); 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 979807f116a5..2dab0da57eaf 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -41,7 +41,7 @@ #include -void Ekf::controlMagFusion() +void Ekf::controlMagFusion(const imuSample &imu_sample) { static constexpr const char *AID_SRC_NAME = "mag"; estimator_aid_source3d_s &aid_src = _aid_src_mag; @@ -59,7 +59,7 @@ void Ekf::controlMagFusion() magSample mag_sample; - if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) { + if (_mag_buffer && _mag_buffer->pop_first_older_than(imu_sample.time_us, &mag_sample)) { if (mag_sample.reset || (_mag_counter == 0)) { // sensor or calibration has changed, reset low pass filter @@ -185,7 +185,7 @@ void Ekf::controlMagFusion() if (mag_sample.reset || 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 = _time_delayed_us; + aid_src.time_last_fuse = imu_sample.time_us; } else { // The normal sequence is to fuse the magnetometer data first before fusing @@ -213,7 +213,7 @@ void Ekf::controlMagFusion() if (no_ne_aiding_or_pre_takeoff) { ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); - aid_src.time_last_fuse = _time_delayed_us; + aid_src.time_last_fuse = imu_sample.time_us; } else { ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); @@ -242,7 +242,7 @@ void Ekf::controlMagFusion() bool reset_heading = !_control_status.flags.yaw_align; resetMagStates(_mag_lpf.getState(), reset_heading); - aid_src.time_last_fuse = _time_delayed_us; + aid_src.time_last_fuse = imu_sample.time_us; if (reset_heading) { _control_status.flags.yaw_align = true; 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 1b7db97e3020..94a44883eecf 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 @@ -39,7 +39,7 @@ #include "ekf.h" #include "ekf_derivation/generated/compute_hagl_innov_var.h" -void Ekf::controlRangeHaglFusion() +void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) { static constexpr const char *HGT_SRC_NAME = "RNG"; @@ -47,7 +47,7 @@ void Ekf::controlRangeHaglFusion() if (_range_buffer) { // Get range data from buffer and check validity - rng_data_ready = _range_buffer->pop_first_older_than(_time_delayed_us, _range_sensor.getSampleAddress()); + rng_data_ready = _range_buffer->pop_first_older_than(imu_sample.time_us, _range_sensor.getSampleAddress()); _range_sensor.setDataReadiness(rng_data_ready); // update range sensor angle parameters in case they have changed @@ -55,7 +55,7 @@ void Ekf::controlRangeHaglFusion() _range_sensor.setCosMaxTilt(_params.range_cos_max_tilt); _range_sensor.setQualityHysteresis(_params.range_valid_quality_s); - _range_sensor.runChecks(_time_delayed_us, _R_to_earth); + _range_sensor.runChecks(imu_sample.time_us, _R_to_earth); if (_range_sensor.isDataHealthy()) { // correct the range data for position offset relative to the IMU @@ -72,7 +72,7 @@ void Ekf::controlRangeHaglFusion() _rng_consistency_check.setGate(_params.range_kin_consistency_gate); _rng_consistency_check.update(_range_sensor.getDistBottom(), math::max(var, 0.001f), _state.vel(2), - P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, _time_delayed_us); + P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, imu_sample.time_us); } } else { @@ -151,7 +151,7 @@ void Ekf::controlRangeHaglFusion() _control_status.flags.rng_hgt = true; stopRngTerrFusion(); - aid_src.time_last_fuse = _time_delayed_us; + aid_src.time_last_fuse = imu_sample.time_us; } } else { @@ -183,7 +183,7 @@ void Ekf::controlRangeHaglFusion() // reset vertical velocity resetVerticalVelocityToZero(); - aid_src.time_last_fuse = _time_delayed_us; + aid_src.time_last_fuse = imu_sample.time_us; } else if (is_fusion_failing) { // Some other height source is still working diff --git a/src/modules/ekf2/EKF/control.cpp b/src/modules/ekf2/EKF/control.cpp index 37d13a32e36b..b8aca027e769 100644 --- a/src/modules/ekf2/EKF/control.cpp +++ b/src/modules/ekf2/EKF/control.cpp @@ -102,7 +102,7 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_MAGNETOMETER) // control use of observations for aiding - controlMagFusion(); + controlMagFusion(imu_delayed); #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_OPTICAL_FLOW) @@ -142,7 +142,7 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_AUXVEL) // Additional horizontal velocity data from an auxiliary sensor can be fused - controlAuxVelFusion(); + controlAuxVelFusion(imu_delayed); #endif // CONFIG_EKF2_AUXVEL // #if defined(CONFIG_EKF2_TERRAIN) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 60c869c575de..85ea4a7625bc 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -841,7 +841,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_RANGE_FINDER) // range height - void controlRangeHaglFusion(); + void controlRangeHaglFusion(const imuSample &imu_delayed); bool isConditionalRangeAidSuitable(); void stopRngHgtFusion(); void stopRngTerrFusion(); @@ -1019,7 +1019,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // control fusion of magnetometer observations - void controlMagFusion(); + void controlMagFusion(const imuSample &imu_sample); bool checkHaglYawResetReq() const; @@ -1052,7 +1052,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_AUXVEL) // control fusion of auxiliary velocity observations - void controlAuxVelFusion(); + void controlAuxVelFusion(const imuSample &imu_sample); void stopAuxVelFusion(); #endif // CONFIG_EKF2_AUXVEL diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index 56a667840a75..4db232ca051f 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -53,7 +53,7 @@ void Ekf::controlHeightFusion(const imuSample &imu_delayed) #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_RANGE_FINDER) - controlRangeHaglFusion(); + controlRangeHaglFusion(imu_delayed); #endif // CONFIG_EKF2_RANGE_FINDER checkHeightSensorRefFallback(); From 9124a7b47160bc9d4a843047da7aacc66107b6b6 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 8 Jul 2024 11:25:21 -0400 Subject: [PATCH 477/652] ekf2: add IMU delta_ang_dt/delta_vel_dt safety constrain before pushing into buffer --- src/modules/ekf2/EKF/covariance.cpp | 4 ++-- src/modules/ekf2/EKF/estimator_interface.cpp | 12 +++++++++++- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 8108d26c1381..58e83b3bd757 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -134,8 +134,8 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) // calculate variances and upper diagonal covariances for quaternion, velocity, position and gyro bias states P = sym::PredictCovariance(_state.vector(), P, - imu_delayed.delta_vel / math::max(imu_delayed.delta_vel_dt, FLT_EPSILON), accel_var, - imu_delayed.delta_ang / math::max(imu_delayed.delta_ang_dt, FLT_EPSILON), gyro_var, + imu_delayed.delta_vel / imu_delayed.delta_vel_dt, accel_var, + imu_delayed.delta_ang / imu_delayed.delta_ang_dt, gyro_var, dt); // Construct the process noise variance diagonal for those states with a stationary process model diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index bce6ec88637f..d4a579f5b8cf 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -94,7 +94,17 @@ void EstimatorInterface::setIMUData(const imuSample &imu_sample) _imu_updated = true; - _imu_buffer.push(_imu_down_sampler.getDownSampledImuAndTriggerReset()); + imuSample imu_downsampled = _imu_down_sampler.getDownSampledImuAndTriggerReset(); + + // as a precaution constrain the integration delta time to prevent numerical problems + const float filter_update_period_s = _params.filter_update_interval_us * 1e-6f; + const float imu_min_dt = 0.5f * filter_update_period_s; + const float imu_max_dt = 2.0f * filter_update_period_s; + + imu_downsampled.delta_ang_dt = math::constrain(imu_downsampled.delta_ang_dt, imu_min_dt, imu_max_dt); + imu_downsampled.delta_vel_dt = math::constrain(imu_downsampled.delta_vel_dt, imu_min_dt, imu_max_dt); + + _imu_buffer.push(imu_downsampled); // get the oldest data from the buffer _time_delayed_us = _imu_buffer.get_oldest().time_us; From 33be5d8356e57ee98ae70e0725cf8e3b4a6e2238 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Thu, 11 Jul 2024 14:54:22 +0200 Subject: [PATCH 478/652] Survey - fix of survey tracking problem on steep slopes (#23371) * initial working * incoperated review --- .../tasks/Auto/FlightTaskAuto.cpp | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index 606776aea8c4..dad05e3c31db 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -632,29 +632,27 @@ bool FlightTaskAuto::_evaluateGlobalReference() State FlightTaskAuto::_getCurrentState() { // Calculate the vehicle current state based on the Navigator triplets and the current position. - const Vector2f u_prev_to_target_xy = Vector2f(_triplet_target - _triplet_prev_wp).unit_or_zero(); - const Vector2f pos_to_target_xy = Vector2f(_triplet_target - _position); - const Vector2f prev_to_pos_xy = Vector2f(_position - _triplet_prev_wp); + const Vector3f u_prev_to_target = (_triplet_target - _triplet_prev_wp).unit_or_zero(); + const Vector3f prev_to_pos = _position - _triplet_prev_wp; + const Vector3f pos_to_target = _triplet_target - _position; // Calculate the closest point to the vehicle position on the line prev_wp - target - const Vector2f closest_pt_xy = Vector2f(_triplet_prev_wp) + u_prev_to_target_xy * (prev_to_pos_xy * - u_prev_to_target_xy); - _closest_pt = Vector3f(closest_pt_xy(0), closest_pt_xy(1), _triplet_target(2)); + _closest_pt = _triplet_prev_wp + u_prev_to_target * (prev_to_pos * u_prev_to_target); State return_state = State::none; - if (u_prev_to_target_xy.length() < FLT_EPSILON) { + if (!u_prev_to_target.longerThan(FLT_EPSILON)) { // Previous and target are the same point, so we better don't try to do any special line following return_state = State::none; - } else if (u_prev_to_target_xy * pos_to_target_xy < 0.0f) { + } else if (u_prev_to_target * pos_to_target < 0.0f) { // Target is behind return_state = State::target_behind; - } else if (u_prev_to_target_xy * prev_to_pos_xy < 0.0f && prev_to_pos_xy.longerThan(_target_acceptance_radius)) { + } else if (u_prev_to_target * prev_to_pos < 0.0f && prev_to_pos.longerThan(_target_acceptance_radius)) { // Previous is in front return_state = State::previous_infront; - } else if (Vector2f(_position - _closest_pt).longerThan(_target_acceptance_radius)) { + } else if ((_position - _closest_pt).longerThan(_target_acceptance_radius)) { // Vehicle too far from the track return_state = State::offtrack; From e2b31454a3843cc0d3a701986bc64c856c5ce818 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 12 Jul 2024 15:17:58 +0200 Subject: [PATCH 479/652] SubscriptionInterval: move updated, update, copy function to a cpp file Saves 17.3 kilobytes of flash :open_mouth: --- platforms/common/uORB/CMakeLists.txt | 1 + .../common/uORB/SubscriptionInterval.cpp | 77 +++++++++++++++++++ .../common/uORB/SubscriptionInterval.hpp | 38 +-------- 3 files changed, 81 insertions(+), 35 deletions(-) create mode 100644 platforms/common/uORB/SubscriptionInterval.cpp diff --git a/platforms/common/uORB/CMakeLists.txt b/platforms/common/uORB/CMakeLists.txt index 609d2aebe68f..2e3add770e1b 100644 --- a/platforms/common/uORB/CMakeLists.txt +++ b/platforms/common/uORB/CMakeLists.txt @@ -47,6 +47,7 @@ set(SRCS_COMMON Subscription.cpp Subscription.hpp SubscriptionCallback.hpp + SubscriptionInterval.cpp SubscriptionInterval.hpp SubscriptionMultiArray.hpp uORB.cpp diff --git a/platforms/common/uORB/SubscriptionInterval.cpp b/platforms/common/uORB/SubscriptionInterval.cpp new file mode 100644 index 000000000000..8f8af333f2ea --- /dev/null +++ b/platforms/common/uORB/SubscriptionInterval.cpp @@ -0,0 +1,77 @@ +/**************************************************************************** + * + * 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 "SubscriptionInterval.hpp" + +namespace uORB +{ + +bool SubscriptionInterval::updated() +{ + if (advertised() && (hrt_elapsed_time(&_last_update) >= _interval_us)) { + return _subscription.updated(); + } + + return false; +} + +bool SubscriptionInterval::update(void *dst) +{ + if (updated()) { + return copy(dst); + } + + return false; +} + +bool SubscriptionInterval::copy(void *dst) +{ + if (_subscription.copy(dst)) { + const hrt_abstime now = hrt_absolute_time(); + + // make sure we don't set a timestamp before the timer started counting (now - _interval_us would wrap because it's unsigned) + if (now > _interval_us) { + // shift last update time forward, but don't let it get further behind than the interval + _last_update = math::constrain(_last_update + _interval_us, now - _interval_us, now); + + } else { + _last_update = now; + } + + return true; + } + + return false; +} + +} // namespace uORB diff --git a/platforms/common/uORB/SubscriptionInterval.hpp b/platforms/common/uORB/SubscriptionInterval.hpp index 07572f72f218..fd6ccdfb61c5 100644 --- a/platforms/common/uORB/SubscriptionInterval.hpp +++ b/platforms/common/uORB/SubscriptionInterval.hpp @@ -93,53 +93,21 @@ class SubscriptionInterval /** * Check if there is a new update. * */ - bool updated() - { - if (advertised() && (hrt_elapsed_time(&_last_update) >= _interval_us)) { - return _subscription.updated(); - } - - return false; - } + bool updated(); /** * Copy the struct if updated. * @param dst The destination pointer where the struct will be copied. * @return true only if topic was updated and copied successfully. */ - bool update(void *dst) - { - if (updated()) { - return copy(dst); - } - - return false; - } + bool update(void *dst); /** * Copy the struct * @param dst The destination pointer where the struct will be copied. * @return true only if topic was copied successfully. */ - bool copy(void *dst) - { - if (_subscription.copy(dst)) { - const hrt_abstime now = hrt_absolute_time(); - - // make sure we don't set a timestamp before the timer started counting (now - _interval_us would wrap because it's unsigned) - if (now > _interval_us) { - // shift last update time forward, but don't let it get further behind than the interval - _last_update = math::constrain(_last_update + _interval_us, now - _interval_us, now); - - } else { - _last_update = now; - } - - return true; - } - - return false; - } + bool copy(void *dst); bool valid() const { return _subscription.valid(); } From b1b0032b8d7ea7ef7a0b7edfe5a9ed787acb3f9c Mon Sep 17 00:00:00 2001 From: Liu1 <108582329+cuav-liu1@users.noreply.github.com> Date: Mon, 15 Jul 2024 06:08:20 +0800 Subject: [PATCH 480/652] BMP581: Add Bosch BMP581 barometer (#23064) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * BMP581: Add Bosch BMP581 barometer * Copyright:fix copyright header year * style: not use pointers and Bool returns, Check the failed condition return * delay: Replace usleep() with ScheduleDelayed() * definitions: Delete unused definitions * comment: Delet redundant comments * constants: Change to uppercase * BMP581: run make format --- src/drivers/barometer/CMakeLists.txt | 3 +- src/drivers/barometer/Kconfig | 1 + src/drivers/barometer/bmp581/CMakeLists.txt | 44 ++ src/drivers/barometer/bmp581/Kconfig | 5 + src/drivers/barometer/bmp581/bmp581.cpp | 727 +++++++++++++++++++ src/drivers/barometer/bmp581/bmp581.h | 320 ++++++++ src/drivers/barometer/bmp581/bmp581_i2c.cpp | 95 +++ src/drivers/barometer/bmp581/bmp581_main.cpp | 127 ++++ src/drivers/barometer/bmp581/bmp581_spi.cpp | 102 +++ src/drivers/drv_sensor.h | 3 +- 10 files changed, 1425 insertions(+), 2 deletions(-) create mode 100644 src/drivers/barometer/bmp581/CMakeLists.txt create mode 100644 src/drivers/barometer/bmp581/Kconfig create mode 100644 src/drivers/barometer/bmp581/bmp581.cpp create mode 100644 src/drivers/barometer/bmp581/bmp581.h create mode 100644 src/drivers/barometer/bmp581/bmp581_i2c.cpp create mode 100644 src/drivers/barometer/bmp581/bmp581_main.cpp create mode 100644 src/drivers/barometer/bmp581/bmp581_spi.cpp diff --git a/src/drivers/barometer/CMakeLists.txt b/src/drivers/barometer/CMakeLists.txt index ba90108c38c2..5bb31ec3452d 100644 --- a/src/drivers/barometer/CMakeLists.txt +++ b/src/drivers/barometer/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2017 PX4 Development Team. All rights reserved. +# Copyright (c) 2017-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 @@ -33,6 +33,7 @@ add_subdirectory(bmp280) add_subdirectory(bmp388) +add_subdirectory(bmp581) add_subdirectory(dps310) add_subdirectory(lps22hb) #add_subdirectory(lps25h) # not ready for general inclusion diff --git a/src/drivers/barometer/Kconfig b/src/drivers/barometer/Kconfig index e13c24c27251..da9c2dd7143a 100644 --- a/src/drivers/barometer/Kconfig +++ b/src/drivers/barometer/Kconfig @@ -4,6 +4,7 @@ menu "barometer" default n select DRIVERS_BAROMETER_BMP280 select DRIVERS_BAROMETER_BMP388 + select DRIVERS_BAROMETER_BMP581 select DRIVERS_BAROMETER_DPS310 select DRIVERS_BAROMETER_LPS22HB select DRIVERS_BAROMETER_LPS33HW diff --git a/src/drivers/barometer/bmp581/CMakeLists.txt b/src/drivers/barometer/bmp581/CMakeLists.txt new file mode 100644 index 000000000000..c5de8e20b3f6 --- /dev/null +++ b/src/drivers/barometer/bmp581/CMakeLists.txt @@ -0,0 +1,44 @@ +############################################################################ +# +# 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_module( + MODULE drivers__barometer__bmp581 + MAIN bmp581 + SRCS + bmp581_spi.cpp + bmp581_i2c.cpp + bmp581.cpp + bmp581_main.cpp + DEPENDS + px4_work_queue + ) diff --git a/src/drivers/barometer/bmp581/Kconfig b/src/drivers/barometer/bmp581/Kconfig new file mode 100644 index 000000000000..49f99b08b2b6 --- /dev/null +++ b/src/drivers/barometer/bmp581/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_BMP581 + bool "bmp581" + default n + ---help--- + Enable support for bmp581 diff --git a/src/drivers/barometer/bmp581/bmp581.cpp b/src/drivers/barometer/bmp581/bmp581.cpp new file mode 100644 index 000000000000..a4a085397c4a --- /dev/null +++ b/src/drivers/barometer/bmp581/bmp581.cpp @@ -0,0 +1,727 @@ +/**************************************************************************** + * + * 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 FITNESSf + * 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 "bmp581.h" +#include + +BMP581::BMP581(const I2CSPIDriverConfig &config, IBMP581 *interface) : + I2CSPIDriver(config), + _interface(interface), + _sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")), + _measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")), + _comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms_errors")) +{ +} + +BMP581::~BMP581() +{ + /* free perf counters */ + perf_free(_sample_perf); + perf_free(_measure_perf); + perf_free(_comms_errors); + + delete _interface; +} + +int BMP581::init() +{ + int ret; + + ret = soft_reset(); + + if (ret != PX4_OK) { + PX4_DEBUG("failed to reset baro during init"); + return -EIO; + } + + _chip_id = _interface->get_reg(BMP5_REG_CHIP_ID_ADDR); + + if ((_chip_id != BMP581_CHIP_ID_PRIM) && (_chip_id != BMP581_CHIP_ID_SEC)) { + PX4_WARN("id of your baro is not: 0x%02x or 0x%02x", BMP581_CHIP_ID_PRIM, BMP581_CHIP_ID_SEC); + return -EIO; + } + + _chip_rev_id = _interface->get_reg(BMP5_REG_REV_ID_ADDR); + + ret = set_config(); + + if (ret != PX4_OK) { + PX4_WARN("failed to set_config"); + return -EIO; + } + + start(); + + return PX4_OK; +} + +void BMP581::print_status() +{ + I2CSPIDriverBase::print_status(); + printf("chip id: 0x%02x rev id: 0x%02x\n", _chip_id, _chip_rev_id); + perf_print_counter(_sample_perf); + perf_print_counter(_measure_perf); + perf_print_counter(_comms_errors); + printf("measurement interval: %u us \n", _measure_interval); +} + +void BMP581::start() +{ + _collect_phase = false; + + ScheduleOnInterval(_measure_interval, _measure_interval * 3); +} + +void BMP581::RunImpl() +{ + + if (_collect_phase) { + collect(); + } + + measure(); +} + +int BMP581::measure() +{ + int ret; + + _collect_phase = true; + + perf_begin(_measure_perf); + + /* start measurement */ + ret = set_power_mode(BMP5_POWERMODE_FORCED); + + if (ret != PX4_OK) { + PX4_DEBUG("failed to set power mode"); + perf_count(_comms_errors); + perf_cancel(_measure_perf); + return -EIO; + } + + perf_end(_measure_perf); + + return PX4_OK; +} + +int BMP581::collect() +{ + _collect_phase = false; + + bmp5_sensor_data data{}; + + uint8_t int_status; + int ret; + + perf_begin(_sample_perf); + + /* this should be fairly close to the end of the conversion, so the best approximation of the time */ + const hrt_abstime timestamp_sample = hrt_absolute_time(); + + int_status = get_interrupt_status(); + + if (int_status & BMP5_INT_ASSERTED_DRDY) { + ret = get_sensor_data(&data); + + if (ret != PX4_OK) { + perf_count(_comms_errors); + perf_cancel(_sample_perf); + return -EIO; + } + } + + //publish + sensor_baro_s sensor_baro{}; + sensor_baro.timestamp_sample = timestamp_sample; + sensor_baro.device_id = _interface->get_device_id(); + sensor_baro.pressure = data.pressure; + sensor_baro.temperature = data.temperature; + sensor_baro.error_count = perf_event_count(_comms_errors); + sensor_baro.timestamp = hrt_absolute_time(); + _sensor_baro_pub.publish(sensor_baro); + + perf_end(_sample_perf); + + return PX4_OK; +} + +/*! + * @brief This API performs the soft reset of the sensor + * + * https://github.com/boschsensortec/BMP5-Sensor-API/blob/master/bmp5.c + */ +int BMP581::soft_reset() +{ + uint8_t status; + int ret; + + if (intf == BMP5_SPI_INTF) { + /* Performing a single read via SPI of registers, + * e.g. registers CHIP_ID, before the actual + * SPI communication with the device. + */ + status = _interface->get_reg(BMP5_REG_CHIP_ID_ADDR); + } + + ret = _interface->set_reg(BMP5_SOFT_RESET_CMD, BMP5_REG_CMD_ADDR); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + + usleep(BMP5_DELAY_US_SOFT_RESET); + + if (intf == BMP5_SPI_INTF) { + /* Performing a single read via SPI of registers, + * e.g. registers CHIP_ID, before the actual + * SPI communication with the device. + */ + status = _interface->get_reg(BMP5_REG_CHIP_ID_ADDR); + } + + status = _interface->get_reg(BMP5_REG_STATUS_ADDR); + + /* Check if nvm_rdy status = 1 and nvm_err status = 0 to proceed */ + if (!((status & BMP5_INT_NVM_RDY) && (!(status & BMP5_INT_NVM_ERR)))) { + return PX4_ERROR; + } + + status = _interface->get_reg(BMP5_REG_INT_STATUS_ADDR); + + if (status & BMP5_INT_ASSERTED_POR_SOFTRESET_COMPLETE) { + return PX4_OK; + + } else { + return PX4_ERROR; + } +} + +int BMP581::set_config() +{ + int ret; + + ret = set_power_mode(BMP5_POWERMODE_STANDBY); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + + ret = set_osr_odr_press_config(); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + + ret = set_iir_config(); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + + ret = configure_interrupt(); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + + ret = int_source_select(); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + + return PX4_OK; +} + +/*! + * @brief This API is used to get interrupt status. + */ +uint8_t BMP581::get_interrupt_status() +{ + uint8_t status = 0xFF; + + status = _interface->get_reg(BMP5_REG_INT_STATUS_ADDR); + + return status; +} + +uint8_t BMP581::check_deepstandby_mode() +{ + int rslt; + uint8_t fifo_frame_sel; + uint8_t reg_data[2]; + uint8_t powermode = 0xFF; + + fifo_frame_sel = _interface->get_reg(BMP5_REG_FIFO_SEL_ADDR); + fifo_frame_sel = BMP5_GET_BITS_POS_0(fifo_frame_sel, BMP5_FIFO_FRAME_SEL); + + rslt = _interface->get_reg_buf(BMP5_REG_OSR_CONFIG_ADDR, reg_data, 2); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + uint8_t odr_reg = 0xFF; + odr_reg = BMP5_GET_BITSLICE(reg_data[1], BMP5_ODR); + + rslt = _interface->get_reg_buf(BMP5_REG_DSP_CONFIG_ADDR, reg_data, 2); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + uint8_t set_iir_t_reg = 0xFF; + uint8_t set_iir_p_reg = 0xFF; + + set_iir_t_reg = BMP5_GET_BITS_POS_0(reg_data[1], BMP5_SET_IIR_TEMP); + set_iir_p_reg = BMP5_GET_BITSLICE(reg_data[1], BMP5_SET_IIR_PRESS); + + /* As per datasheet odr should be less than 5Hz. But register value for 5Hz is less than 4Hz and so, + * thus in this below condition odr is checked whether greater than 5Hz macro. + */ + if ((odr_reg > BMP5_ODR_05_HZ) && (fifo_frame_sel == BMP5_DISABLE) && + (set_iir_t_reg == BMP5_IIR_FILTER_BYPASS) && (set_iir_p_reg == BMP5_IIR_FILTER_BYPASS)) { + powermode = BMP5_POWERMODE_DEEP_STANDBY; + } + + return powermode; +} + +/*! + * @brief This API is used to get powermode of the sensor. + */ +uint8_t BMP581::get_power_mode() +{ + uint8_t deep_dis; + uint8_t reg_data; + uint8_t powermode; + + reg_data = _interface->get_reg(BMP5_REG_ODR_CONFIG_ADDR); + powermode = BMP5_GET_BITS_POS_0(reg_data, BMP5_POWERMODE); + + if (powermode == BMP5_POWERMODE_STANDBY) { + deep_dis = BMP5_GET_BITSLICE(reg_data, BMP5_DEEP_DISABLE); + + if (deep_dis == BMP5_DEEP_ENABLED) { + powermode = check_deepstandby_mode(); + } + } + + return powermode; +} + +/*! + * @brief This API is used to set powermode of the sensor. + */ +int BMP581::set_power_mode(uint8_t power_mode) +{ + uint8_t lst_pwrmode; + uint8_t reg_data; + int rslt; + + lst_pwrmode = get_power_mode(); + + if (lst_pwrmode != BMP5_POWERMODE_STANDBY) { + reg_data = _interface->get_reg(BMP5_REG_ODR_CONFIG_ADDR); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_DEEP_DISABLE, BMP5_DEEP_DISABLED); + reg_data = BMP5_SET_BITS_POS_0(reg_data, BMP5_POWERMODE, BMP5_POWERMODE_STANDBY); + rslt = _interface->set_reg(reg_data, BMP5_REG_ODR_CONFIG_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + ScheduleDelayed(BMP5_DELAY_US_STANDBY); + } + + switch (power_mode) { + case BMP5_POWERMODE_DEEP_STANDBY: + rslt = set_deep_standby_mode(); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + break; + + case BMP5_POWERMODE_STANDBY: + break; + + case BMP5_POWERMODE_NORMAL: + case BMP5_POWERMODE_FORCED: + case BMP5_POWERMODE_CONTINOUS: + reg_data = _interface->get_reg(BMP5_REG_ODR_CONFIG_ADDR); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_DEEP_DISABLE, BMP5_DEEP_DISABLED); + reg_data = BMP5_SET_BITS_POS_0(reg_data, BMP5_POWERMODE, power_mode); + rslt = _interface->set_reg(reg_data, BMP5_REG_ODR_CONFIG_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + break; + } + + return PX4_OK; +} + +/*! + * @brief This internal API is used to set sensor in deep standby mode. + */ +int BMP581::set_deep_standby_mode() +{ + uint8_t reg_data; + int rslt; + + reg_data = _interface->get_reg(BMP5_REG_ODR_CONFIG_ADDR); + reg_data = BMP5_SET_BIT_VAL_0(reg_data, BMP5_DEEP_DISABLE); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_ODR, BMP5_ODR_01_HZ); + rslt = _interface->set_reg(reg_data, BMP5_REG_ODR_CONFIG_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + reg_data = _interface->get_reg(BMP5_REG_DSP_IIR_ADDR); + reg_data = reg_data & BMP5_IIR_BYPASS; + rslt = _interface->set_reg(reg_data, BMP5_REG_DSP_IIR_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + reg_data = _interface->get_reg(BMP5_REG_FIFO_SEL_ADDR); + reg_data = BMP5_SET_BIT_VAL_0(reg_data, BMP5_FIFO_FRAME_SEL); + rslt = _interface->set_reg(reg_data, BMP5_REG_FIFO_SEL_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + return PX4_OK; +} + +/*! + * @brief This internal API is used to set sensor in standby powermode when powermode is deepstandby mode. + */ +int BMP581::set_standby_mode() +{ + uint8_t powermode; + int ret; + + powermode = get_power_mode(); + + if (powermode == BMP5_POWERMODE_DEEP_STANDBY) { + ret = set_power_mode(BMP5_POWERMODE_STANDBY); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + } + + return PX4_OK; +} + +uint32_t BMP581::get_measurement_time() +{ + /* + From BST-BMP3581-DS004-04.pdf, page 19, table 9 + + Pressure Temperature Measurement + Oversample Oversample Time + 1x 1x 2.7 ms + 2x 1x 3.3 ms + 4x 1x 4.6 ms + 8x 1x 7.2 ms + 16x 1x 12.5 ms + 32x 2x 23.3 ms + 64x 4x 44.2 ms + 128x 8x 88.0 ms + */ + + uint32_t meas_time_us = 0; // unsupported value by default + + if (OVERSAMPLING_TEMPERATURE == BMP5_OVERSAMPLING_1X) { + switch (OVERSAMPLING_PRESSURE) { + case BMP5_OVERSAMPLING_1X: + meas_time_us = 2700; + break; + + case BMP5_OVERSAMPLING_2X: + meas_time_us = 3300; + break; + + case BMP5_OVERSAMPLING_4X: + meas_time_us = 4600; + break; + + case BMP5_OVERSAMPLING_8X: + meas_time_us = 7200; + break; + + case BMP5_OVERSAMPLING_16X: + meas_time_us = 12500; + break; + } + + } else if (OVERSAMPLING_TEMPERATURE == BMP5_OVERSAMPLING_2X) { + switch (OVERSAMPLING_PRESSURE) { + case BMP5_OVERSAMPLING_32X: + meas_time_us = 23300; + break; + + } + + } else if (OVERSAMPLING_TEMPERATURE == BMP5_OVERSAMPLING_4X) { + switch (OVERSAMPLING_PRESSURE) { + case BMP5_OVERSAMPLING_64X: + meas_time_us = 44200; + break; + + } + + } else if (OVERSAMPLING_TEMPERATURE == BMP5_OVERSAMPLING_8X) { + switch (OVERSAMPLING_PRESSURE) { + case BMP5_OVERSAMPLING_128X: + meas_time_us = 88000; + break; + + } + } + + return meas_time_us; +} + +/*! + * @brief This API sets the configuration for oversampling temperature, oversampling of + * pressure and ODR configuration along with pressure enable. + * + * @note If ODR is set to a value higher than 5Hz then powermode is set as standby mode, as ODR value greater than 5HZ + * without disabling deep-standby mode makes powermode invalid. + */ +int BMP581::set_osr_odr_press_config() +{ + uint8_t reg_data[2] = {0}; + int rslt; + + _measure_interval = get_measurement_time(); + + if (_measure_interval == 0) { + PX4_WARN("unsupported oversampling selected"); + return false; + } + + if (OUTPUT_DATA_RATE < BMP5_ODR_05_HZ) { + rslt = set_standby_mode(); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + } + + rslt = _interface->get_reg_buf(BMP5_REG_OSR_CONFIG_ADDR, reg_data, 2); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + reg_data[0] = BMP5_SET_BITS_POS_0(reg_data[0], BMP5_TEMP_OS, OVERSAMPLING_TEMPERATURE); + reg_data[0] = BMP5_SET_BITSLICE(reg_data[0], BMP5_PRESS_OS, OVERSAMPLING_PRESSURE); + reg_data[0] = BMP5_SET_BITSLICE(reg_data[0], BMP5_PRESS_EN, PRESSURE_ENABLE); + reg_data[1] = BMP5_SET_BITSLICE(reg_data[1], BMP5_ODR, OUTPUT_DATA_RATE); + + rslt = _interface->set_reg(reg_data[0], BMP5_REG_OSR_CONFIG_ADDR); + rslt = _interface->set_reg(reg_data[1], BMP5_REG_ODR_CONFIG_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + return PX4_OK; +} + +/*! + * @brief This API sets the configuration for IIR of temperature and pressure. + * + * @note If IIR value for both temperature and pressure is set a value other than bypass then powermode is set + * as standby mode, as IIR with value other than bypass without disabling deep-standby mode makes powermode invalid. + */ +int BMP581::set_iir_config() +{ + uint8_t curr_powermdoe; + uint8_t reg_data[2]; + int rslt; + + if ((IIR_FILTER_COEFF_TEMPERATURE != BMP5_IIR_FILTER_BYPASS) || (IIR_FILTER_COEFF_PRESSURE != BMP5_IIR_FILTER_BYPASS)) { + rslt = set_standby_mode(); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + } + + curr_powermdoe = get_power_mode(); + + if (curr_powermdoe != BMP5_POWERMODE_STANDBY) { + rslt = set_power_mode(BMP5_POWERMODE_STANDBY); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + } + + rslt = _interface->get_reg_buf(BMP5_REG_DSP_CONFIG_ADDR, reg_data, 2); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + reg_data[0] = BMP5_SET_BITSLICE(reg_data[0], BMP5_SHDW_SET_IIR_TEMP, BMP5_ENABLE); + reg_data[0] = BMP5_SET_BITSLICE(reg_data[0], BMP5_SHDW_SET_IIR_PRESS, BMP5_ENABLE); + reg_data[0] = BMP5_SET_BITSLICE(reg_data[0], BMP5_IIR_FLUSH_FORCED_EN, BMP5_ENABLE); + + reg_data[1] = IIR_FILTER_COEFF_TEMPERATURE; + reg_data[1] = BMP5_SET_BITSLICE(reg_data[1], BMP5_SET_IIR_PRESS, IIR_FILTER_COEFF_PRESSURE); + + rslt = _interface->set_reg(reg_data[0], BMP5_REG_DSP_CONFIG_ADDR); + rslt = _interface->set_reg(reg_data[1], BMP5_REG_DSP_IIR_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + /* Since IIR works only in standby mode we are not re-writing to deepstandby mode + * as deep standby mode resets the IIR settings to default + */ + if ((curr_powermdoe != BMP5_POWERMODE_STANDBY) && (curr_powermdoe != BMP5_POWERMODE_DEEP_STANDBY)) { + if (!set_power_mode(curr_powermdoe)) { + return PX4_ERROR; + } + + } + + return PX4_OK; +} + +/*! +* @brief This API is used to configure the interrupt settings. +*/ +int BMP581::configure_interrupt() +{ + uint8_t reg_data = 0; + uint8_t int_source = 0; + int rslt; + + reg_data = _interface->get_reg(BMP5_REG_INT_CONFIG_ADDR); + + /* Any change between latched/pulsed mode has to be applied while interrupt is disabled */ + /* Step 1 : Turn off all INT sources (INT_SOURCE -> 0x00) */ + rslt = _interface->set_reg(int_source, BMP5_REG_INT_SOURCE_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + /* Step 2 : Read the INT_STATUS register to clear the status */ + _interface->get_reg(BMP5_REG_INT_STATUS_ADDR); + + /* Step 3 : Set the desired mode in INT_CONFIG.int_mode */ + reg_data = BMP5_SET_BITS_POS_0(reg_data, BMP5_INT_MODE, INTERRUPT_MODE); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_INT_POL, INTERRUPT_POLARITY); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_INT_OD, INTERRUPT_DRIVE); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_INT_EN, BMP5_ENABLE); + + rslt = _interface->set_reg(reg_data, BMP5_REG_INT_CONFIG_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + return PX4_OK; +} + +int BMP581::int_source_select() +{ + uint8_t reg_data; + int rslt; + + reg_data = _interface->get_reg(BMP5_REG_INT_SOURCE_ADDR); + + reg_data = BMP5_SET_BITS_POS_0(reg_data, BMP5_INT_DRDY_EN, BMP5_ENABLE); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_INT_FIFO_FULL_EN, BMP5_DISABLE); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_INT_FIFO_THRES_EN, BMP5_DISABLE); + reg_data = BMP5_SET_BITSLICE(reg_data, BMP5_INT_OOR_PRESS_EN, BMP5_DISABLE); + + rslt = _interface->set_reg(reg_data, BMP5_REG_INT_SOURCE_ADDR); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + return PX4_OK; +} + +/*! + * @brief This API reads the temperature(deg C) or both pressure(Pa) and temperature(deg C) data from the + * sensor and store it in the bmp5_sensor_data structure instance passed by the user. + */ +int BMP581::get_sensor_data(bmp5_sensor_data *sensor_data) +{ + uint8_t reg_data[6] = {0}; + int32_t raw_data_t; + uint32_t raw_data_p; + int8_t rslt; + + rslt = _interface->get_reg_buf(BMP5_REG_TEMP_DATA_XLSB_ADDR, reg_data, 6); + + if (rslt != PX4_OK) { + return PX4_ERROR; + } + + raw_data_t = (int32_t)((int32_t)((uint32_t)(((uint32_t)reg_data[2] << 16) | ((uint16_t)reg_data[1] << 8) | reg_data[0]) + << 8) >> 8); + /* Division by 2^16(whose equivalent value is 65536) is performed to get temperature data in deg C */ + sensor_data->temperature = (float)(raw_data_t / 65536.0); + + if (PRESSURE_ENABLE == BMP5_ENABLE) { + raw_data_p = (uint32_t)((uint32_t)(reg_data[5] << 16) | (uint16_t)(reg_data[4] << 8) | reg_data[3]); + /* Division by 2^6(whose equivalent value is 64) is performed to get pressure data in Pa */ + sensor_data->pressure = (float)(raw_data_p / 64.0); + + } else { + sensor_data->pressure = 0.0; + } + + return PX4_OK; +} diff --git a/src/drivers/barometer/bmp581/bmp581.h b/src/drivers/barometer/bmp581/bmp581.h new file mode 100644 index 000000000000..56d87fa3f1df --- /dev/null +++ b/src/drivers/barometer/bmp581/bmp581.h @@ -0,0 +1,320 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file bmp581.h + * + * Shared defines for the bmp581 driver. + */ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "board_config.h" + +// From https://github.com/boschsensortec/BMP5-Sensor-API/blob/master/bmp5_defs.h + +/* BIT SLICE GET AND SET FUNCTIONS */ +#define BMP5_GET_BITSLICE(regvar, bitname) \ + ((regvar & bitname##_MSK) >> bitname##_POS) + +#define BMP5_SET_BITSLICE(regvar, bitname, val) \ + ((regvar & ~bitname##_MSK) | \ + ((val << bitname##_POS) & bitname##_MSK)) + +#define BMP5_SET_BIT_VAL_0(reg_data, bitname) (reg_data & ~(bitname##_MSK)) + +#define BMP5_SET_BITS_POS_0(reg_data, bitname, data) \ + ((reg_data & ~(bitname##_MSK)) | \ + (data & bitname##_MSK)) + +#define BMP5_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK)) + +/* Chip id of BMP5 */ +#define BMP581_CHIP_ID_PRIM (0x50) +#define BMP581_CHIP_ID_SEC (0x51) + +#define BMP5_ENABLE (0x01) +#define BMP5_DISABLE (0x00) + +/* Register addresses */ +#define BMP5_REG_CHIP_ID_ADDR (0x01) +#define BMP5_REG_REV_ID_ADDR (0x02) +#define BMP5_REG_INT_CONFIG_ADDR (0x14) +#define BMP5_REG_INT_SOURCE_ADDR (0x15) +#define BMP5_REG_FIFO_SEL_ADDR (0x18) +#define BMP5_REG_TEMP_DATA_XLSB_ADDR (0x1D) +#define BMP5_REG_INT_STATUS_ADDR (0x27) +#define BMP5_REG_STATUS_ADDR (0x28) +#define BMP5_REG_NVM_ADDR (0x2B) +#define BMP5_REG_DSP_CONFIG_ADDR (0x30) +#define BMP5_REG_DSP_IIR_ADDR (0x31) +#define BMP5_REG_OSR_CONFIG_ADDR (0x36) +#define BMP5_REG_ODR_CONFIG_ADDR (0x37) +#define BMP5_REG_CMD_ADDR (0x7E) + +/* Delay definition */ +#define BMP5_DELAY_US_SOFT_RESET (2000) +#define BMP5_DELAY_US_STANDBY (2500) + +/* Soft reset command */ +#define BMP5_SOFT_RESET_CMD (0xB6) + +/* Deepstandby enable/disable */ +#define BMP5_DEEP_ENABLED (0) +#define BMP5_DEEP_DISABLED (1) + +/* ODR settings */ +#define BMP5_ODR_50_HZ (0x0F) +#define BMP5_ODR_05_HZ (0x18) +#define BMP5_ODR_01_HZ (0x1C) + + +/* Oversampling for temperature and pressure */ +#define BMP5_OVERSAMPLING_1X (0x00) +#define BMP5_OVERSAMPLING_2X (0x01) +#define BMP5_OVERSAMPLING_4X (0x02) +#define BMP5_OVERSAMPLING_8X (0x03) +#define BMP5_OVERSAMPLING_16X (0x04) +#define BMP5_OVERSAMPLING_32X (0x05) +#define BMP5_OVERSAMPLING_64X (0x06) +#define BMP5_OVERSAMPLING_128X (0x07) + +/* IIR filter for temperature and pressure */ +#define BMP5_IIR_FILTER_BYPASS (0x00) +#define BMP5_IIR_FILTER_COEFF_1 (0x01) + +/* Macro is used to bypass both iir_t and iir_p together */ +#define BMP5_IIR_BYPASS (0xC0) + +/* Interrupt configurations */ +#define BMP5_INT_MODE_PULSED (0) +#define BMP5_INT_POL_ACTIVE_HIGH (1) +#define BMP5_INT_OD_PUSHPULL (0) + +/* NVM and Interrupt status asserted macros */ +#define BMP5_INT_ASSERTED_POR_SOFTRESET_COMPLETE (0x10) +#define BMP5_INT_NVM_RDY (0x02) +#define BMP5_INT_NVM_ERR (0x04) + +/* Interrupt configurations */ +#define BMP5_INT_MODE_MSK (0x01) + +#define BMP5_INT_POL_MSK (0x02) +#define BMP5_INT_POL_POS (1) + +#define BMP5_INT_OD_MSK (0x04) +#define BMP5_INT_OD_POS (2) + +#define BMP5_INT_EN_MSK (0x08) +#define BMP5_INT_EN_POS (3) + +#define BMP5_INT_DRDY_EN_MSK (0x01) + +#define BMP5_INT_FIFO_FULL_EN_MSK (0x02) +#define BMP5_INT_FIFO_FULL_EN_POS (1) + +#define BMP5_INT_FIFO_THRES_EN_MSK (0x04) +#define BMP5_INT_FIFO_THRES_EN_POS (2) + +#define BMP5_INT_OOR_PRESS_EN_MSK (0x08) +#define BMP5_INT_OOR_PRESS_EN_POS (3) + +/* ODR configuration */ +#define BMP5_ODR_MSK (0x7C) +#define BMP5_ODR_POS (2) + +/* OSR configurations */ +#define BMP5_TEMP_OS_MSK (0x07) + +#define BMP5_PRESS_OS_MSK (0x38) +#define BMP5_PRESS_OS_POS (3) + +/* Pressure enable */ +#define BMP5_PRESS_EN_MSK (0x40) +#define BMP5_PRESS_EN_POS (6) + +/* IIR configurations */ +#define BMP5_SET_IIR_TEMP_MSK (0x07) + +#define BMP5_SET_IIR_PRESS_MSK (0x38) +#define BMP5_SET_IIR_PRESS_POS (3) + +#define BMP5_SHDW_SET_IIR_TEMP_MSK (0x08) +#define BMP5_SHDW_SET_IIR_TEMP_POS (3) + +#define BMP5_SHDW_SET_IIR_PRESS_MSK (0x20) +#define BMP5_SHDW_SET_IIR_PRESS_POS (5) + +#define BMP5_IIR_FLUSH_FORCED_EN_MSK (0x04) +#define BMP5_IIR_FLUSH_FORCED_EN_POS (2) + +/* Powermode */ +#define BMP5_POWERMODE_MSK (0x03) + +#define BMP5_DEEP_DISABLE_MSK (0x80) +#define BMP5_DEEP_DISABLE_POS (7) + +/* Fifo configurations */ +#define BMP5_FIFO_FRAME_SEL_MSK (0x03) + +/* NVM and Interrupt status asserted macros */ +#define BMP5_INT_ASSERTED_DRDY (0x01) + +/*! + * @brief Enumerator for powermode selection + */ +enum bmp5_powermode { + BMP5_POWERMODE_STANDBY, + BMP5_POWERMODE_NORMAL, + BMP5_POWERMODE_FORCED, + BMP5_POWERMODE_CONTINOUS, + BMP5_POWERMODE_DEEP_STANDBY +}; + +/*! + * @brief Enumerator for interface selection + */ +enum bmp5_intf { + BMP5_SPI_INTF, + BMP5_I2C_INTF, +}; + +/*! + * @brief BMP5 sensor data structure which comprises of temperature and pressure in floating point with data type as + * float for pressure and temperature. + */ +struct bmp5_sensor_data { + float pressure; + float temperature; +}; + +/* + * BMP581 internal constants and data structures. + */ +class IBMP581 +{ +public: + virtual ~IBMP581() = default; + + virtual int init() = 0; + + // read reg value + virtual uint8_t get_reg(uint8_t addr) = 0; + + // bulk read reg value + virtual int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) = 0; + + // write reg value + virtual int set_reg(uint8_t value, uint8_t addr) = 0; + + virtual uint32_t get_device_id() const = 0; + + virtual uint8_t get_device_address() const = 0; +}; + +class BMP581 : public I2CSPIDriver +{ +public: + BMP581(const I2CSPIDriverConfig &config, IBMP581 *interface); + virtual ~BMP581(); + + static I2CSPIDriverBase *instantiate(const I2CSPIDriverConfig &config, int runtime_instance); + static void print_usage(); + + virtual int init(); + + void print_status(); + + void RunImpl(); + + +private: + static constexpr uint8_t OVERSAMPLING_TEMPERATURE{BMP5_OVERSAMPLING_2X}; + static constexpr uint8_t OVERSAMPLING_PRESSURE{BMP5_OVERSAMPLING_32X}; + static constexpr uint8_t OUTPUT_DATA_RATE{BMP5_ODR_50_HZ}; + static constexpr uint8_t PRESSURE_ENABLE{BMP5_ENABLE}; + static constexpr uint8_t IIR_FILTER_COEFF_TEMPERATURE{BMP5_IIR_FILTER_COEFF_1}; + static constexpr uint8_t IIR_FILTER_COEFF_PRESSURE{BMP5_IIR_FILTER_COEFF_1}; + + static constexpr uint8_t INTERRUPT_MODE{BMP5_INT_MODE_PULSED}; + static constexpr uint8_t INTERRUPT_POLARITY{BMP5_INT_POL_ACTIVE_HIGH}; + static constexpr uint8_t INTERRUPT_DRIVE{BMP5_INT_OD_PUSHPULL}; + + uORB::PublicationMulti _sensor_baro_pub{ORB_ID(sensor_baro)}; + IBMP581 *_interface{nullptr}; + + unsigned _measure_interval{0}; // interval in microseconds needed to measure + + perf_counter_t _sample_perf; + perf_counter_t _measure_perf; + perf_counter_t _comms_errors; + + bool _collect_phase{false}; + + uint8_t _chip_id{0}; + uint8_t _chip_rev_id{0}; + + void start(); + int measure(); + int collect(); // get results and publish + + uint32_t get_measurement_time(); + + int soft_reset(); + int set_config(); + uint8_t get_interrupt_status(); + int configure_interrupt(); + int int_source_select(); + uint8_t get_power_mode(); + int set_power_mode(uint8_t power_mode); + uint8_t check_deepstandby_mode(); + int set_standby_mode(); + int set_deep_standby_mode(); + int set_osr_odr_press_config(); + int set_iir_config(); + int get_sensor_data(bmp5_sensor_data *sensor_data); +}; + + +/* interface factories */ +extern IBMP581 *bmp581_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode); +extern IBMP581 *bmp581_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency); +extern enum bmp5_intf intf; diff --git a/src/drivers/barometer/bmp581/bmp581_i2c.cpp b/src/drivers/barometer/bmp581/bmp581_i2c.cpp new file mode 100644 index 000000000000..3e4a0add5fa1 --- /dev/null +++ b/src/drivers/barometer/bmp581/bmp581_i2c.cpp @@ -0,0 +1,95 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file bmp581_i2c.cpp + * + * I2C interface for BMP581 + */ + +#include + +#include "bmp581.h" + +class BMP581_I2C: public device::I2C, public IBMP581 +{ +public: + BMP581_I2C(uint8_t bus, uint32_t device, int bus_frequency); + virtual ~BMP581_I2C() = default; + + int init(); + + uint8_t get_reg(uint8_t addr); + int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len); + int set_reg(uint8_t value, uint8_t addr); + + uint32_t get_device_id() const override { return device::I2C::get_device_id(); } + + uint8_t get_device_address() const override { return device::I2C::get_device_address(); } +}; + +IBMP581 *bmp581_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency) +{ + return new BMP581_I2C(busnum, device, bus_frequency); +} + +BMP581_I2C::BMP581_I2C(uint8_t bus, uint32_t device, int bus_frequency) : + I2C(DRV_BARO_DEVTYPE_BMP581, MODULE_NAME, bus, device, bus_frequency) +{ +} + +int BMP581_I2C::init() +{ + return I2C::init(); +} + +uint8_t BMP581_I2C::get_reg(uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr), 0}; + transfer(&cmd[0], 1, &cmd[1], 1); + + return cmd[1]; +} + +int BMP581_I2C::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) +{ + const uint8_t cmd = (uint8_t)(addr); + return transfer(&cmd, sizeof(cmd), buf, len); +} + +int BMP581_I2C::set_reg(uint8_t value, uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr), value}; + return transfer(cmd, sizeof(cmd), nullptr, 0); +} + diff --git a/src/drivers/barometer/bmp581/bmp581_main.cpp b/src/drivers/barometer/bmp581/bmp581_main.cpp new file mode 100644 index 000000000000..d92ba376ac89 --- /dev/null +++ b/src/drivers/barometer/bmp581/bmp581_main.cpp @@ -0,0 +1,127 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +#include "bmp581.h" + +enum bmp5_intf intf; + +void BMP581::print_usage() +{ + PRINT_MODULE_USAGE_NAME("bmp581", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("baro"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true); + PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x46); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +I2CSPIDriverBase *BMP581::instantiate(const I2CSPIDriverConfig &config, int runtime_instance) +{ + IBMP581 *interface = nullptr; + + if (config.bus_type == BOARD_I2C_BUS) { + interface = bmp581_i2c_interface(config.bus, config.i2c_address, config.bus_frequency); + intf = BMP5_I2C_INTF; + + } else if (config.bus_type == BOARD_SPI_BUS) { + interface = bmp581_spi_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode); + intf = BMP5_SPI_INTF; + } + + if (interface == nullptr) { + PX4_ERR("failed creating interface for bus %i (devid 0x%" PRIx32 ")", config.bus, config.spi_devid); + return nullptr; + } + + if (interface->init() != OK) { + delete interface; + PX4_DEBUG("no device on bus %i (devid 0x%" PRIx32 ")", config.bus, config.spi_devid); + return nullptr; + } + + BMP581 *dev = new BMP581(config, interface); + + if (dev == nullptr) { + delete interface; + return nullptr; + } + + if (dev->init() != OK) { + delete dev; + return nullptr; + } + + return dev; +} + + +extern "C" int bmp581_main(int argc, char *argv[]) +{ + using ThisDriver = BMP581; + BusCLIArguments cli{true, true}; + cli.i2c_address = 0x46; + cli.default_i2c_frequency = 100 * 1000; + cli.default_spi_frequency = 10 * 1000 * 1000; + + const char *verb = cli.parseDefaultArguments(argc, argv); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_BARO_DEVTYPE_BMP581); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; + + + + +} diff --git a/src/drivers/barometer/bmp581/bmp581_spi.cpp b/src/drivers/barometer/bmp581/bmp581_spi.cpp new file mode 100644 index 000000000000..cda214e623bd --- /dev/null +++ b/src/drivers/barometer/bmp581/bmp581_spi.cpp @@ -0,0 +1,102 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file bmp581_spi.cpp + * + * SPI interface for BMP 581 (NOTE: untested!) + */ + +#include + +#include "bmp581.h" + +/* SPI protocol address bits */ +#define DIR_READ (1<<7) //for set +#define DIR_WRITE ~(1<<7) //for clear + +class BMP581_SPI: public device::SPI, public IBMP581 +{ +public: + BMP581_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode); + virtual ~BMP581_SPI() = default; + + int init(); + + uint8_t get_reg(uint8_t addr); + int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len); + int set_reg(uint8_t value, uint8_t addr); + + uint32_t get_device_id() const override { return device::SPI::get_device_id(); } + + uint8_t get_device_address() const override { return device::SPI::get_device_address(); } +}; + +IBMP581 *bmp581_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode) +{ + return new BMP581_SPI(busnum, device, bus_frequency, spi_mode); +} + +BMP581_SPI::BMP581_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) : + SPI(DRV_BARO_DEVTYPE_BMP581, MODULE_NAME, bus, device, spi_mode, bus_frequency) +{ +} + +int BMP581_SPI::init() +{ + return SPI::init(); +} + +uint8_t BMP581_SPI::get_reg(uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr | DIR_READ), 0}; //set MSB bit + transfer(&cmd[0], &cmd[0], 2); + return cmd[1]; +} + +int BMP581_SPI::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) +{ + uint8_t cmd[len + 1] = {(uint8_t)(addr | DIR_READ)}; + int ret; + + ret = transfer(&cmd[0], &cmd[0], (len + 1)); + memcpy(buf, &cmd[1], len); + + return ret; +} + +int BMP581_SPI::set_reg(uint8_t value, uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr & DIR_WRITE), value}; //clear MSB bit + return transfer(&cmd[0], nullptr, 2); +} diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 604ab4946b29..378c92b6736c 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -151,6 +151,7 @@ #define DRV_ACC_DEVTYPE_BMI085 0x6C #define DRV_GYR_DEVTYPE_BMI085 0x6D #define DRV_BARO_DEVTYPE_BMP390 0x6E +#define DRV_BARO_DEVTYPE_BMP581 0x6F #define DRV_DIST_DEVTYPE_LL40LS 0x70 #define DRV_DIST_DEVTYPE_MAPPYDOT 0x71 From 59b96f4968690ff29fb3ad76462d649b38caa49f Mon Sep 17 00:00:00 2001 From: KonradRudin <98741601+KonradRudin@users.noreply.github.com> Date: Mon, 15 Jul 2024 10:42:43 +0200 Subject: [PATCH 481/652] tecs: fast descend: do not shut down throttle while still climbing (#23397) --- src/lib/tecs/TECS.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index 0c264706831d..4a6d3593e894 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -524,8 +524,13 @@ void TECSControl::_calcThrottleControl(float dt, const SpecificEnergyRates &spec float throttle_setpoint{param.throttle_min}; if (1.f - param.fast_descend < FLT_EPSILON) { - // During fast descend, we control airspeed over the pitch control loop and give minimal thrust. - throttle_setpoint = param.throttle_min; + // During fast descend, we control airspeed over the pitch control loop. Give minimal thrust as soon as we are descending + if (specific_energy_rates.spe_rate.estimate > 0) { // We have a positive altitude rate and are stil climbing + throttle_setpoint = param.throttle_trim; // Do not cut off throttle yet + + } else { + throttle_setpoint = param.throttle_min; + } } else { _calcThrottleControlUpdate(dt, limit, ste_rate, param, flag); From dc5f8118b06c9e88ff167cbb182caa881cf6ea84 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 12 Jul 2024 13:09:20 -0400 Subject: [PATCH 482/652] ekf2: range finder cleanup duplicate logic --- .../range_finder/range_height_control.cpp | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 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 94a44883eecf..ce8377e06baa 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 @@ -232,21 +232,20 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) void Ekf::updateRangeHagl(estimator_aid_source1d_s &aid_src) { - aid_src.observation = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance); - aid_src.innovation = getHagl() - aid_src.observation; + const float measurement = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance); + const float measurement_variance = getRngVar(); - const float observation_variance = getRngVar(); float innovation_variance; - sym::ComputeHaglInnovVar(P, observation_variance, &innovation_variance); + sym::ComputeHaglInnovVar(P, measurement_variance, &innovation_variance); const float innov_gate = math::max(_params.range_innov_gate, 1.f); updateAidSourceStatus(aid_src, - _range_sensor.getSampleAddress()->time_us, // sample timestamp - math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance), // observation - observation_variance, // observation variance - getHagl() - aid_src.observation, // innovation - innovation_variance, // innovation variance - math::max(_params.range_innov_gate, 1.f)); // innovation gate + _range_sensor.getSampleAddress()->time_us, // sample timestamp + measurement, // observation + measurement_variance, // observation variance + getHagl() - measurement, // innovation + innovation_variance, // innovation variance + innov_gate); // innovation gate // z special case if there is bad vertical acceleration data, then don't reject measurement, // but limit innovation to prevent spikes that could destabilise the filter From be551097e00f6d0d5a75c57e141ba5dafdd2aa53 Mon Sep 17 00:00:00 2001 From: Boris Date: Sun, 14 Jul 2024 00:04:50 +0200 Subject: [PATCH 483/652] mc_wind_estimator_tuning: Changed Quaternion package installed by requirements.txt --- .../EKF/python/tuning_tools/mc_wind_estimator/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/requirements.txt b/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/requirements.txt index 10d3fbc54990..42c95282314d 100644 --- a/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/requirements.txt +++ b/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator/requirements.txt @@ -1,6 +1,6 @@ matplotlib==3.5.1 numpy==1.22.2 pyulog==0.9.0 -quaternion==3.5.2.post4 +numpy-quaternion==2023.0.4 scipy==1.8.0 sympy==1.10.1 From a5a67315fd447d6703a89462510f6bcf27b650c1 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 12 Jul 2024 13:13:36 -0400 Subject: [PATCH 484/652] ekf2: optical flow magnitude check compensated - additionally don't use flow for reset if magnitude isn't acceptable --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 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 0e4b8b668ed6..89bbb6add0c4 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 @@ -71,8 +71,6 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) : _params.flow_qual_min_gnd; const bool is_quality_good = (flow_sample.quality >= min_quality); - const bool is_magnitude_good = flow_sample.flow_rate.isAllFinite() - && !flow_sample.flow_rate.longerThan(_flow_max_rate); bool is_tilt_good = true; @@ -120,6 +118,10 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) const bool is_within_max_sensor_dist = getHagl() <= _flow_max_distance; + const bool is_magnitude_good = flow_sample.flow_rate.isAllFinite() + && !flow_sample.flow_rate.longerThan(_flow_max_rate) + && !flow_compensated.longerThan(_flow_max_rate); + const bool continuing_conditions_passing = (_params.flow_ctrl == 1) && _control_status.flags.tilt_align && is_within_max_sensor_dist; @@ -142,7 +144,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) { + if (is_flow_required && is_quality_good && is_magnitude_good) { resetFlowFusion(); if (_control_status.flags.opt_flow_terrain && !isTerrainEstimateValid()) { From e03aef616c95d42a316fef54228512b62466715d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 15 Jul 2024 10:25:42 -0400 Subject: [PATCH 485/652] ekf2: add terrain/dist_bottom reset deltas (vehicle_local_position/vehicle_global_position) --- msg/VehicleGlobalPosition.msg | 2 ++ msg/VehicleLocalPosition.msg | 6 ++++- .../optical_flow/optical_flow_control.cpp | 18 +++++++++++-- .../range_finder/range_height_control.cpp | 18 +++++++++++-- src/modules/ekf2/EKF/ekf.h | 14 +++++++---- src/modules/ekf2/EKF/position_fusion.cpp | 13 +++++++++- src/modules/ekf2/EKF2.cpp | 6 ++++- src/modules/ekf2/EKF2Selector.cpp | 25 +++++++++++++++++++ src/modules/ekf2/EKF2Selector.hpp | 6 +++++ .../tasks/FlightTask/FlightTask.cpp | 7 +++++- .../tasks/FlightTask/FlightTask.hpp | 2 ++ 11 files changed, 104 insertions(+), 13 deletions(-) diff --git a/msg/VehicleGlobalPosition.msg b/msg/VehicleGlobalPosition.msg index c7d9ee78128a..e37155fe25a9 100644 --- a/msg/VehicleGlobalPosition.msg +++ b/msg/VehicleGlobalPosition.msg @@ -14,8 +14,10 @@ float32 alt # Altitude AMSL, (meters) float32 alt_ellipsoid # Altitude above ellipsoid, (meters) float32 delta_alt # Reset delta for altitude +float32 delta_terrain # Reset delta for terrain uint8 lat_lon_reset_counter # Counter for reset events on horizontal position coordinates uint8 alt_reset_counter # Counter for reset events on altitude +uint8 terrain_reset_counter # Counter for reset events on terrain float32 eph # Standard deviation of horizontal position error, (metres) float32 epv # Standard deviation of vertical position error, (metres) diff --git a/msg/VehicleLocalPosition.msg b/msg/VehicleLocalPosition.msg index 25551ab4fb70..0e74ac0f4bfc 100644 --- a/msg/VehicleLocalPosition.msg +++ b/msg/VehicleLocalPosition.msg @@ -55,9 +55,13 @@ float64 ref_lon # Reference point longitude, (degrees) float32 ref_alt # Reference altitude AMSL, (metres) # Distance to surface +bool dist_bottom_valid # true if distance to bottom surface is valid float32 dist_bottom # Distance from from bottom surface to ground, (metres) float32 dist_bottom_var # terrain estimate variance (m^2) -bool dist_bottom_valid # true if distance to bottom surface is valid + +float32 delta_dist_bottom # Amount of vertical shift of dist bottom estimate in latest reset [m] +uint8 dist_bottom_reset_counter # Index of latest dist bottom estimate reset + uint8 dist_bottom_sensor_bitfield # bitfield indicating what type of sensor is used to estimate dist_bottom uint8 DIST_BOTTOM_SENSOR_NONE = 0 uint8 DIST_BOTTOM_SENSOR_RANGE = 1 # (1 << 0) a range sensor is used to estimate dist_bottom field 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 89bbb6add0c4..a6c0569ac7d4 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 @@ -219,15 +219,29 @@ void Ekf::resetFlowFusion() void Ekf::resetTerrainToFlow() { ECL_INFO("reset hagl to flow"); + // TODO: use the flow data - _state.terrain = fmaxf(0.0f, _state.pos(2)); + const float new_terrain = fmaxf(0.0f, _state.pos(2)); + const float delta_terrain = new_terrain - _state.terrain; + _state.terrain = new_terrain; P.uncorrelateCovarianceSetVariance(State::terrain.idx, 100.f); - _terrain_vpos_reset_counter++; resetAidSourceStatusZeroInnovation(_aid_src_optical_flow); _innov_check_fail_status.flags.reject_optflow_X = false; _innov_check_fail_status.flags.reject_optflow_Y = false; + + + // record the state change + if (_state_reset_status.reset_count.hagl == _state_reset_count_prev.hagl) { + _state_reset_status.hagl_change = delta_terrain; + + } else { + // there's already a reset this update, accumulate total delta + _state_reset_status.hagl_change += delta_terrain; + } + + _state_reset_status.reset_count.hagl++; } void Ekf::stopFlowFusion() 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 ce8377e06baa..541dede81973 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 @@ -267,9 +267,23 @@ float Ekf::getRngVar() const void Ekf::resetTerrainToRng(estimator_aid_source1d_s &aid_src) { - _state.terrain = _state.pos(2) + aid_src.observation; + const float new_terrain = _state.pos(2) + aid_src.observation; + const float delta_terrain = new_terrain - _state.terrain; + + _state.terrain = new_terrain; P.uncorrelateCovarianceSetVariance(State::terrain.idx, aid_src.observation_variance); - _terrain_vpos_reset_counter++; + + // record the state change + if (_state_reset_status.reset_count.hagl == _state_reset_count_prev.hagl) { + _state_reset_status.hagl_change = delta_terrain; + + } else { + // there's already a reset this update, accumulate total delta + _state_reset_status.hagl_change += delta_terrain; + } + + _state_reset_status.reset_count.hagl++; + aid_src.time_last_fuse = _time_delayed_us; } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 85ea4a7625bc..f23f514fd6f8 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -104,9 +104,6 @@ class Ekf final : public EstimatorInterface float getTerrainVertPos() const { return _state.terrain; }; float getHagl() const { return _state.terrain - _state.pos(2); } - // get the number of times the vertical terrain position has been reset - uint8_t getTerrainVertPosResetCounter() const { return _terrain_vpos_reset_counter; }; - // get the terrain variance float getTerrainVariance() const { return P(State::terrain.idx, State::terrain.idx); } @@ -358,6 +355,13 @@ class Ekf final : public EstimatorInterface *counter = _state_reset_status.reset_count.posD; } + uint8_t get_hagl_reset_count() const { return _state_reset_status.reset_count.hagl; } + void get_hagl_reset(float *delta, uint8_t *counter) const + { + *delta = _state_reset_status.hagl_change; + *counter = _state_reset_status.reset_count.hagl; + } + // return the amount the local vertical velocity changed in the last reset and the number of reset events uint8_t get_velD_reset_count() const { return _state_reset_status.reset_count.velD; } void get_velD_reset(float *delta, uint8_t *counter) const @@ -551,6 +555,7 @@ class Ekf final : public EstimatorInterface uint8_t posNE{0}; ///< number of horizontal position reset events (allow to wrap if count exceeds 255) uint8_t posD{0}; ///< number of vertical position reset events (allow to wrap if count exceeds 255) uint8_t quat{0}; ///< number of quaternion reset events (allow to wrap if count exceeds 255) + uint8_t hagl{0}; ///< number of height above ground level reset events (allow to wrap if count exceeds 255) }; struct StateResets { @@ -559,6 +564,7 @@ class Ekf final : public EstimatorInterface Vector2f posNE_change; ///< North, East position change due to last reset (m) float posD_change; ///< Down position change due to last reset (m) Quatf quat_change; ///< quaternion delta due to last reset - multiply pre-reset quaternion by this to get post-reset quaternion + float hagl_change; ///< Height above ground level change due to last reset (m) StateResetCounts reset_count{}; }; @@ -599,8 +605,6 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_TERRAIN) // Terrain height state estimation - uint8_t _terrain_vpos_reset_counter{0}; ///< number of times _terrain_vpos has been reset - float _last_on_ground_posD{0.0f}; ///< last vertical position when the in_air status was false (m) #endif // CONFIG_EKF2_TERRAIN diff --git a/src/modules/ekf2/EKF/position_fusion.cpp b/src/modules/ekf2/EKF/position_fusion.cpp index 6cc503de7323..cf8e7de04b33 100644 --- a/src/modules/ekf2/EKF/position_fusion.cpp +++ b/src/modules/ekf2/EKF/position_fusion.cpp @@ -167,7 +167,18 @@ void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_v #if defined(CONFIG_EKF2_TERRAIN) _state.terrain += delta_z; -#endif + + // record the state change + if (_state_reset_status.reset_count.hagl == _state_reset_count_prev.hagl) { + _state_reset_status.hagl_change = delta_z; + + } else { + // there's already a reset this update, accumulate total delta + _state_reset_status.hagl_change += delta_z; + } + + _state_reset_status.reset_count.hagl++; +#endif // CONFIG_EKF2_TERRAIN // Reset the timout timer _time_last_hgt_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index cee124db0c25..44656a206737 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1191,6 +1191,9 @@ void EKF2::PublishGlobalPosition(const hrt_abstime ×tamp) global_pos.terrain_alt_valid = true; } + float delta_hagl = 0.f; + _ekf.get_hagl_reset(&delta_hagl, &global_pos.terrain_reset_counter); + global_pos.delta_terrain = -delta_z; #endif // CONFIG_EKF2_TERRAIN global_pos.dead_reckoning = _ekf.control_status_flags().inertial_dead_reckoning @@ -1619,9 +1622,10 @@ void EKF2::PublishLocalPosition(const hrt_abstime ×tamp) #if defined(CONFIG_EKF2_TERRAIN) // Distance to bottom surface (ground) in meters, must be positive + lpos.dist_bottom_valid = _ekf.isTerrainEstimateValid(); lpos.dist_bottom = math::max(_ekf.getHagl(), 0.f); lpos.dist_bottom_var = _ekf.getTerrainVariance(); - lpos.dist_bottom_valid = _ekf.isTerrainEstimateValid(); + _ekf.get_hagl_reset(&lpos.delta_dist_bottom, &lpos.dist_bottom_reset_counter); lpos.dist_bottom_sensor_bitfield = vehicle_local_position_s::DIST_BOTTOM_SENSOR_NONE; diff --git a/src/modules/ekf2/EKF2Selector.cpp b/src/modules/ekf2/EKF2Selector.cpp index 99fb863eed96..f5f67e2cded9 100644 --- a/src/modules/ekf2/EKF2Selector.cpp +++ b/src/modules/ekf2/EKF2Selector.cpp @@ -479,18 +479,32 @@ void EKF2Selector::PublishVehicleLocalPosition() _delta_heading_reset = matrix::wrap_pi(local_position.heading - _local_position_last.heading); } + // HAGL (dist_bottom) reset + if (!instance_change + && (local_position.dist_bottom_reset_counter == _local_position_last.dist_bottom_reset_counter + 1)) { + ++_hagl_reset_counter; + _delta_hagl_reset = local_position.delta_dist_bottom; + + } else if (instance_change + || (local_position.dist_bottom_reset_counter != _local_position_last.dist_bottom_reset_counter)) { + ++_hagl_reset_counter; + _delta_hagl_reset = local_position.dist_bottom - _local_position_last.dist_bottom; + } + } else { _xy_reset_counter = local_position.xy_reset_counter; _z_reset_counter = local_position.z_reset_counter; _vxy_reset_counter = local_position.vxy_reset_counter; _vz_reset_counter = local_position.vz_reset_counter; _heading_reset_counter = local_position.heading_reset_counter; + _hagl_reset_counter = local_position.dist_bottom_reset_counter; _delta_xy_reset = Vector2f{local_position.delta_xy}; _delta_z_reset = local_position.delta_z; _delta_vxy_reset = Vector2f{local_position.delta_vxy}; _delta_vz_reset = local_position.delta_vz; _delta_heading_reset = local_position.delta_heading; + _delta_hagl_reset = local_position.delta_dist_bottom; } bool publish = true; @@ -513,6 +527,7 @@ void EKF2Selector::PublishVehicleLocalPosition() local_position.vxy_reset_counter = _vxy_reset_counter; local_position.vz_reset_counter = _vz_reset_counter; local_position.heading_reset_counter = _heading_reset_counter; + local_position.dist_bottom_reset_counter = _hagl_reset_counter; _delta_xy_reset.copyTo(local_position.delta_xy); local_position.delta_z = _delta_z_reset; @@ -612,6 +627,16 @@ void EKF2Selector::PublishVehicleGlobalPosition() _delta_alt_reset = global_position.delta_alt - _global_position_last.delta_alt; } + // terrain reset + if (!instance_change && (global_position.terrain_reset_counter == _global_position_last.terrain_reset_counter + 1)) { + ++_terrain_reset_counter; + _delta_terrain_reset = global_position.delta_terrain; + + } else if (instance_change || (global_position.terrain_reset_counter != _global_position_last.terrain_reset_counter)) { + ++_terrain_reset_counter; + _delta_terrain_reset = global_position.delta_terrain - _global_position_last.delta_terrain; + } + } else { _lat_lon_reset_counter = global_position.lat_lon_reset_counter; _alt_reset_counter = global_position.alt_reset_counter; diff --git a/src/modules/ekf2/EKF2Selector.hpp b/src/modules/ekf2/EKF2Selector.hpp index 6507233bd3e8..535af97e6d38 100644 --- a/src/modules/ekf2/EKF2Selector.hpp +++ b/src/modules/ekf2/EKF2Selector.hpp @@ -202,11 +202,14 @@ class EKF2Selector : public ModuleParams, public px4::ScheduledWorkItem matrix::Vector2f _delta_vxy_reset{}; float _delta_vz_reset{0.f}; float _delta_heading_reset{0}; + float _delta_hagl_reset{0.f}; + uint8_t _xy_reset_counter{0}; uint8_t _z_reset_counter{0}; uint8_t _vxy_reset_counter{0}; uint8_t _vz_reset_counter{0}; uint8_t _heading_reset_counter{0}; + uint8_t _hagl_reset_counter{0}; // vehicle_odometry vehicle_odometry_s _odometry_last{}; @@ -217,8 +220,11 @@ class EKF2Selector : public ModuleParams, public px4::ScheduledWorkItem double _delta_lat_reset{0}; double _delta_lon_reset{0}; float _delta_alt_reset{0.f}; + float _delta_terrain_reset{0.f}; + uint8_t _lat_lon_reset_counter{0}; uint8_t _alt_reset_counter{0}; + uint8_t _terrain_reset_counter{0}; // wind estimate wind_s _wind_last{}; diff --git a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp index 063b78dcf6c6..55b587d270d9 100644 --- a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp +++ b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp @@ -63,6 +63,11 @@ void FlightTask::_checkEkfResetCounters() _reset_counters.z = _sub_vehicle_local_position.get().z_reset_counter; } + if (_sub_vehicle_local_position.get().dist_bottom_reset_counter != _reset_counters.hagl) { + _ekfResetHandlerHagl(_sub_vehicle_local_position.get().delta_dist_bottom); + _reset_counters.hagl = _sub_vehicle_local_position.get().dist_bottom_reset_counter; + } + if (_sub_vehicle_local_position.get().vz_reset_counter != _reset_counters.vz) { _ekfResetHandlerVelocityZ(_sub_vehicle_local_position.get().delta_vz); _reset_counters.vz = _sub_vehicle_local_position.get().vz_reset_counter; @@ -138,7 +143,7 @@ void FlightTask::_evaluateVehicleLocalPosition() // distance to bottom if (_sub_vehicle_local_position.get().dist_bottom_valid && PX4_ISFINITE(_sub_vehicle_local_position.get().dist_bottom)) { - _dist_to_bottom = _sub_vehicle_local_position.get().dist_bottom; + _dist_to_bottom = _sub_vehicle_local_position.get().dist_bottom; } // global frame reference coordinates to enable conversions diff --git a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp index 7e938bb0a9d7..6ee861f3cda1 100644 --- a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp +++ b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp @@ -61,6 +61,7 @@ struct ekf_reset_counters_s { uint8_t z; uint8_t vz; uint8_t heading; + uint8_t hagl; }; class FlightTask : public ModuleParams @@ -191,6 +192,7 @@ class FlightTask : public ModuleParams virtual void _ekfResetHandlerPositionXY(const matrix::Vector2f &delta_xy) {}; virtual void _ekfResetHandlerVelocityXY(const matrix::Vector2f &delta_vxy) {}; virtual void _ekfResetHandlerPositionZ(float delta_z) {}; + virtual void _ekfResetHandlerHagl(float delta_hagl) {}; virtual void _ekfResetHandlerVelocityZ(float delta_vz) {}; virtual void _ekfResetHandlerHeading(float delta_psi) {}; From 9bbfc8715eb241194d8edbb924b08d4e73cb956d Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Mon, 15 Jul 2024 12:39:00 +0000 Subject: [PATCH 486/652] Update submodule mavlink to latest Mon Jul 15 12:39:00 UTC 2024 - mavlink in PX4/Firmware (abcf9ca6f0aadc91b203342db689f07630ec0e3a): https://github.com/mavlink/mavlink/commit/da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3 - mavlink current upstream: https://github.com/mavlink/mavlink/commit/d65952bacc02c4a5a1ed8249be73e6a66fa800ab - Changes: https://github.com/mavlink/mavlink/compare/da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3...d65952bacc02c4a5a1ed8249be73e6a66fa800ab d65952ba 2024-07-05 Peter Barker - common.xml: correct description of GLOBAL_POSIITON_INT.relative_alt frame (#2131) 5fc2ff8e 2024-06-26 Hamish Willee - Add multiplier field to docs, if present (#2125) a13d2317 2024-06-26 Roman Bapst - Added MAV_CMD_EXTERNAL_WIND_ESTIMATE to development (#2122) d8af87fd 2024-06-19 jokalode - Update common.xml (#2116) --- src/modules/mavlink/mavlink | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index da3223ff9380..d65952bacc02 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3 +Subproject commit d65952bacc02c4a5a1ed8249be73e6a66fa800ab From 177613eb68731990f3d0c620aad0dbef22216eb3 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 10 Jul 2024 13:09:33 -0400 Subject: [PATCH 487/652] ekf2: GNSS velocity control should own vertical velocity reset if height faiing - GNSS height control using the velocity sample directly is ignoring potential position offsets --- .../EKF/aid_sources/gnss/gnss_height_control.cpp | 9 --------- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 16 +++++++++++----- 2 files changed, 11 insertions(+), 14 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index ff04cc3b3977..c141d415eec5 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -108,15 +108,6 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) resetVerticalPositionTo(-(measurement - bias_est.getBias()), measurement_var); bias_est.setBias(_state.pos(2) + measurement); - // reset vertical velocity - if (PX4_ISFINITE(gps_sample.vel(2)) && (_params.gnss_ctrl & static_cast(GnssCtrl::VEL))) { - // use 1.5 as a typical ratio of vacc/hacc - resetVerticalVelocityTo(gps_sample.vel(2), sq(math::max(1.5f * gps_sample.sacc, _params.gps_vel_noise))); - - } else { - resetVerticalVelocityToZero(); - } - aid_src.time_last_fuse = _time_delayed_us; } else if (is_fusion_failing) { diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index 83f7ef624d64..b8440595aecd 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -132,17 +132,23 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) } if (do_vel_pos_reset) { - ECL_WARN("GPS fusion timeout, resetting velocity / position"); + ECL_WARN("GPS fusion timeout, resetting"); + } - if (gnss_vel_enabled) { + if (gnss_vel_enabled) { + if (do_vel_pos_reset) { resetVelocityToGnss(_aid_src_gnss_vel); - } - if (gnss_pos_enabled) { - resetHorizontalPositionToGnss(_aid_src_gnss_pos); + } else if (isHeightResetRequired()) { + // reset vertical velocity if height is failing + resetVerticalVelocityTo(_aid_src_gnss_vel.observation[2], _aid_src_gnss_vel.observation_variance[2]); } } + if (gnss_pos_enabled && do_vel_pos_reset) { + resetHorizontalPositionToGnss(_aid_src_gnss_pos); + } + } else { stopGpsFusion(); } From 40349fa3dc72b626504e256ed136f7b3f71f4f17 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 10 Jul 2024 13:20:16 -0400 Subject: [PATCH 488/652] ekf2: EV velocity control should own vertical velocity reset if height failing --- .../external_vision/ev_height_control.cpp | 28 ------------------- .../external_vision/ev_vel_control.cpp | 11 ++++++++ 2 files changed, 11 insertions(+), 28 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp index 0684536ae587..e7b6f13f1181 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp @@ -149,34 +149,6 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp resetVerticalPositionTo(measurement - bias_est.getBias(), measurement_var); bias_est.setBias(-_state.pos(2) + measurement); - // reset vertical velocity - if (ev_sample.vel.isAllFinite() && (_params.ev_ctrl & static_cast(EvCtrl::VEL))) { - - // correct velocity for offset relative to IMU - const Vector3f angular_velocity = (imu_sample.delta_ang / imu_sample.delta_ang_dt) - _state.gyro_bias; - const Vector3f vel_offset_body = angular_velocity % pos_offset_body; - const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body; - - switch (ev_sample.vel_frame) { - case VelocityFrame::LOCAL_FRAME_NED: - case VelocityFrame::LOCAL_FRAME_FRD: { - const Vector3f reset_vel = ev_sample.vel - vel_offset_earth; - resetVerticalVelocityTo(reset_vel(2), math::max(ev_sample.velocity_var(2), sq(_params.ev_vel_noise))); - } - break; - - case VelocityFrame::BODY_FRAME_FRD: { - const Vector3f reset_vel = _R_to_earth * (ev_sample.vel - vel_offset_body); - const Matrix3f reset_vel_cov = _R_to_earth * matrix::diag(ev_sample.velocity_var) * _R_to_earth.transpose(); - resetVerticalVelocityTo(reset_vel(2), math::max(reset_vel_cov(2, 2), sq(_params.ev_vel_noise))); - } - break; - } - - } else { - resetVerticalVelocityToZero(); - } - aid_src.time_last_fuse = _time_delayed_us; } else if (is_fusion_failing) { diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp index a5ba562cad23..b94f24f45e9f 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel_control.cpp @@ -212,6 +212,17 @@ void Ekf::controlEvVelFusion(const imuSample &imu_sample, const extVisionSample stopEvVelFusion(); } + + } else if (isHeightResetRequired()) { + // reset vertical velocity if height is failing + if (ev_sample.vel_frame == VelocityFrame::BODY_FRAME_FRD) { + const Vector3f measurement_ekf_frame = _R_to_earth * measurement; + const Vector3f measurement_var_ekf_frame = rotateVarianceToEkf(measurement_var); + resetVerticalVelocityTo(measurement_ekf_frame(2), measurement_var_ekf_frame(2)); + + } else { + resetVerticalVelocityTo(measurement(2), measurement_var(2)); + } } } else { From 80ee622f77371f6af1344310f2a5b99e3b87bf9b Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 10 Jul 2024 13:24:35 -0400 Subject: [PATCH 489/652] ekf2: baro only reset vz as a last resort --- .../ekf2/EKF/aid_sources/barometer/baro_height_control.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index c6c6f220de70..264c826738f2 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -134,8 +134,10 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) resetVerticalPositionTo(-(_baro_lpf.getState() - bias_est.getBias()), measurement_var); bias_est.setBias(_state.pos(2) + _baro_lpf.getState()); - // reset vertical velocity - resetVerticalVelocityToZero(); + // reset vertical velocity if no valid sources available + if (!isVerticalVelocityAidingActive()) { + resetVerticalVelocityToZero(); + } aid_src.time_last_fuse = imu_sample.time_us; From 8e5f28f834bc0063a36c98485a33bebdff602b7f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 10 Jul 2024 13:25:14 -0400 Subject: [PATCH 490/652] ekf2: rng only reset vz as a last resort --- .../EKF/aid_sources/range_finder/range_height_control.cpp | 6 ++++-- src/modules/ekf2/test/test_EKF_terrain.cpp | 4 ++-- 2 files changed, 6 insertions(+), 4 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 541dede81973..6c33d4db639a 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 @@ -180,8 +180,10 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) _information_events.flags.reset_hgt_to_rng = true; resetVerticalPositionTo(-(aid_src.observation - _state.terrain)); - // reset vertical velocity - resetVerticalVelocityToZero(); + // reset vertical velocity if no valid sources available + if (!isVerticalVelocityAidingActive()) { + resetVerticalVelocityToZero(); + } aid_src.time_last_fuse = imu_sample.time_us; diff --git a/src/modules/ekf2/test/test_EKF_terrain.cpp b/src/modules/ekf2/test/test_EKF_terrain.cpp index c3c2ad6714a9..5549eb8030d0 100644 --- a/src/modules/ekf2/test/test_EKF_terrain.cpp +++ b/src/modules/ekf2/test/test_EKF_terrain.cpp @@ -207,9 +207,9 @@ TEST_F(EkfTerrainTest, testHeightReset) const float new_baro_height = _sensor_simulator._baro.getData() + 50.f; _sensor_simulator._baro.setData(new_baro_height); _sensor_simulator.stopGps(); // prevent from switching to GNSS height - _sensor_simulator.runSeconds(6); + _sensor_simulator.runSeconds(10); - // THEN: a height reset occured and the estimated distance to the ground remains constant + // THEN: a height reset occurred and the estimated distance to the ground remains constant reset_logging_checker.capturePostResetState(); EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); EXPECT_NEAR(estimated_distance_to_ground, _ekf->getHagl(), 1e-3f); From 9d6c2baa908026af000cbdbf0680621f2b0fa777 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 15 Jul 2024 14:38:45 +0200 Subject: [PATCH 491/652] ekf2-flow: only allow flow when in range Also, as the flow makes the link between range and horizontal velocity, only allow it to start if at least one of the two is known. Otherwise the EKF will struggle to estimate both values at the same time. --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 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 a6c0569ac7d4..390a957992bf 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 @@ -116,7 +116,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && (_control_status.flags.inertial_dead_reckoning // is doing inertial dead-reckoning so must constrain drift urgently || isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)); - const bool is_within_max_sensor_dist = getHagl() <= _flow_max_distance; + const bool is_within_sensor_dist = (getHagl() >= _flow_min_distance) && (getHagl() <= _flow_max_distance); const bool is_magnitude_good = flow_sample.flow_rate.isAllFinite() && !flow_sample.flow_rate.longerThan(_flow_max_rate) @@ -124,12 +124,13 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) const bool continuing_conditions_passing = (_params.flow_ctrl == 1) && _control_status.flags.tilt_align - && is_within_max_sensor_dist; + && is_within_sensor_dist; const bool starting_conditions_passing = continuing_conditions_passing && is_quality_good && is_magnitude_good && is_tilt_good + && (isTerrainEstimateValid() || isHorizontalAidingActive()) && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching // If the height is relative to the ground, terrain height cannot be observed. From 1cd7d54170439378a77e17bb7c5c44275a1de2a9 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 15 Jul 2024 12:50:51 -0400 Subject: [PATCH 492/652] ekf2: consolidate GNSS yaw in gnss_yaw_control.cpp and fix naming (GPS->GNSS) Co-authored-by: Mathieu Bresciani --- msg/EstimatorStatusFlags.msg | 4 +- .../checks/estimatorCheck.cpp | 2 +- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- ...ps_yaw_fusion.cpp => gnss_yaw_control.cpp} | 130 +++++++++++++++--- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 106 +------------- .../aid_sources/magnetometer/mag_control.cpp | 2 +- .../zero_innovation_heading_update.cpp | 2 +- src/modules/ekf2/EKF/common.h | 6 +- src/modules/ekf2/EKF/ekf.h | 16 +-- src/modules/ekf2/EKF/ekf_helper.cpp | 2 +- src/modules/ekf2/EKF/estimator_interface.cpp | 2 +- src/modules/ekf2/EKF/estimator_interface.h | 2 +- src/modules/ekf2/EKF2.cpp | 4 +- src/modules/ekf2/test/CMakeLists.txt | 2 +- .../test/sensor_simulator/ekf_wrapper.cpp | 2 +- src/modules/ekf2/test/test_EKF_basics.cpp | 4 +- ..._EKF_gps_yaw.cpp => test_EKF_gnss_yaw.cpp} | 0 18 files changed, 144 insertions(+), 146 deletions(-) rename src/modules/ekf2/EKF/aid_sources/gnss/{gps_yaw_fusion.cpp => gnss_yaw_control.cpp} (57%) rename src/modules/ekf2/test/{test_EKF_gps_yaw.cpp => test_EKF_gnss_yaw.cpp} (100%) diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index 2d6a7c39a171..23e6e15fd48f 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -26,12 +26,12 @@ bool cs_mag_fault # 18 - true when the magnetometer has been declare bool cs_fuse_aspd # 19 - true when airspeed measurements are being fused bool cs_gnd_effect # 20 - true when protection from ground effect induced static pressure rise is active bool cs_rng_stuck # 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough -bool cs_gps_yaw # 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended +bool cs_gnss_yaw # 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended bool cs_mag_aligned_in_flight # 23 - true when the in-flight mag field alignment has been completed bool cs_ev_vel # 24 - true when local frame velocity data fusion from external vision measurements is intended bool cs_synthetic_mag_z # 25 - true when we are using a synthesized measurement for the magnetometer Z component bool cs_vehicle_at_rest # 26 - true when the vehicle is at rest -bool cs_gps_yaw_fault # 27 - true when the GNSS heading has been declared faulty and is no longer being used +bool cs_gnss_yaw_fault # 27 - true when the GNSS heading has been declared faulty and is no longer being used bool cs_rng_fault # 28 - true when the range finder has been declared faulty and is no longer being used bool cs_inertial_dead_reckoning # 29 - true if we are no longer fusing measurements that constrain horizontal velocity drift bool cs_wind_dead_reckoning # 30 - true if we are navigationg reliant on wind relative measurements diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 7441e76f08c2..d1bc06a74218 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -623,7 +623,7 @@ void EstimatorChecks::checkEstimatorStatusFlags(const Context &context, Report & } } - if (estimator_status_flags.cs_gps_yaw_fault) { + if (estimator_status_flags.cs_gnss_yaw_fault) { /* EVENT * @description * Land now diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 3f5d9d142f36..c4d0d1162584 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -175,7 +175,7 @@ if(CONFIG_EKF2_GNSS) ) if(CONFIG_EKF2_GNSS_YAW) - list(APPEND EKF_SRCS EKF/aid_sources/gnss/gps_yaw_fusion.cpp) + list(APPEND EKF_SRCS EKF/aid_sources/gnss/gnss_yaw_control.cpp) endif() list(APPEND EKF_LIBS yaw_estimator) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 1134d1942b12..f404817ef4e1 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -96,7 +96,7 @@ if(CONFIG_EKF2_GNSS) ) if(CONFIG_EKF2_GNSS_YAW) - list(APPEND EKF_SRCS aid_sources/gnss/gps_yaw_fusion.cpp) + list(APPEND EKF_SRCS aid_sources/gnss/gnss_yaw_control.cpp) endif() add_subdirectory(yaw_estimator) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_yaw_control.cpp similarity index 57% rename from src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp rename to src/modules/ekf2/EKF/aid_sources/gnss/gnss_yaw_control.cpp index d66fbac7c6f3..456691635a00 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_yaw_control.cpp @@ -32,37 +32,122 @@ ****************************************************************************/ /** - * @file gps_yaw_fusion.cpp - * Definition of functions required to use yaw obtained from GPS dual antenna measurements. - * Equations generated using EKF/python/ekf_derivation/main.py - * - * @author Paul Riseborough + * @file gnss_yaw_control.cpp + * Definition of functions required to use yaw obtained from GNSS dual antenna measurements. + * Equations generated using src/modules/ekf2/EKF/python/ekf_derivation/derivation.py * */ #include "ekf.h" -#include #include #include -void Ekf::updateGpsYaw(const gnssSample &gps_sample) +#include + +void Ekf::controlGnssYawFusion(const gnssSample &gnss_sample) +{ + if (!(_params.gnss_ctrl & static_cast(GnssCtrl::YAW)) + || _control_status.flags.gnss_yaw_fault) { + + stopGnssYawFusion(); + return; + } + + const bool is_new_data_available = PX4_ISFINITE(gnss_sample.yaw); + + if (is_new_data_available) { + + updateGnssYaw(gnss_sample); + + const bool continuing_conditions_passing = _control_status.flags.tilt_align; + + const bool is_gnss_yaw_data_intermittent = !isNewestSampleRecent(_time_last_gnss_yaw_buffer_push, + 2 * GNSS_YAW_MAX_INTERVAL); + + const bool starting_conditions_passing = continuing_conditions_passing + && _gps_checks_passed + && !is_gnss_yaw_data_intermittent + && !_gps_intermittent; + + if (_control_status.flags.gnss_yaw) { + if (continuing_conditions_passing) { + + fuseGnssYaw(gnss_sample.yaw_offset); + + const bool is_fusion_failing = isTimedOut(_aid_src_gnss_yaw.time_last_fuse, _params.reset_timeout_max); + + if (is_fusion_failing) { + stopGnssYawFusion(); + + // Before takeoff, we do not want to continue to rely on the current heading + // if we had to stop the fusion + if (!_control_status.flags.in_air) { + ECL_INFO("clearing yaw alignment"); + _control_status.flags.yaw_align = false; + } + } + + } else { + // Stop GNSS yaw fusion but do not declare it faulty + stopGnssYawFusion(); + } + + } else { + if (starting_conditions_passing) { + // Try to activate GNSS yaw fusion + const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; + + if (!_control_status.flags.in_air + || !_control_status.flags.yaw_align + || not_using_ne_aiding) { + + // Reset before starting the fusion + if (resetYawToGnss(gnss_sample.yaw, gnss_sample.yaw_offset)) { + + resetAidSourceStatusZeroInnovation(_aid_src_gnss_yaw); + + _control_status.flags.gnss_yaw = true; + _control_status.flags.yaw_align = true; + } + + } else if (!_aid_src_gnss_yaw.innovation_rejected) { + // Do not force a reset but wait for the consistency check to pass + _control_status.flags.gnss_yaw = true; + fuseGnssYaw(gnss_sample.yaw_offset); + } + + if (_control_status.flags.gnss_yaw) { + ECL_INFO("starting GNSS yaw fusion"); + } + } + } + + } else if (_control_status.flags.gnss_yaw + && !isNewestSampleRecent(_time_last_gnss_yaw_buffer_push, _params.reset_timeout_max)) { + + // No yaw data in the message anymore. Stop until it comes back. + stopGnssYawFusion(); + } +} + +void Ekf::updateGnssYaw(const gnssSample &gnss_sample) { // calculate the observed yaw angle of antenna array, converting a from body to antenna yaw measurement - const float measured_hdg = wrap_pi(gps_sample.yaw + gps_sample.yaw_offset); + const float measured_hdg = wrap_pi(gnss_sample.yaw + gnss_sample.yaw_offset); - const float yaw_acc = PX4_ISFINITE(gps_sample.yaw_acc) ? gps_sample.yaw_acc : 0.f; - const float R_YAW = sq(fmaxf(yaw_acc, _params.gps_heading_noise)); + const float yaw_acc = PX4_ISFINITE(gnss_sample.yaw_acc) ? gnss_sample.yaw_acc : 0.f; + const float R_YAW = sq(fmaxf(yaw_acc, _params.gnss_heading_noise)); float heading_pred; float heading_innov_var; VectorState H; - sym::ComputeGnssYawPredInnovVarAndH(_state.vector(), P, gps_sample.yaw_offset, R_YAW, FLT_EPSILON, + sym::ComputeGnssYawPredInnovVarAndH(_state.vector(), P, gnss_sample.yaw_offset, R_YAW, FLT_EPSILON, &heading_pred, &heading_innov_var, &H); updateAidSourceStatus(_aid_src_gnss_yaw, - gps_sample.time_us, // sample timestamp + gnss_sample.time_us, // sample timestamp measured_hdg, // observation R_YAW, // observation variance wrap_pi(heading_pred - measured_hdg), // innovation @@ -70,7 +155,7 @@ void Ekf::updateGpsYaw(const gnssSample &gps_sample) math::max(_params.heading_innov_gate, 1.f)); // innovation gate } -void Ekf::fuseGpsYaw(float antenna_yaw_offset) +void Ekf::fuseGnssYaw(float antenna_yaw_offset) { auto &aid_src = _aid_src_gnss_yaw; @@ -99,7 +184,8 @@ void Ekf::fuseGpsYaw(float antenna_yaw_offset) // we reinitialise the covariance matrix and abort this fusion step initialiseCovariance(); - ECL_ERR("GPS yaw numerical error - covariance reset"); + ECL_ERR("GNSS yaw numerical error - covariance reset"); + stopGnssYawFusion(); return; } @@ -129,7 +215,7 @@ void Ekf::fuseGpsYaw(float antenna_yaw_offset) } } -bool Ekf::resetYawToGps(const float gnss_yaw, const float gnss_yaw_offset) +bool Ekf::resetYawToGnss(const float gnss_yaw, const float gnss_yaw_offset) { // define the predicted antenna array vector and rotate into earth frame const Vector3f ant_vec_bf = {cosf(gnss_yaw_offset), sinf(gnss_yaw_offset), 0.0f}; @@ -140,11 +226,21 @@ bool Ekf::resetYawToGps(const float gnss_yaw, const float gnss_yaw_offset) return false; } - // GPS yaw measurement is alreday compensated for antenna offset in the driver + // GNSS yaw measurement is already compensated for antenna offset in the driver const float measured_yaw = gnss_yaw; - const float yaw_variance = sq(fmaxf(_params.gps_heading_noise, 1.e-2f)); + const float yaw_variance = sq(fmaxf(_params.gnss_heading_noise, 1.e-2f)); resetQuatStateYaw(measured_yaw, yaw_variance); return true; } + +void Ekf::stopGnssYawFusion() +{ + if (_control_status.flags.gnss_yaw) { + + _control_status.flags.gnss_yaw = false; + + ECL_INFO("stopping GNSS yaw fusion"); + } +} diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index b8440595aecd..7bfb2e283107 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -98,7 +98,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) if (_gps_data_ready) { #if defined(CONFIG_EKF2_GNSS_YAW) const gnssSample &gnss_sample = _gps_sample_delayed; - controlGpsYawFusion(gnss_sample); + controlGnssYawFusion(gnss_sample); #endif // CONFIG_EKF2_GNSS_YAW controlGnssYawEstimator(_aid_src_gnss_vel); @@ -285,8 +285,8 @@ bool Ekf::tryYawEmergencyReset() #if defined(CONFIG_EKF2_GNSS_YAW) - if (_control_status.flags.gps_yaw) { - _control_status.flags.gps_yaw_fault = true; + if (_control_status.flags.gnss_yaw) { + _control_status.flags.gnss_yaw_fault = true; } #endif // CONFIG_EKF2_GNSS_YAW @@ -354,104 +354,6 @@ bool Ekf::shouldResetGpsFusion() const return (is_reset_required || is_inflight_nav_failure); } -#if defined(CONFIG_EKF2_GNSS_YAW) -void Ekf::controlGpsYawFusion(const gnssSample &gps_sample) -{ - if (!(_params.gnss_ctrl & static_cast(GnssCtrl::YAW)) - || _control_status.flags.gps_yaw_fault) { - - stopGpsYawFusion(); - return; - } - - const bool is_new_data_available = PX4_ISFINITE(gps_sample.yaw); - - if (is_new_data_available) { - - updateGpsYaw(gps_sample); - - const bool continuing_conditions_passing = _control_status.flags.tilt_align; - - const bool is_gps_yaw_data_intermittent = !isNewestSampleRecent(_time_last_gps_yaw_buffer_push, - 2 * GNSS_YAW_MAX_INTERVAL); - - const bool starting_conditions_passing = continuing_conditions_passing - && _gps_checks_passed - && !is_gps_yaw_data_intermittent - && !_gps_intermittent; - - if (_control_status.flags.gps_yaw) { - if (continuing_conditions_passing) { - - fuseGpsYaw(gps_sample.yaw_offset); - - const bool is_fusion_failing = isTimedOut(_aid_src_gnss_yaw.time_last_fuse, _params.reset_timeout_max); - - if (is_fusion_failing) { - stopGpsYawFusion(); - - // Before takeoff, we do not want to continue to rely on the current heading - // if we had to stop the fusion - if (!_control_status.flags.in_air) { - ECL_INFO("clearing yaw alignment"); - _control_status.flags.yaw_align = false; - } - } - - } else { - // Stop GPS yaw fusion but do not declare it faulty - stopGpsYawFusion(); - } - - } else { - if (starting_conditions_passing) { - // Try to activate GPS yaw fusion - const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; - - if (!_control_status.flags.in_air - || !_control_status.flags.yaw_align - || not_using_ne_aiding) { - - // Reset before starting the fusion - if (resetYawToGps(gps_sample.yaw, gps_sample.yaw_offset)) { - - resetAidSourceStatusZeroInnovation(_aid_src_gnss_yaw); - - _control_status.flags.gps_yaw = true; - _control_status.flags.yaw_align = true; - } - - } else if (!_aid_src_gnss_yaw.innovation_rejected) { - // Do not force a reset but wait for the consistency check to pass - _control_status.flags.gps_yaw = true; - fuseGpsYaw(gps_sample.yaw_offset); - } - - if (_control_status.flags.gps_yaw) { - ECL_INFO("starting GPS yaw fusion"); - } - } - } - - } else if (_control_status.flags.gps_yaw - && !isNewestSampleRecent(_time_last_gps_yaw_buffer_push, _params.reset_timeout_max)) { - - // No yaw data in the message anymore. Stop until it comes back. - stopGpsYawFusion(); - } -} - -void Ekf::stopGpsYawFusion() -{ - if (_control_status.flags.gps_yaw) { - - _control_status.flags.gps_yaw = false; - - ECL_INFO("stopping GPS yaw fusion"); - } -} -#endif // CONFIG_EKF2_GNSS_YAW - void Ekf::stopGpsFusion() { if (_control_status.flags.gps) { @@ -465,7 +367,7 @@ void Ekf::stopGpsFusion() stopGpsHgtFusion(); #if defined(CONFIG_EKF2_GNSS_YAW) - stopGpsYawFusion(); + stopGnssYawFusion(); #endif // CONFIG_EKF2_GNSS_YAW _yawEstimator.reset(); 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 2dab0da57eaf..35dd869e1fb7 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -153,7 +153,7 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) && !_control_status.flags.mag_fault && !_control_status.flags.mag_field_disturbed && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; + && !_control_status.flags.gnss_yaw; _control_status.flags.mag_3D = common_conditions_passing && (_params.mag_fusion_type == MagFuseType::AUTO) diff --git a/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp b/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp index 3c0a2c1d6cf7..fded4cfbcc13 100644 --- a/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp +++ b/src/modules/ekf2/EKF/aid_sources/zero_innovation_heading_update.cpp @@ -41,7 +41,7 @@ void Ekf::controlZeroInnovationHeadingUpdate() { const bool yaw_aiding = _control_status.flags.mag_hdg || _control_status.flags.mag_3D - || _control_status.flags.ev_yaw || _control_status.flags.gps_yaw; + || _control_status.flags.ev_yaw || _control_status.flags.gnss_yaw; // fuse zero innovation at a limited rate if the yaw variance is too large if (!yaw_aiding diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 05610bca5858..da07028edce8 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -338,7 +338,7 @@ struct parameters { # if defined(CONFIG_EKF2_GNSS_YAW) // GNSS heading fusion - float gps_heading_noise{0.1f}; ///< measurement noise standard deviation used for GNSS heading fusion (rad) + float gnss_heading_noise{0.1f}; ///< measurement noise standard deviation used for GNSS heading fusion (rad) # endif // CONFIG_EKF2_GNSS_YAW // Parameters used to control when yaw is reset to the EKF-GSF yaw estimator value @@ -580,7 +580,7 @@ uint64_t gnd_effect : 1; ///< 20 - true when protection from ground effect induced static pressure rise is active uint64_t rng_stuck : 1; ///< 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough -uint64_t gps_yaw : +uint64_t gnss_yaw : 1; ///< 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended uint64_t mag_aligned_in_flight : 1; ///< 23 - true when the in-flight mag field alignment has been completed uint64_t ev_vel : @@ -588,7 +588,7 @@ uint64_t ev_vel : uint64_t synthetic_mag_z : 1; ///< 25 - true when we are using a synthesized measurement for the magnetometer Z component uint64_t vehicle_at_rest : 1; ///< 26 - true when the vehicle is at rest -uint64_t gps_yaw_fault : +uint64_t gnss_yaw_fault : 1; ///< 27 - true when the GNSS heading has been declared faulty and is no longer being used uint64_t rng_fault : 1; ///< 28 - true when the range finder has been declared faulty and is no longer being used diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index f23f514fd6f8..7070c71bf363 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -144,7 +144,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_GNSS_YAW) - if (_control_status.flags.gps_yaw) { + if (_control_status.flags.gnss_yaw) { return _aid_src_gnss_yaw.innovation; } @@ -173,7 +173,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_GNSS_YAW) - if (_control_status.flags.gps_yaw) { + if (_control_status.flags.gnss_yaw) { return _aid_src_gnss_yaw.innovation_variance; } @@ -202,7 +202,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_GNSS_YAW) - if (_control_status.flags.gps_yaw) { + if (_control_status.flags.gnss_yaw) { return _aid_src_gnss_yaw.test_ratio; } @@ -995,17 +995,17 @@ class Ekf final : public EstimatorInterface void resetGpsDriftCheckFilters(); # if defined(CONFIG_EKF2_GNSS_YAW) - void controlGpsYawFusion(const gnssSample &gps_sample); - void stopGpsYawFusion(); + void controlGnssYawFusion(const gnssSample &gps_sample); + void stopGnssYawFusion(); // fuse the yaw angle obtained from a dual antenna GPS unit - void fuseGpsYaw(float antenna_yaw_offset); + void fuseGnssYaw(float antenna_yaw_offset); // reset the quaternions states using the yaw angle obtained from a dual antenna GPS unit // return true if the reset was successful - bool resetYawToGps(float gnss_yaw, float gnss_yaw_offset); + bool resetYawToGnss(float gnss_yaw, float gnss_yaw_offset); - void updateGpsYaw(const gnssSample &gps_sample); + void updateGnssYaw(const gnssSample &gps_sample); # endif // CONFIG_EKF2_GNSS_YAW diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index e44d6c0bf61b..02675d1f746f 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -333,7 +333,7 @@ float Ekf::getHeadingInnovationTestRatio() const #if defined(CONFIG_EKF2_GNSS_YAW) - if (_control_status.flags.gps_yaw) { + if (_control_status.flags.gnss_yaw) { test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_yaw.test_ratio_filtered)); } diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index d4a579f5b8cf..f7a6c70dec39 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -193,7 +193,7 @@ void EstimatorInterface::setGpsData(const gnssSample &gnss_sample) #if defined(CONFIG_EKF2_GNSS_YAW) if (PX4_ISFINITE(gnss_sample.yaw)) { - _time_last_gps_yaw_buffer_push = _time_latest_us; + _time_last_gnss_yaw_buffer_push = _time_latest_us; } #endif // CONFIG_EKF2_GNSS_YAW diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 4477f17b5164..75e65268304d 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -397,7 +397,7 @@ class EstimatorInterface # if defined(CONFIG_EKF2_GNSS_YAW) // innovation consistency check monitoring ratios - uint64_t _time_last_gps_yaw_buffer_push{0}; + uint64_t _time_last_gnss_yaw_buffer_push{0}; # endif // CONFIG_EKF2_GNSS_YAW #endif // CONFIG_EKF2_GNSS diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 44656a206737..7f4c8d6516c3 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1912,12 +1912,12 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_fuse_aspd = _ekf.control_status_flags().fuse_aspd; status_flags.cs_gnd_effect = _ekf.control_status_flags().gnd_effect; status_flags.cs_rng_stuck = _ekf.control_status_flags().rng_stuck; - status_flags.cs_gps_yaw = _ekf.control_status_flags().gps_yaw; + status_flags.cs_gnss_yaw = _ekf.control_status_flags().gnss_yaw; status_flags.cs_mag_aligned_in_flight = _ekf.control_status_flags().mag_aligned_in_flight; status_flags.cs_ev_vel = _ekf.control_status_flags().ev_vel; status_flags.cs_synthetic_mag_z = _ekf.control_status_flags().synthetic_mag_z; status_flags.cs_vehicle_at_rest = _ekf.control_status_flags().vehicle_at_rest; - status_flags.cs_gps_yaw_fault = _ekf.control_status_flags().gps_yaw_fault; + status_flags.cs_gnss_yaw_fault = _ekf.control_status_flags().gnss_yaw_fault; status_flags.cs_rng_fault = _ekf.control_status_flags().rng_fault; status_flags.cs_inertial_dead_reckoning = _ekf.control_status_flags().inertial_dead_reckoning; status_flags.cs_wind_dead_reckoning = _ekf.control_status_flags().wind_dead_reckoning; diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index 424a2a208a6e..800b568d96d7 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -45,7 +45,7 @@ px4_add_unit_gtest(SRC test_EKF_flow_generated.cpp LINKLIBS ecl_EKF ecl_sensor_s px4_add_unit_gtest(SRC test_EKF_gyroscope.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_fusionLogic.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gps.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) -px4_add_unit_gtest(SRC test_EKF_gps_yaw.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_gnss_yaw.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_gnss_yaw_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_height_fusion.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_imuSampling.cpp LINKLIBS ecl_EKF ecl_sensor_sim) diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp index 26a1dd73c605..9fd62885e36b 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp @@ -132,7 +132,7 @@ void EkfWrapper::disableGpsHeadingFusion() bool EkfWrapper::isIntendingGpsHeadingFusion() const { - return _ekf->control_status_flags().gps_yaw; + return _ekf->control_status_flags().gnss_yaw; } void EkfWrapper::enableFlowFusion() diff --git a/src/modules/ekf2/test/test_EKF_basics.cpp b/src/modules/ekf2/test/test_EKF_basics.cpp index c7a8ffa83643..e95443344235 100644 --- a/src/modules/ekf2/test/test_EKF_basics.cpp +++ b/src/modules/ekf2/test/test_EKF_basics.cpp @@ -123,7 +123,7 @@ TEST_F(EkfBasicsTest, initialControlMode) EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_fault); EXPECT_EQ(0, (int) _ekf->control_status_flags().gnd_effect); EXPECT_EQ(0, (int) _ekf->control_status_flags().rng_stuck); - EXPECT_EQ(0, (int) _ekf->control_status_flags().gps_yaw); + EXPECT_EQ(0, (int) _ekf->control_status_flags().gnss_yaw); EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_aligned_in_flight); EXPECT_EQ(0, (int) _ekf->control_status_flags().ev_vel); EXPECT_EQ(0, (int) _ekf->control_status_flags().synthetic_mag_z); @@ -178,7 +178,7 @@ TEST_F(EkfBasicsTest, gpsFusion) EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_fault); EXPECT_EQ(0, (int) _ekf->control_status_flags().gnd_effect); EXPECT_EQ(0, (int) _ekf->control_status_flags().rng_stuck); - EXPECT_EQ(0, (int) _ekf->control_status_flags().gps_yaw); + EXPECT_EQ(0, (int) _ekf->control_status_flags().gnss_yaw); EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_aligned_in_flight); EXPECT_EQ(0, (int) _ekf->control_status_flags().ev_vel); EXPECT_EQ(0, (int) _ekf->control_status_flags().synthetic_mag_z); diff --git a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp b/src/modules/ekf2/test/test_EKF_gnss_yaw.cpp similarity index 100% rename from src/modules/ekf2/test/test_EKF_gps_yaw.cpp rename to src/modules/ekf2/test/test_EKF_gnss_yaw.cpp From 48f1687d3a5711db635d06ac7a4986176f90ecd4 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 15 Jul 2024 15:50:02 -0400 Subject: [PATCH 493/652] ekf2: cleanup legacy EKF solution_status_flags --- src/modules/ekf2/EKF/common.h | 22 -------- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF/ekf_helper.cpp | 80 ++++++++++++++++++----------- src/modules/ekf2/EKF2.cpp | 2 +- 4 files changed, 52 insertions(+), 54 deletions(-) diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index da07028edce8..2e317cd71fac 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -613,28 +613,6 @@ uint64_t mag_heading_consistent : uint64_t value; }; -// Mavlink bitmask containing state of estimator solution -union ekf_solution_status_u { - struct { - uint16_t attitude : 1; ///< 0 - True if the attitude estimate is good - uint16_t velocity_horiz : 1; ///< 1 - True if the horizontal velocity estimate is good - uint16_t velocity_vert : 1; ///< 2 - True if the vertical velocity estimate is good - uint16_t pos_horiz_rel : 1; ///< 3 - True if the horizontal position (relative) estimate is good - uint16_t pos_horiz_abs : 1; ///< 4 - True if the horizontal position (absolute) estimate is good - uint16_t pos_vert_abs : 1; ///< 5 - True if the vertical position (absolute) estimate is good - uint16_t pos_vert_agl : 1; ///< 6 - True if the vertical position (above ground) estimate is good -uint16_t const_pos_mode : - 1; ///< 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) -uint16_t pred_pos_horiz_rel : - 1; ///< 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate -uint16_t pred_pos_horiz_abs : - 1; ///< 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate - uint16_t gps_glitch : 1; ///< 10 - True if the EKF has detected a GPS glitch - uint16_t accel_error : 1; ///< 11 - True if the EKF has detected bad accelerometer data - } flags; - uint16_t value; -}; - // define structure used to communicate information events union information_event_status_u { struct { diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 7070c71bf363..8d5cdc4e3482 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -407,7 +407,7 @@ class Ekf final : public EstimatorInterface float getHeightAboveGroundInnovationTestRatio() const; // return a bitmask integer that describes which state estimates are valid - void get_ekf_soln_status(uint16_t *status) const; + uint16_t get_ekf_soln_status() const; HeightSensor getHeightSensorRef() const { return _height_sensor_ref; } diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 02675d1f746f..8d25dfffdbd6 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -531,50 +531,70 @@ float Ekf::getHeightAboveGroundInnovationTestRatio() const return NAN; } -void Ekf::get_ekf_soln_status(uint16_t *status) const +uint16_t Ekf::get_ekf_soln_status() const { - ekf_solution_status_u soln_status{}; - // TODO: Is this accurate enough? + // LEGACY Mavlink bitmask containing state of estimator solution (see Mavlink ESTIMATOR_STATUS_FLAGS) + union ekf_solution_status_u { + struct { + uint16_t attitude : 1; + uint16_t velocity_horiz : 1; + uint16_t velocity_vert : 1; + uint16_t pos_horiz_rel : 1; + uint16_t pos_horiz_abs : 1; + uint16_t pos_vert_abs : 1; + uint16_t pos_vert_agl : 1; + uint16_t const_pos_mode : 1; + uint16_t pred_pos_horiz_rel : 1; + uint16_t pred_pos_horiz_abs : 1; + uint16_t gps_glitch : 1; + uint16_t accel_error : 1; + } flags; + uint16_t value; + } soln_status{}; + + // 1 ESTIMATOR_ATTITUDE True if the attitude estimate is good soln_status.flags.attitude = attitude_valid(); - soln_status.flags.velocity_horiz = (isHorizontalAidingActive() || (_control_status.flags.fuse_beta - && _control_status.flags.fuse_aspd)) && (_fault_status.value == 0); - soln_status.flags.velocity_vert = (_control_status.flags.baro_hgt || _control_status.flags.ev_hgt - || _control_status.flags.gps_hgt || _control_status.flags.rng_hgt) && (_fault_status.value == 0); - soln_status.flags.pos_horiz_rel = (_control_status.flags.gps || _control_status.flags.ev_pos - || _control_status.flags.opt_flow) && (_fault_status.value == 0); - soln_status.flags.pos_horiz_abs = (_control_status.flags.gps || _control_status.flags.ev_pos) - && (_fault_status.value == 0); - soln_status.flags.pos_vert_abs = soln_status.flags.velocity_vert; + + // 2 ESTIMATOR_VELOCITY_HORIZ True if the horizontal velocity estimate is good + soln_status.flags.velocity_horiz = local_position_is_valid(); + + // 4 ESTIMATOR_VELOCITY_VERT True if the vertical velocity estimate is good + soln_status.flags.velocity_vert = isLocalVerticalVelocityValid() || isLocalVerticalPositionValid(); + + // 8 ESTIMATOR_POS_HORIZ_REL True if the horizontal position (relative) estimate is good + soln_status.flags.pos_horiz_rel = local_position_is_valid(); + + // 16 ESTIMATOR_POS_HORIZ_ABS True if the horizontal position (absolute) estimate is good + soln_status.flags.pos_horiz_abs = global_position_is_valid(); + + // 32 ESTIMATOR_POS_VERT_ABS True if the vertical position (absolute) estimate is good + soln_status.flags.pos_vert_abs = isVerticalAidingActive(); + + // 64 ESTIMATOR_POS_VERT_AGL True if the vertical position (above ground) estimate is good #if defined(CONFIG_EKF2_TERRAIN) soln_status.flags.pos_vert_agl = isTerrainEstimateValid(); #endif // CONFIG_EKF2_TERRAIN - soln_status.flags.const_pos_mode = !soln_status.flags.velocity_horiz; - soln_status.flags.pred_pos_horiz_rel = soln_status.flags.pos_horiz_rel; - soln_status.flags.pred_pos_horiz_abs = soln_status.flags.pos_horiz_abs; - bool mag_innov_good = true; + // 128 ESTIMATOR_CONST_POS_MODE True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) + soln_status.flags.const_pos_mode = _control_status.flags.fake_pos || _control_status.flags.vehicle_at_rest; -#if defined(CONFIG_EKF2_MAGNETOMETER) + // 256 ESTIMATOR_PRED_POS_HORIZ_REL True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate + soln_status.flags.pred_pos_horiz_rel = isHorizontalAidingActive(); - if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { - if (Vector3f(_aid_src_mag.test_ratio).max() < 1.f) { - mag_innov_good = false; - } - } - -#endif // CONFIG_EKF2_MAGNETOMETER + // 512 ESTIMATOR_PRED_POS_HORIZ_ABS True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate + soln_status.flags.pred_pos_horiz_abs = _control_status.flags.gps || _control_status.flags.aux_gpos; + // 1024 ESTIMATOR_GPS_GLITCH True if the EKF has detected a GPS glitch #if defined(CONFIG_EKF2_GNSS) const bool gps_vel_innov_bad = Vector3f(_aid_src_gnss_vel.test_ratio).max() > 1.f; const bool gps_pos_innov_bad = Vector2f(_aid_src_gnss_pos.test_ratio).max() > 1.f; - - soln_status.flags.gps_glitch = (gps_vel_innov_bad || gps_pos_innov_bad) && mag_innov_good; -#else - (void)mag_innov_good; + soln_status.flags.gps_glitch = (gps_vel_innov_bad || gps_pos_innov_bad); #endif // CONFIG_EKF2_GNSS - soln_status.flags.accel_error = _fault_status.flags.bad_acc_vertical; - *status = soln_status.value; + // 2048 ESTIMATOR_ACCEL_ERROR True if the EKF has detected bad accelerometer data + soln_status.flags.accel_error = _fault_status.flags.bad_acc_vertical || _fault_status.flags.bad_acc_clipping; + + return soln_status.value; } void Ekf::fuse(const VectorState &K, float innovation) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 7f4c8d6516c3..005e303e74b8 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1825,7 +1825,7 @@ void EKF2::PublishStatus(const hrt_abstime ×tamp) status.beta_test_ratio = _ekf.getSyntheticSideslipInnovationTestRatio(); _ekf.get_ekf_lpos_accuracy(&status.pos_horiz_accuracy, &status.pos_vert_accuracy); - _ekf.get_ekf_soln_status(&status.solution_status_flags); + status.solution_status_flags = _ekf.get_ekf_soln_status(); // reset counters status.reset_count_vel_ne = _ekf.state_reset_status().reset_count.velNE; From fe5a07a96de2085bfb22a3e2339d906f48d398cf Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Mon, 13 May 2024 17:23:55 -0600 Subject: [PATCH 494/652] gz: added x500_lidar model for publishing obstacle_distance --- .../init.d-posix/airframes/4013_gz_x500_lidar | 10 +++ .../init.d-posix/airframes/CMakeLists.txt | 1 + platforms/posix/Debug/launch_sitl.json.in | 1 + src/modules/simulation/gz_bridge/GZBridge.cpp | 89 +++++++++++++++++++ src/modules/simulation/gz_bridge/GZBridge.hpp | 4 + 5 files changed, 105 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4013_gz_x500_lidar diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4013_gz_x500_lidar b/ROMFS/px4fmu_common/init.d-posix/airframes/4013_gz_x500_lidar new file mode 100644 index 000000000000..a316310abe42 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4013_gz_x500_lidar @@ -0,0 +1,10 @@ +#!/bin/sh +# +# @name Gazebo x500 lidar +# +# @type Quadrotor +# + +PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_lidar} + +. ${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 33d6d857e8c2..9235b2e66340 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -84,6 +84,7 @@ px4_add_romfs_files( 4010_gz_x500_mono_cam 4011_gz_lawnmower 4012_gz_rover_ackermann + 4013_gz_x500_lidar 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/platforms/posix/Debug/launch_sitl.json.in b/platforms/posix/Debug/launch_sitl.json.in index 2fb0a4bc6b0e..6703f4290346 100644 --- a/platforms/posix/Debug/launch_sitl.json.in +++ b/platforms/posix/Debug/launch_sitl.json.in @@ -223,6 +223,7 @@ "options": [ "x500", "x500_depth", + "x500_lidar", "rc_cessna", "standard_vtol", ], diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 56c6d028a0cd..117040555a41 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -196,6 +196,14 @@ int GZBridge::init() return PX4_ERROR; } + // Laser Scan + std::string laser_scan_topic = "/world/" + _world_name + "/model/" + _model_name + "/link/link/sensor/lidar_2d_v2/scan"; + + if (!_node.Subscribe(laser_scan_topic, &GZBridge::laserScanCallback, this)) { + PX4_ERR("failed to subscribe to %s", laser_scan_topic.c_str()); + return PX4_ERROR; + } + #if 0 // Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name + @@ -741,6 +749,87 @@ void GZBridge::navSatCallback(const gz::msgs::NavSat &nav_sat) pthread_mutex_unlock(&_node_mutex); } +void GZBridge::laserScanCallback(const gz::msgs::LaserScan &scan) +{ + static constexpr int SECTOR_SIZE_DEG = 10; // PX4 Collision Prevention only has 36 sectors of 10 degrees each + + double angle_min_deg = scan.angle_min() * 180 / M_PI; + double angle_step_deg = scan.angle_step() * 180 / M_PI; + + int samples_per_sector = std::round(SECTOR_SIZE_DEG / angle_step_deg); + int number_of_sectors = scan.ranges_size() / samples_per_sector; + + std::vector ds_array(number_of_sectors, UINT16_MAX); + + // Downsample -- take average of samples per sector + for (int i = 0; i < number_of_sectors; i++) { + + double sum = 0; + + int samples_used_in_sector = 0; + + for (int j = 0; j < samples_per_sector; j++) { + + double distance = scan.ranges()[i * samples_per_sector + j]; + + // inf values mean no object + if (isinf(distance)) { + continue; + } + + sum += distance; + samples_used_in_sector++; + } + + // If all samples in a sector are inf then it means the sector is clear + if (samples_used_in_sector == 0) { + ds_array[i] = scan.range_max(); + + } else { + ds_array[i] = sum / samples_used_in_sector; + } + } + + // Publish to uORB + obstacle_distance_s obs {}; + + // Initialize unknown + for (auto &i : obs.distances) { + i = UINT16_MAX; + } + + obs.timestamp = hrt_absolute_time(); + obs.frame = obstacle_distance_s::MAV_FRAME_BODY_FRD; + obs.sensor_type = obstacle_distance_s::MAV_DISTANCE_SENSOR_LASER; + obs.min_distance = static_cast(scan.range_min() * 100.); + obs.max_distance = static_cast(scan.range_max() * 100.); + obs.angle_offset = static_cast(angle_min_deg); + obs.increment = static_cast(SECTOR_SIZE_DEG); + + // Map samples in FOV into sectors in ObstacleDistance + int index = 0; + + // Iterate in reverse because array is FLU and we need FRD + for (std::vector::reverse_iterator i = ds_array.rbegin(); i != ds_array.rend(); ++i) { + + uint16_t distance_cm = (*i) * 100.; + + if (distance_cm >= obs.max_distance) { + obs.distances[index] = obs.max_distance + 1; + + } else if (distance_cm < obs.min_distance) { + obs.distances[index] = 0; + + } else { + obs.distances[index] = distance_cm; + } + + index++; + } + + _obstacle_distance_pub.publish(obs); +} + void GZBridge::rotateQuaternion(gz::math::Quaterniond &q_FRD_to_NED, const gz::math::Quaterniond q_FLU_to_ENU) { // FLU (ROS) to FRD (PX4) static rotation diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index 6d2e2670a15e..8a832f7961b2 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -58,6 +58,7 @@ #include #include #include +#include #include #include @@ -67,6 +68,7 @@ #include #include #include +#include using namespace time_literals; @@ -106,6 +108,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void poseInfoCallback(const gz::msgs::Pose_V &pose); void odometryCallback(const gz::msgs::OdometryWithCovariance &odometry); void navSatCallback(const gz::msgs::NavSat &nav_sat); + void laserScanCallback(const gz::msgs::LaserScan &scan); /** * @@ -121,6 +124,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; //uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; + uORB::Publication _obstacle_distance_pub{ORB_ID(obstacle_distance)}; uORB::Publication _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)}; uORB::Publication _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)}; uORB::Publication _gpos_ground_truth_pub{ORB_ID(vehicle_global_position_groundtruth)}; From aa8a9e3a06293122e8d2fc5741de1f08a64d3b1a Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Thu, 30 May 2024 12:00:22 -0600 Subject: [PATCH 495/652] laser scan subscription optional --- src/modules/simulation/gz_bridge/GZBridge.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 117040555a41..3464c628694c 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -196,12 +196,11 @@ int GZBridge::init() return PX4_ERROR; } - // Laser Scan + // Laser Scan: optional std::string laser_scan_topic = "/world/" + _world_name + "/model/" + _model_name + "/link/link/sensor/lidar_2d_v2/scan"; if (!_node.Subscribe(laser_scan_topic, &GZBridge::laserScanCallback, this)) { - PX4_ERR("failed to subscribe to %s", laser_scan_topic.c_str()); - return PX4_ERROR; + PX4_WARN("failed to subscribe to %s", laser_scan_topic.c_str()); } #if 0 From 76cf54c9485c5e90062d2492d130eebb91c72000 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Fri, 12 Jul 2024 15:15:17 +0200 Subject: [PATCH 496/652] adapted UORB Description to match MAVLink --- msg/ObstacleDistance.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/ObstacleDistance.msg b/msg/ObstacleDistance.msg index e3c4963ab24e..e4a07d1cacc9 100644 --- a/msg/ObstacleDistance.msg +++ b/msg/ObstacleDistance.msg @@ -19,6 +19,6 @@ float32 increment # Angular width in degrees of each array element. uint16 min_distance # Minimum distance the sensor can measure in centimeters. uint16 max_distance # Maximum distance the sensor can measure in centimeters. -float32 angle_offset # Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive values are offsets to the right. +float32 angle_offset # Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. # TOPICS obstacle_distance obstacle_distance_fused From 13b62a74d6010e3dab43b0b15b37bdb96844f3a1 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 12 Jul 2024 13:25:24 -0400 Subject: [PATCH 497/652] ekf2: optical flow adjust jacobian epsilon to avoid numerical issues - in the generated code there's a 1 / eps^2 term if the height and terrain estimates are the same --- .../ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp | 3 ++- .../ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp | 3 ++- 2 files changed, 4 insertions(+), 2 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 390a957992bf..3c4c031f316c 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 @@ -89,8 +89,9 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) // calculate the optical flow observation variance const float R_LOS = calcOptFlowMeasVar(flow_sample); + const float epsilon = 1e-3f; Vector2f innov_var; - sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, R_LOS, FLT_EPSILON, &innov_var, &H); + sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, R_LOS, epsilon, &innov_var, &H); // run the innovation consistency check and record result updateAidSourceStatus(_aid_src_optical_flow, diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 531a7b56d09e..860c6eca5eec 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -72,7 +72,8 @@ bool Ekf::fuseOptFlow(VectorState &H, const bool update_terrain) } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) const float R_LOS = _aid_src_optical_flow.observation_variance[1]; - sym::ComputeFlowYInnovVarAndH(state_vector, P, R_LOS, FLT_EPSILON, &_aid_src_optical_flow.innovation_variance[1], &H); + const float epsilon = 1e-3f; + sym::ComputeFlowYInnovVarAndH(state_vector, P, R_LOS, epsilon, &_aid_src_optical_flow.innovation_variance[1], &H); // recalculate the innovation using the updated state const Vector3f flow_gyro_corrected = _flow_sample_delayed.gyro_rate - _flow_gyro_bias; From 397ff4a102053eeca697423b2def56985ab214d1 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 12 Jul 2024 13:29:23 -0400 Subject: [PATCH 498/652] ekf2: sideslip symforce increase epsilon to avoid 1/e^2 numerical issues --- .../ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp index 6a9ab3442220..f7365b733370 100644 --- a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp @@ -82,10 +82,10 @@ void Ekf::updateSideslip(estimator_aid_source1d_s &aid_src) const { float observation = 0.f; const float R = math::max(sq(_params.beta_noise), sq(0.01f)); // observation noise variance - + const float epsilon = 1e-3f; float innov; float innov_var; - sym::ComputeSideslipInnovAndInnovVar(_state.vector(), P, R, FLT_EPSILON, &innov, &innov_var); + sym::ComputeSideslipInnovAndInnovVar(_state.vector(), P, R, epsilon, &innov, &innov_var); updateAidSourceStatus(aid_src, _time_delayed_us, // sample timestamp @@ -130,10 +130,11 @@ void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) _fault_status.flags.bad_sideslip = false; + const float epsilon = 1e-3f; VectorState H; // Observation jacobian VectorState K; // Kalman gain vector - sym::ComputeSideslipHAndK(_state.vector(), P, sideslip.innovation_variance, FLT_EPSILON, &H, &K); + sym::ComputeSideslipHAndK(_state.vector(), P, sideslip.innovation_variance, epsilon, &H, &K); if (update_wind_only) { const Vector2f K_wind = K.slice(State::wind_vel.idx, 0); From b48aca10a0efeb7a66dbb5862af88f599bb70d05 Mon Sep 17 00:00:00 2001 From: bazooka joe Date: Thu, 20 Jun 2024 15:20:15 +0300 Subject: [PATCH 499/652] mc_position_control: avoid calculating arw if not needed --- .../PositionControl/PositionControl.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/modules/mc_pos_control/PositionControl/PositionControl.cpp b/src/modules/mc_pos_control/PositionControl/PositionControl.cpp index 0cf632c04359..72ae5a4a3173 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControl.cpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControl.cpp @@ -185,15 +185,15 @@ void PositionControl::_velocityControl(const float dt) // Use tracking Anti-Windup for horizontal direction: during saturation, the integrator is used to unsaturate the output // see Anti-Reset Windup for PID controllers, L.Rundqwist, 1990 const Vector2f acc_sp_xy_produced = Vector2f(_thr_sp) * (CONSTANTS_ONE_G / _hover_thrust); - const float arw_gain = 2.f / _gain_vel_p(0); // The produced acceleration can be greater or smaller than the desired acceleration due to the saturations and the actual vertical thrust (computed independently). // The ARW loop needs to run if the signal is saturated only. - const Vector2f acc_sp_xy = _acc_sp.xy(); - const Vector2f acc_limited_xy = (acc_sp_xy.norm_squared() > acc_sp_xy_produced.norm_squared()) - ? acc_sp_xy_produced - : acc_sp_xy; - vel_error.xy() = Vector2f(vel_error) - arw_gain * (acc_sp_xy - acc_limited_xy); + if (_acc_sp.xy().norm_squared() > acc_sp_xy_produced.norm_squared()) { + const float arw_gain = 2.f / _gain_vel_p(0); + const Vector2f acc_sp_xy = _acc_sp.xy(); + + vel_error.xy() = Vector2f(vel_error) - arw_gain * (acc_sp_xy - acc_sp_xy_produced); + } // Make sure integral doesn't get NAN ControlMath::setZeroIfNanVector3f(vel_error); From 20c0d3a096a22347a7b0541ec6f0d462ce6405b5 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 15 Jul 2024 17:35:03 +0200 Subject: [PATCH 500/652] ekf2: enable all GNSS checks by default --- src/modules/ekf2/module.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 848ca02a9bf6..7edba1721ceb 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -149,7 +149,7 @@ parameters: 7: Max horizontal speed (EKF2_REQ_HDRIFT) 8: Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) 9: Spoofing check - default: 245 + default: 1023 min: 0 max: 1023 EKF2_REQ_EPH: From f832ae688dfaeb28f7a56d92c25ede2d4796b354 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 21 Jun 2024 11:51:55 -0400 Subject: [PATCH 501/652] ekf2: require valid filter vz for GPS vspeed check --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 22 +++++++++++-------- src/modules/ekf2/EKF/ekf.h | 2 +- 2 files changed, 14 insertions(+), 10 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 652069caf574..da7fc4e16060 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -189,15 +189,15 @@ bool Ekf::runGnssChecks(const gnssSample &gps) // Apply a low pass filter _gps_pos_deriv_filt = pos_derived * filter_coef + _gps_pos_deriv_filt * (1.0f - filter_coef); - // Calculate the horizontal drift speed and fail if too high + // hdrift: calculate the horizontal drift speed and fail if too high _gps_horizontal_position_drift_rate_m_s = Vector2f(_gps_pos_deriv_filt.xy()).norm(); _gps_check_fail_status.flags.hdrift = (_gps_horizontal_position_drift_rate_m_s > _params.req_hdrift); - // Fail if the vertical drift speed is too high + // vdrift: fail if the vertical drift speed is too high _gps_vertical_position_drift_rate_m_s = fabsf(_gps_pos_deriv_filt(2)); _gps_check_fail_status.flags.vdrift = (_gps_vertical_position_drift_rate_m_s > _params.req_vdrift); - // Check the magnitude of the filtered horizontal GPS velocity + // hspeed: check the magnitude of the filtered horizontal GNSS velocity const Vector2f gps_velNE = matrix::constrain(Vector2f(gps.vel.xy()), -10.0f * _params.req_hdrift, 10.0f * _params.req_hdrift); @@ -205,12 +205,20 @@ bool Ekf::runGnssChecks(const gnssSample &gps) _gps_filtered_horizontal_velocity_m_s = _gps_velNE_filt.norm(); _gps_check_fail_status.flags.hspeed = (_gps_filtered_horizontal_velocity_m_s > _params.req_hdrift); + // vspeed: check the magnitude of the filtered vertical GNSS velocity + const float gnss_vz_limit = 10.f * _params.req_vdrift; + const float gnss_vz = math::constrain(gps.vel(2), -gnss_vz_limit, gnss_vz_limit); + _gps_vel_d_filt = gnss_vz * filter_coef + _gps_vel_d_filt * (1.f - filter_coef); + + _gps_check_fail_status.flags.vspeed = (fabsf(_gps_vel_d_filt) > _params.req_vdrift); + } else if (_control_status.flags.in_air) { // These checks are always declared as passed when flying // If on ground and moving, the last result before movement commenced is kept _gps_check_fail_status.flags.hdrift = false; _gps_check_fail_status.flags.vdrift = false; _gps_check_fail_status.flags.hspeed = false; + _gps_check_fail_status.flags.vspeed = false; resetGpsDriftCheckFilters(); @@ -223,12 +231,6 @@ bool Ekf::runGnssChecks(const gnssSample &gps) _gps_pos_prev.initReference(lat, lon, gps.time_us); _gps_alt_prev = gps.alt; - // Check the filtered difference between GPS and EKF vertical velocity - const float vz_diff_limit = 10.0f * _params.req_vdrift; - const float vertVel = math::constrain(gps.vel(2) - _state.vel(2), -vz_diff_limit, vz_diff_limit); - _gps_velD_diff_filt = vertVel * filter_coef + _gps_velD_diff_filt * (1.0f - filter_coef); - _gps_check_fail_status.flags.vspeed = (fabsf(_gps_velD_diff_filt) > _params.req_vdrift); - // assume failed first time through if (_last_gps_fail_us == 0) { _last_gps_fail_us = _time_delayed_us; @@ -260,6 +262,8 @@ bool Ekf::runGnssChecks(const gnssSample &gps) void Ekf::resetGpsDriftCheckFilters() { _gps_velNE_filt.setZero(); + _gps_vel_d_filt = 0.f; + _gps_pos_deriv_filt.setZero(); _gps_horizontal_position_drift_rate_m_s = NAN; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 8d5cdc4e3482..6498de504b9c 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -652,7 +652,7 @@ class Ekf final : public EstimatorInterface Vector3f _gps_pos_deriv_filt{}; ///< GPS NED position derivative (m/sec) Vector2f _gps_velNE_filt{}; ///< filtered GPS North and East velocity (m/sec) - float _gps_velD_diff_filt{0.0f}; ///< GPS filtered Down velocity (m/sec) + float _gps_vel_d_filt{0.0f}; ///< GNSS filtered Down velocity (m/sec) uint64_t _last_gps_fail_us{0}; ///< last system time in usec that the GPS failed it's checks uint64_t _last_gps_pass_us{0}; ///< last system time in usec that the GPS passed it's checks uint32_t _min_gps_health_time_us{10000000}; ///< GPS is marked as healthy only after this amount of time From 81575049dfb52392673154e52c4499f360284b1b Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 16 Jul 2024 12:05:09 +0200 Subject: [PATCH 502/652] ekf2: reword EKF2_GPS_CHECK param --- src/modules/ekf2/module.yaml | 34 ++++++++++++---------------------- 1 file changed, 12 insertions(+), 22 deletions(-) diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 7edba1721ceb..9c37daac7726 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -125,30 +125,20 @@ parameters: EKF2_GPS_CHECK: description: short: Integer bitmask controlling GPS checks - long: 'Set bits to 1 to enable checks. Checks enabled by the following bit - positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Maximum - allowed PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position - error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set - by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : - Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check - will only run when the vehicle is on ground and stationary. 6 : Maximum - allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only - run when the vehicle is on ground and stationary. 7 : Maximum allowed horizontal - speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle - is on ground and stationary. 8 : Maximum allowed vertical velocity discrepancy - set by EKF2_REQ_VDRIFT. 9: Fails if GPS driver detects consistent spoofing' + long: 'Each threshold value is defined by the parameter indicated next to the check. + Drift and offset checks only run when the vehicle is on ground and stationary.' type: bitmask bit: - 0: Min sat count (EKF2_REQ_NSATS) - 1: Max PDOP (EKF2_REQ_PDOP) - 2: Max horizontal position error (EKF2_REQ_EPH) - 3: Max vertical position error (EKF2_REQ_EPV) - 4: Max speed error (EKF2_REQ_SACC) - 5: Max horizontal position rate (EKF2_REQ_HDRIFT) - 6: Max vertical position rate (EKF2_REQ_VDRIFT) - 7: Max horizontal speed (EKF2_REQ_HDRIFT) - 8: Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) - 9: Spoofing check + 0: Sat count (EKF2_REQ_NSATS) + 1: PDOP (EKF2_REQ_PDOP) + 2: EPH (EKF2_REQ_EPH) + 3: EPV (EKF2_REQ_EPV) + 4: Speed accuracy (EKF2_REQ_SACC) + 5: Horizontal position drift (EKF2_REQ_HDRIFT) + 6: Vertical position drift (EKF2_REQ_VDRIFT) + 7: Horizontal speed offset (EKF2_REQ_HDRIFT) + 8: Vertical speed offset (EKF2_REQ_VDRIFT) + 9: Spoofing default: 1023 min: 0 max: 1023 From 8c4620b77ecf38eac9c52e29694162502432ae57 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Wed, 17 Jul 2024 12:22:52 +0200 Subject: [PATCH 503/652] battery: simplify battery scale calculation (#23417) --- src/lib/battery/battery.cpp | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index 213d8fc017e1..302cbca05698 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -339,17 +339,12 @@ uint16_t Battery::determineFaults() void Battery::computeScale() { - const float voltage_range = (_params.v_charged - _params.v_empty); + _scale = _params.v_charged / _cell_voltage_filter_v.getState(); - // reusing capacity calculation to get single cell voltage before drop - const float bat_v = _params.v_empty + (voltage_range * _state_of_charge_volt_based); + if (PX4_ISFINITE(_scale)) { + _scale = math::constrain(_scale, 1.f, 1.3f); // Allow at most 30% compensation - _scale = _params.v_charged / bat_v; - - if (_scale > 1.3f) { // Allow at most 30% compensation - _scale = 1.3f; - - } else if (!PX4_ISFINITE(_scale) || _scale < 1.f) { // Shouldn't ever be more than the power at full battery + } else { _scale = 1.f; } } From c5c27a87f1c49b34919e079d9ea3d32eba43f1e9 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 17 Jul 2024 10:16:32 -0400 Subject: [PATCH 504/652] ekf2: track last terrain fuse time and update logic --- .../optical_flow/optical_flow_fusion.cpp | 4 ++ .../range_finder/range_height_fusion.cpp | 4 ++ src/modules/ekf2/EKF/ekf.cpp | 1 + src/modules/ekf2/EKF/ekf.h | 1 + src/modules/ekf2/EKF/terrain_control.cpp | 27 ++++---- .../test/change_indication/ekf_gsf_reset.csv | 62 +++++++++---------- .../ekf2/test/change_indication/iris_gps.csv | 28 ++++----- 7 files changed, 68 insertions(+), 59 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index 860c6eca5eec..e5c0e7bd3548 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -99,6 +99,10 @@ bool Ekf::fuseOptFlow(VectorState &H, const bool update_terrain) _aid_src_optical_flow.time_last_fuse = _time_delayed_us; _aid_src_optical_flow.fused = true; + if (update_terrain) { + _time_last_terrain_fuse = _time_delayed_us; + } + return true; } diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp index a06bdb9478b8..c2fd63672003 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_fusion.cpp @@ -66,5 +66,9 @@ bool Ekf::fuseHaglRng(estimator_aid_source1d_s &aid_src, bool update_height, boo aid_src.time_last_fuse = _time_delayed_us; aid_src.fused = true; + if (update_terrain) { + _time_last_terrain_fuse = _time_delayed_us; + } + return true; } diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 1b439c887956..5efb2b84ff4b 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -110,6 +110,7 @@ void Ekf::reset() _time_last_hor_vel_fuse = 0; _time_last_ver_vel_fuse = 0; _time_last_heading_fuse = 0; + _time_last_terrain_fuse = 0; _last_known_pos.setZero(); diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 6498de504b9c..2a5b7ab317d5 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -585,6 +585,7 @@ class Ekf final : public EstimatorInterface uint64_t _time_last_hor_vel_fuse{0}; ///< time the last fusion of horizontal velocity measurements was performed (uSec) uint64_t _time_last_ver_vel_fuse{0}; ///< time the last fusion of verticalvelocity measurements was performed (uSec) uint64_t _time_last_heading_fuse{0}; + uint64_t _time_last_terrain_fuse{0}; Vector3f _last_known_pos{}; ///< last known local position vector (m) diff --git a/src/modules/ekf2/EKF/terrain_control.cpp b/src/modules/ekf2/EKF/terrain_control.cpp index 8f277abac6f9..61356b1a41af 100644 --- a/src/modules/ekf2/EKF/terrain_control.cpp +++ b/src/modules/ekf2/EKF/terrain_control.cpp @@ -67,15 +67,7 @@ void Ekf::controlTerrainFakeFusion() && !_control_status.flags.rng_terrain && !_control_status.flags.opt_flow_terrain) { - bool recent_terrain_aiding = false; - -#if defined(CONFIG_EKF2_RANGE_FINDER) - recent_terrain_aiding |= isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)1e6); -#endif // CONFIG_EKF2_RANGE_FINDER - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - recent_terrain_aiding |= isRecent(_aid_src_optical_flow.time_last_fuse, (uint64_t)1e6); -#endif // CONFIG_EKF2_OPTICAL_FLOW + bool recent_terrain_aiding = isRecent(_time_last_terrain_fuse, (uint64_t)1e6); if (_control_status.flags.vehicle_at_rest || !recent_terrain_aiding) { initTerrain(); @@ -85,15 +77,22 @@ void Ekf::controlTerrainFakeFusion() bool Ekf::isTerrainEstimateValid() const { - // Assume being valid when the uncertainty is small compared to the height above ground - float hagl_var = INFINITY; - sym::ComputeHaglInnovVar(P, 0.f, &hagl_var); - bool valid = hagl_var < fmaxf(sq(0.1f * getHagl()), 0.2f); + bool valid = false; + + if (_time_last_terrain_fuse != 0) { + // Assume being valid when the uncertainty is small compared to the height above ground + float hagl_var = INFINITY; + sym::ComputeHaglInnovVar(P, 0.f, &hagl_var); + + if (hagl_var < fmaxf(sq(0.1f * getHagl()), 0.2f)) { + valid = true; + } + } #if defined(CONFIG_EKF2_RANGE_FINDER) // Assume that the terrain estimate is always valid when direct observations are fused - if (_control_status.flags.rng_terrain && isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)5e6)) { + if (_control_status.flags.rng_terrain && isRecent(_aid_src_rng_hgt.time_last_fuse, _params.hgt_fusion_timeout_max)) { valid = true; } diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv index 4c928c8ca1ad..ba51b8a17aba 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -358,34 +358,34 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0048,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 -35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 -35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 -36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 -36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 -36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 -36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 -36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 -36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 -36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 -36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 -36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0051,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 -36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 -37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 -37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 -37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 -37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 -37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 -37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 -37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 -37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 -37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0066,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 -37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 -38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 -38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 -38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 -38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 -38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 -38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 -38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 -38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 -38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 +35890000,0.64,-0.0067,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 +35990000,0.64,-0.0067,0.02,0.77,-3.4,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.066,0.0048,-0.11,-0.2,-0.047,0.46,0.00045,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 +36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0049,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 +36190000,0.64,-0.0068,0.02,0.77,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00055,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 +36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0048,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 +36390000,0.64,-0.0068,0.02,0.77,-3.5,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0049,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 +36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.067,0.0049,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 +36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.067,0.0049,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 +36690000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.067,0.0051,-0.11,-0.2,-0.047,0.46,0.00059,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 +36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 +36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0052,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 +36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 +37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 +37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,0.0015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 +37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0055,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 +37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 +37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0055,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 +37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.5e-05,0.068,0.0055,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 +37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.042,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.9e-05,0.069,0.0056,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 +37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.7e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 +37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.069,0.0057,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0066,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 +37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.069,0.0055,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 +38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.078,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 +38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.069,0.0055,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 +38290000,0.64,-0.0071,0.021,0.77,-4,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.069,0.0055,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 +38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 +38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.91 +38590000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.069,0.0056,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 +38690000,0.64,-0.007,0.021,0.77,-4.1,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0058,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 +38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.068,0.0056,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.87,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 +38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.068,0.0057,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 7204af4ab9c8..d1b4885f8f03 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -333,19 +333,19 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.0059,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 -33490000,-0.3,0.015,-0.0058,0.96,0.02,0.097,-0.078,0.097,0.004,-0.00072,-0.0013,-0.0058,-2.1e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 -33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 -33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.7e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 -33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.071,0.094,-0.013,-0.028,-0.0013,-0.0058,-3.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 -33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 -33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 -34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 -34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.7e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 -34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 -34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 -34490000,-0.3,0.015,-0.0051,0.95,0.045,0.1,-0.055,0.097,-0.0068,-0.061,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 -34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 -34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 +33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.011,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 +33490000,-0.3,0.015,-0.0058,0.96,0.02,0.097,-0.077,0.097,0.004,0.0016,-0.0013,-0.0058,-2.1e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 +33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.074,0.096,-0.0089,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 +33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.075,0.097,9.1e-05,-0.014,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 +33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.069,0.094,-0.013,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 +33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.069,0.097,-0.004,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 +33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.065,0.096,-0.012,-0.032,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 +34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.064,0.099,-0.0027,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 +34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.061,0.094,-0.014,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 +34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.06,0.098,-0.0047,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 +34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.055,0.093,-0.016,-0.049,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 +34490000,-0.3,0.015,-0.0051,0.95,0.045,0.1,-0.053,0.097,-0.0068,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 +34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 +34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38 34890000,-0.3,0.014,-0.005,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41 From 6fe0fa6d63ed20683295468153e1919b7d7d9f49 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 5 Jul 2024 10:56:25 -0400 Subject: [PATCH 505/652] ekf2: fake_pos don't use fuseHorizontalPosition helper - fake_pos shouldn't update _time_last_hor_pos_fuse --- src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp index 3704434d5fde..df7257d9b038 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp @@ -87,7 +87,15 @@ void Ekf::controlFakePosFusion() if ((aid_src.test_ratio[0] < sq(100.0f / innov_gate)) && (aid_src.test_ratio[1] < sq(100.0f / innov_gate)) ) { - fuseHorizontalPosition(aid_src); + if (!aid_src.innovation_rejected + && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], + State::pos.idx + 0) + && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], + State::pos.idx + 1) + ) { + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; + } } const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, (uint64_t)4e5); From 57c1ba545f8ccde1a925447e7d1ea397281694ba Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 5 Jul 2024 11:00:29 -0400 Subject: [PATCH 506/652] ekf2: fake_hgt don't use fuseVerticalPosition helper - fake_hgt shouldn't update _time_last_hgt_fuse --- src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp index 4ecb5b532564..d9635c8e4aa6 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp @@ -63,7 +63,13 @@ void Ekf::controlFakeHgtFusion() // always protect against extreme values that could result in a NaN if (aid_src.test_ratio < sq(100.0f / innov_gate)) { - fuseVerticalPosition(aid_src); + if (!aid_src.innovation_rejected + && fuseDirectStateMeasurement(aid_src.innovation, aid_src.innovation_variance, aid_src.observation_variance, + State::pos.idx + 2) + ) { + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; + } } const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, (uint64_t)4e5); From 691fdf713cf5a80dbe674c850eb08a5a16168753 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 5 Jul 2024 12:43:07 -0400 Subject: [PATCH 507/652] ekf2: airspeed update last hor vel timestamp if successfully updating all states --- src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp index c9822d4829bf..46dc33e491fd 100644 --- a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp @@ -217,6 +217,10 @@ void Ekf::fuseAirspeed(const airspeedSample &airspeed_sample, estimator_aid_sour if (is_fused) { aid_src.time_last_fuse = _time_delayed_us; + + if (!update_wind_only) { + _time_last_hor_vel_fuse = _time_delayed_us; + } } } From f8f8ddc101214a7123d0f276fed09edd215afbb7 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 5 Jul 2024 12:43:35 -0400 Subject: [PATCH 508/652] ekf2: optical flow update last hor vel timestamp on success --- .../ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index e5c0e7bd3548..e95df3dbc2d1 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -99,6 +99,8 @@ bool Ekf::fuseOptFlow(VectorState &H, const bool update_terrain) _aid_src_optical_flow.time_last_fuse = _time_delayed_us; _aid_src_optical_flow.fused = true; + _time_last_hor_vel_fuse = _time_delayed_us; + if (update_terrain) { _time_last_terrain_fuse = _time_delayed_us; } From 5083ec52ecde6442c5e276b244521892a37c8a04 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Wed, 17 Jul 2024 17:02:53 +0200 Subject: [PATCH 509/652] battery: migrate parameters in .c file to .yaml file --- src/lib/battery/battery_params_common.c | 101 ------------------------ src/lib/battery/module.yaml | 58 ++++++++++++++ 2 files changed, 58 insertions(+), 101 deletions(-) delete mode 100644 src/lib/battery/battery_params_common.c diff --git a/src/lib/battery/battery_params_common.c b/src/lib/battery/battery_params_common.c deleted file mode 100644 index b98c4cff2e9b..000000000000 --- a/src/lib/battery/battery_params_common.c +++ /dev/null @@ -1,101 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file battery_params.c - * - * Parameters defined by the battery lib, shared between all batteries. - * - * @author Julian Oes - */ - -/** - * Low threshold - * - * Sets the threshold when the battery will be reported as low. - * This has to be higher than the critical threshold. - * - * @group Battery Calibration - * @unit norm - * @min 0.12 - * @max 0.5 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(BAT_LOW_THR, 0.15f); - -/** - * Critical threshold - * - * Sets the threshold when the battery will be reported as critically low. - * This has to be lower than the low threshold. This threshold commonly - * will trigger RTL. - * - * @group Battery Calibration - * @unit norm - * @min 0.05 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(BAT_CRIT_THR, 0.07f); - -/** - * Emergency threshold - * - * Sets the threshold when the battery will be reported as dangerously low. - * This has to be lower than the critical threshold. This threshold commonly - * will trigger landing. - * - * @group Battery Calibration - * @unit norm - * @min 0.03 - * @max 0.1 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(BAT_EMERGEN_THR, 0.05f); - -/** - * Expected battery current in flight. - * - * This value is used to initialize the in-flight average current estimation, - * which in turn is used for estimating remaining flight time and RTL triggering. - * - * @group Battery Calibration - * @unit A - * @min 0 - * @max 500 - * @increment 0.1 - */ -PARAM_DEFINE_FLOAT(BAT_AVRG_CURRENT, 15.0f); diff --git a/src/lib/battery/module.yaml b/src/lib/battery/module.yaml index 1b6ee5802fb4..e92f090ea981 100644 --- a/src/lib/battery/module.yaml +++ b/src/lib/battery/module.yaml @@ -121,3 +121,61 @@ parameters: num_instances: *max_num_config_instances instance_start: 1 default: [0, -1, -1] + + BAT_LOW_THR: + description: + short: Low threshold. + long: | + Sets the threshold when the battery will be reported as low. + This has to be higher than the critical threshold. + type: float + unit: norm + min: 0.12 + max: 0.5 + decimal: 2 + increment: 0.01 + default: 0.15 + + BAT_CRIT_THR: + description: + short: Critical threshold. + long: | + Sets the threshold when the battery will be reported as critically low. + This has to be lower than the low threshold. This threshold commonly + will trigger RTL. + type: float + unit: norm + min: 0.05 + max: 0.25 + decimal: 2 + increment: 0.01 + default: 0.07 + + BAT_EMERGEN_THR: + description: + short: Emergency threshold. + long: | + Sets the threshold when the battery will be reported as dangerously low. + This has to be lower than the critical threshold. This threshold commonly + will trigger landing. + type: float + unit: norm + min: 0.03 + max: 0.1 + decimal: 2 + increment: 0.01 + default: 0.05 + + BAT_AVRG_CURRENT: + description: + short: Expected battery current in flight. + long: | + This value is used to initialize the in-flight average current estimation, + which in turn is used for estimating remaining flight time and RTL triggering. + type: float + unit: A + min: 0 + max: 500 + decimal: 2 + increment: 0.1 + default: 15 From 08c790217dc660eb165b75b53fd3818f8bd32143 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Wed, 17 Jul 2024 17:35:38 +0200 Subject: [PATCH 510/652] battery: increase max value for battery thresholds --- src/lib/battery/module.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/battery/module.yaml b/src/lib/battery/module.yaml index e92f090ea981..e784923250a5 100644 --- a/src/lib/battery/module.yaml +++ b/src/lib/battery/module.yaml @@ -146,7 +146,7 @@ parameters: type: float unit: norm min: 0.05 - max: 0.25 + max: 0.5 decimal: 2 increment: 0.01 default: 0.07 @@ -161,7 +161,7 @@ parameters: type: float unit: norm min: 0.03 - max: 0.1 + max: 0.5 decimal: 2 increment: 0.01 default: 0.05 From a42dc2165ceb7ec11216e86cbe6aa153666dd33d Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 9 Jul 2024 12:21:00 +0200 Subject: [PATCH 511/652] add pure pursuit library --- src/lib/CMakeLists.txt | 1 + src/lib/pure_pursuit/CMakeLists.txt | 39 +++++ src/lib/pure_pursuit/PurePursuit.cpp | 75 +++++++++ src/lib/pure_pursuit/PurePursuit.hpp | 91 +++++++++++ src/lib/pure_pursuit/PurePursuitTest.cpp | 194 +++++++++++++++++++++++ 5 files changed, 400 insertions(+) create mode 100644 src/lib/pure_pursuit/CMakeLists.txt create mode 100644 src/lib/pure_pursuit/PurePursuit.cpp create mode 100644 src/lib/pure_pursuit/PurePursuit.hpp create mode 100644 src/lib/pure_pursuit/PurePursuitTest.cpp diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 4e20ce106ba8..7a7b5973fd4a 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -64,6 +64,7 @@ add_subdirectory(perf EXCLUDE_FROM_ALL) add_subdirectory(fw_performance_model EXCLUDE_FROM_ALL) add_subdirectory(pid EXCLUDE_FROM_ALL) add_subdirectory(pid_design EXCLUDE_FROM_ALL) +add_subdirectory(pure_pursuit EXCLUDE_FROM_ALL) add_subdirectory(rate_control EXCLUDE_FROM_ALL) add_subdirectory(rc EXCLUDE_FROM_ALL) add_subdirectory(ringbuffer EXCLUDE_FROM_ALL) diff --git a/src/lib/pure_pursuit/CMakeLists.txt b/src/lib/pure_pursuit/CMakeLists.txt new file mode 100644 index 000000000000..1547d3dcdb69 --- /dev/null +++ b/src/lib/pure_pursuit/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(pure_pursuit + PurePursuit.cpp + PurePursuit.hpp +) + +px4_add_unit_gtest(SRC PurePursuitTest.cpp LINKLIBS pure_pursuit) diff --git a/src/lib/pure_pursuit/PurePursuit.cpp b/src/lib/pure_pursuit/PurePursuit.cpp new file mode 100644 index 000000000000..5313efb393db --- /dev/null +++ b/src/lib/pure_pursuit/PurePursuit.cpp @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * 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 "PurePursuit.hpp" +#include + +float PurePursuit::calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, + const Vector2f &curr_pos_ned, + const float lookahead_distance) +{ + // Check input validity + if (!curr_wp_ned.isAllFinite() || !curr_pos_ned.isAllFinite() || lookahead_distance < FLT_EPSILON + || !PX4_ISFINITE(lookahead_distance) || !prev_wp_ned.isAllFinite()) { + return NAN; + } + + // Pure pursuit + const Vector2f curr_pos_to_curr_wp = curr_wp_ned - curr_pos_ned; + const Vector2f prev_wp_to_curr_wp = curr_wp_ned - prev_wp_ned; + + if (curr_pos_to_curr_wp.norm() < lookahead_distance + || prev_wp_to_curr_wp.norm() < + FLT_EPSILON) { // Target current waypoint if closer to it than lookahead or waypoints overlap + return atan2f(curr_pos_to_curr_wp(1), curr_pos_to_curr_wp(0)); + } + + const Vector2f prev_wp_to_curr_pos = curr_pos_ned - prev_wp_ned; + const Vector2f prev_wp_to_curr_wp_u = prev_wp_to_curr_wp.unit_or_zero(); + const Vector2f distance_on_line_segment = (prev_wp_to_curr_pos * prev_wp_to_curr_wp_u) * + prev_wp_to_curr_wp_u; // Projection of prev_wp_to_curr_pos onto prev_wp_to_curr_wp + const Vector2f curr_pos_to_path = distance_on_line_segment - + prev_wp_to_curr_pos; // Shortest vector from the current position to the path + + if (curr_pos_to_path.norm() > lookahead_distance) { // Target closest point on path if there is no intersection point + return atan2f(curr_pos_to_path(1), curr_pos_to_path(0)); + } + + const float line_extension = sqrt(powf(lookahead_distance, 2.f) - powf(curr_pos_to_path.norm(), + 2.f)); // Length of the vector from the endpoint of distance_on_line_segment to the intersection point + const Vector2f prev_wp_to_intersection_point = distance_on_line_segment + line_extension * + prev_wp_to_curr_wp_u; + const Vector2f curr_pos_to_intersection_point = prev_wp_to_intersection_point - prev_wp_to_curr_pos; + return atan2f(curr_pos_to_intersection_point(1), curr_pos_to_intersection_point(0)); + +} diff --git a/src/lib/pure_pursuit/PurePursuit.hpp b/src/lib/pure_pursuit/PurePursuit.hpp new file mode 100644 index 000000000000..6e6203296194 --- /dev/null +++ b/src/lib/pure_pursuit/PurePursuit.hpp @@ -0,0 +1,91 @@ +/**************************************************************************** + * + * 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 + +using namespace matrix; + +/** + * @file PurePursuit.hpp + * + * Implementation of pure pursuit guidance logic. + * + * Acknowledgements and References: + * + * This implementation has been built for PX4 based on the idea from [1] (not including any code). + * + * [1] Coulter, R. C. (1992). Implementation of the Pure Pursuit Path Tracking Algorithm + * (Techreport CMU-RI-TR-92-01). + * + * Pure pursuit is a path following algorithm that uses the intersection between the path and + * a circle (the radius of which is referred to as lookahead distance) around the vehicle as + * the target point for the vehicle. + * C + * / + * __/__ + * / / \ + * / / \ + * | / V | + * \/ / + * /\ _____ / + * N (0 rad) / + * ^ P + * | + * | D + * (-1.5708 rad) <----- ⨂ -----> E (1.5708 rad) + * | + * | + * ⌄ + * (+- 3.14159 rad) + * + * Input: Current/prev waypoint and the vehicle position in NED frame as well as the lookahead distance. + * Output: Calculates the intersection points and returns the heading towards the point that is closer to the current waypoint. + */ +class PurePursuit +{ +public: + /** + * @brief Return heading towards the intersection point between a circle with a radius of + * lookahead_distance around the vehicle and an extended line segment from the previous to the current waypoint. + * Exceptions: + * Will return heading towards the current waypoint if it is closer to the vehicle than the lookahead. + * Will return heading towards the closest point on the path if there are no intersection points (crosstrack error bigger than lookahead). + * Will return NAN if input is invalid. + * @param curr_wp_ned North/East coordinates of current waypoint in NED frame [m]. + * @param prev_wp_ned North/East coordinates of previous waypoint in NED frame [m]. + * @param curr_pos_ned North/East coordinates of current position of the vehicle in NED frame [m]. + * @param lookahead_distance Radius of circle around vehicle [m]. + */ + float calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, + const float lookahead_distance); +}; diff --git a/src/lib/pure_pursuit/PurePursuitTest.cpp b/src/lib/pure_pursuit/PurePursuitTest.cpp new file mode 100644 index 000000000000..6d1ad1caae67 --- /dev/null +++ b/src/lib/pure_pursuit/PurePursuitTest.cpp @@ -0,0 +1,194 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/****************************************************************** + * Test code for the Pure Pursuit algorithm + * Run this test only using "make tests TESTFILTER=PurePursuit" + * + * Graphic interpretation: + * Legend: + * C: Current waypoint + * P: Previous waypoint + * V: Vehicle + * |: Line segment + * Orientation: + * C + * / + * __/__ + * / / \ + * / / \ + * | / V | + * \/ / + * /\ _____ / + * N (0 rad) / + * ^ P + * | + * | D + * (-1.5708 rad) <----- ⨂ -----> E (1.5708 rad) + * | + * | + * ⌄ + * (+- 3.14159 rad) +******************************************************************/ + +#include +#include + +using namespace matrix; + +TEST(PurePursuitTest, InvalidLookaheadDistance) +{ + PurePursuit pure_pursuit; + // V C + // / + // / + // / + // P + const Vector2f curr_wp_ned(10.f, 10.f); + const Vector2f prev_wp_ned(0.f, 0.f); + const Vector2f curr_pos_ned(10.f, 0.f); + // Zero lookahead + const float desired_heading1 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, 0.f); + // Negative lookahead + const float desired_heading2 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, -1.f); + // NaN lookahead + const float desired_heading3 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, NAN); + EXPECT_FALSE(PX4_ISFINITE(desired_heading1)); + EXPECT_FALSE(PX4_ISFINITE(desired_heading2)); + EXPECT_FALSE(PX4_ISFINITE(desired_heading3)); +} + +TEST(PurePursuitTest, InvalidWaypoints) +{ + PurePursuit pure_pursuit; + // V C + // / + // / + // / + // P + const Vector2f curr_wp_ned(10.f, 10.f); + const Vector2f prev_wp_ned(0.f, 0.f); + const Vector2f curr_pos_ned(10.f, 0.f); + const float lookahead_distance{5.f}; + // Prev WP is NAN + const float desired_heading1 = pure_pursuit.calcDesiredHeading(curr_wp_ned, Vector2f(NAN, NAN), curr_pos_ned, + lookahead_distance); + // Curr WP is NAN + const float desired_heading2 = pure_pursuit.calcDesiredHeading(Vector2f(NAN, NAN), prev_wp_ned, curr_pos_ned, + lookahead_distance); + + // Curr Pos is NAN + const float desired_heading3 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, Vector2f(NAN, NAN), + lookahead_distance); + EXPECT_FALSE(PX4_ISFINITE(desired_heading1)); + EXPECT_FALSE(PX4_ISFINITE(desired_heading2)); + EXPECT_FALSE(PX4_ISFINITE(desired_heading3)); +} + +TEST(PurePursuitTest, OutOfLookahead) +{ + PurePursuit pure_pursuit; + const float lookahead_distance{5.f}; + // V C + // / + // / + // / + // P + const float desired_heading1 = pure_pursuit.calcDesiredHeading(Vector2f(10.f, 10.f), Vector2f(0.f, 0.f), Vector2f(10.f, + 0.f), + lookahead_distance); + // V + // + // P ----- C + const float desired_heading2 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 20.f), Vector2f(0.f, 0.f), Vector2f(10.f, + 10.f), + lookahead_distance); + EXPECT_NEAR(desired_heading1, M_PI_2_F + M_PI_4_F, FLT_EPSILON); // Fallback: Bearing to current waypoint + EXPECT_NEAR(desired_heading2, M_PI_F, FLT_EPSILON); // Fallback: Bearing to current waypoint +} + +TEST(PurePursuitTest, WaypointOverlap) +{ + PurePursuit pure_pursuit; + const float lookahead_distance{5.f}; + // C/P + // + // + // + // V + const float desired_heading1 = pure_pursuit.calcDesiredHeading(Vector2f(10.f, 10.f), Vector2f(10.f, 10.f), Vector2f(0.f, + 0.f), + lookahead_distance); + // V + // + // + // + // C/P + const float desired_heading2 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 0.f), Vector2f(0.f, 0.f), Vector2f(10.f, + 10.f), + lookahead_distance); + EXPECT_NEAR(desired_heading1, M_PI_4_F, FLT_EPSILON); // Fallback: Bearing to current waypoint + EXPECT_NEAR(desired_heading2, -(M_PI_4_F + M_PI_2_F), FLT_EPSILON); // Fallback: Bearing to current waypoint +} + +TEST(PurePursuitTest, CurrAndPrevSameNorthCoordinate) +{ + PurePursuit pure_pursuit; + const float lookahead_distance{5.f}; + // P -- V -- C + const float desired_heading1 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 20.f), Vector2f(0.f, 0.f), Vector2f(0.f, + 10.f), + lookahead_distance); + + // V + // P ------ C + const float desired_heading2 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 20.f), Vector2f(0.f, 0.f), + Vector2f(5.f / sqrtf(2.f), 10.f), + lookahead_distance); + // V + // C ------ P + const float desired_heading3 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 0.f), Vector2f(0.f, 20.f), + Vector2f(5.f / sqrtf(2.f), 10.f), + lookahead_distance); + // V + // + // P ------ C + const float desired_heading4 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 20.f), Vector2f(0.f, 0.f), Vector2f(10.f, + 10.f), + lookahead_distance); + + EXPECT_NEAR(desired_heading1, M_PI_2_F, FLT_EPSILON); + EXPECT_NEAR(desired_heading2, M_PI_2_F + M_PI_4_F, FLT_EPSILON); + EXPECT_NEAR(desired_heading3, -(M_PI_2_F + M_PI_4_F), FLT_EPSILON); + EXPECT_NEAR(desired_heading4, M_PI_F, FLT_EPSILON); // Fallback: Bearing to current waypoint +} From eac14b7db2e66612e0438fb2413720b018109115 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 17 Jun 2024 18:48:12 -0400 Subject: [PATCH 512/652] ekf2/commander: simplify navigation filter preflight checks - remove commander test ratio "tuning knobs" (COM_ARM_EKF_{HGT,POS,VEL,YAW}) - these are effectively redundant with the actual tuning (noise & gate) in the estimator, plus most users have no idea why they'd be adjusting these other than to silence an annoying preflight complaint - remove ekf2 "PreFlightChecker" with hard coded innovation limits - ekf2 preflight innovation flags are now simply if any active source exceeds half the limit preflight --- .../scripts/itcm_functions_includes.ld | 6 - msg/EstimatorStatus.msg | 3 +- .../checks/estimatorCheck.cpp | 96 ++------ .../checks/estimatorCheck.hpp | 8 +- src/modules/commander/commander_params.c | 44 ---- src/modules/ekf2/CMakeLists.txt | 3 - src/modules/ekf2/EKF/ekf.h | 3 +- src/modules/ekf2/EKF/ekf_helper.cpp | 66 +++++- src/modules/ekf2/EKF2.cpp | 66 ++---- src/modules/ekf2/EKF2.hpp | 3 - src/modules/ekf2/Utility/CMakeLists.txt | 45 ---- src/modules/ekf2/Utility/InnovationLpf.hpp | 79 ------- src/modules/ekf2/Utility/PreFlightChecker.cpp | 180 --------------- src/modules/ekf2/Utility/PreFlightChecker.hpp | 211 ------------------ .../ekf2/Utility/PreFlightCheckerTest.cpp | 97 -------- 15 files changed, 104 insertions(+), 806 deletions(-) delete mode 100644 src/modules/ekf2/Utility/CMakeLists.txt delete mode 100644 src/modules/ekf2/Utility/InnovationLpf.hpp delete mode 100644 src/modules/ekf2/Utility/PreFlightChecker.cpp delete mode 100644 src/modules/ekf2/Utility/PreFlightChecker.hpp delete mode 100644 src/modules/ekf2/Utility/PreFlightCheckerTest.cpp 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 2b32ba473ac3..9b169ae36005 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 @@ -335,7 +335,6 @@ *(.text._ZThn16_N7sensors22VehicleAngularVelocity3RunEv) *(.text._ZN29MavlinkStreamObstacleDistance4sendEv) *(.text._ZN24MavlinkStreamOrbitStatus4sendEv) -*(.text._ZN16PreFlightChecker26preFlightCheckHeightFailedERK23estimator_innovations_sf) *(.text._ZN9Navigator3runEv) *(.text._ZN24MavlinkParametersManager11send_paramsEv) *(.text._ZN17MavlinkLogHandler4sendEv) @@ -374,7 +373,6 @@ *(.text.imxrt_ioctl) *(.text._ZN3Ekf25checkMagBiasObservabilityEv) *(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv) -*(.text._ZN16PreFlightChecker6updateEfRK23estimator_innovations_s) *(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0) *(.text._ZN19StickAccelerationXYC1EP12ModuleParams) *(.text.imxrt_epsubmit) @@ -458,7 +456,6 @@ *(.text._ZN14FlightTaskAuto17_evaluateTripletsEv) *(.text._ZN11calibration9Gyroscope23SensorCorrectionsUpdateEb) *(.text._ZN25MavlinkStreamMagCalReport4sendEv) -*(.text._ZN16PreFlightChecker27preFlightCheckHeadingFailedERK23estimator_innovations_sf) *(.text.imxrt_config_gpio) *(.text.nxsig_timeout) *(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_) @@ -593,7 +590,6 @@ *(.text.uart_xmitchars_done) *(.text._ZN4EKF225PublishYawEstimatorStatusERKy) *(.text.sin) -*(.text._ZN16PreFlightChecker27preFlightCheckVertVelFailedERK23estimator_innovations_sf) *(.text._ZN6Safety19safetyButtonHandlerEv) *(.text._ZN3Ekf19controlAuxVelFusionEv) *(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_) @@ -667,10 +663,8 @@ *(.text._ZN26MavlinkStreamCameraTrigger8get_sizeEv) *(.text.iob_navail) *(.text._ZN12FailsafeBase25removeNonActivatedActionsEv) -*(.text._ZN16PreFlightChecker28preFlightCheckHorizVelFailedERK23estimator_innovations_sf) *(.text._ZN15TakeoffHandling10updateRampEff) *(.text._Z7led_offi) -*(.text._ZN16PreFlightChecker22selectHeadingTestLimitEv) *(.text.led_off) *(.text.udp_wrbuffer_test) *(.text._ZNK3Ekf34updateVerticalPositionAidSrcStatusERKyfffR24estimator_aid_source1d_s) diff --git a/msg/EstimatorStatus.msg b/msg/EstimatorStatus.msg index a603a0f5ad86..0b479b1545b4 100644 --- a/msg/EstimatorStatus.msg +++ b/msg/EstimatorStatus.msg @@ -102,9 +102,10 @@ uint8 reset_count_quat # number of quaternion reset events (allow to wrap if c float32 time_slip # cumulative amount of time in seconds that the EKF inertial calculation has slipped relative to system time bool pre_flt_fail_innov_heading +bool pre_flt_fail_innov_height +bool pre_flt_fail_innov_pos_horiz bool pre_flt_fail_innov_vel_horiz bool pre_flt_fail_innov_vel_vert -bool pre_flt_fail_innov_height bool pre_flt_fail_mag_field_disturbed uint32 accel_device_id diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index d1bc06a74218..58f8e582c982 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -63,6 +63,7 @@ void EstimatorChecks::checkAndReport(const Context &context, Report &reporter) bool pre_flt_fail_innov_heading = false; bool pre_flt_fail_innov_vel_horiz = false; + bool pre_flt_fail_innov_pos_horiz = false; bool missing_data = false; const NavModes required_groups = (NavModes)reporter.failsafeFlags().mode_req_attitude; @@ -90,6 +91,7 @@ void EstimatorChecks::checkAndReport(const Context &context, Report &reporter) if (_estimator_status_sub.copy(&estimator_status)) { pre_flt_fail_innov_heading = estimator_status.pre_flt_fail_innov_heading; pre_flt_fail_innov_vel_horiz = estimator_status.pre_flt_fail_innov_vel_horiz; + pre_flt_fail_innov_pos_horiz = estimator_status.pre_flt_fail_innov_pos_horiz; checkEstimatorStatus(context, reporter, estimator_status, required_groups); checkEstimatorStatusFlags(context, reporter, estimator_status, lpos); @@ -123,7 +125,8 @@ void EstimatorChecks::checkAndReport(const Context &context, Report &reporter) } // set mode requirements - setModeRequirementFlags(context, pre_flt_fail_innov_heading, pre_flt_fail_innov_vel_horiz, lpos, vehicle_gps_position, + setModeRequirementFlags(context, pre_flt_fail_innov_heading, pre_flt_fail_innov_vel_horiz, pre_flt_fail_innov_pos_horiz, + lpos, vehicle_gps_position, reporter.failsafeFlags(), reporter); @@ -166,6 +169,17 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: vertical velocity unstable"); } + } else if (!context.isArmed() && estimator_status.pre_flt_fail_innov_pos_horiz) { + /* EVENT + */ + reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate, + events::ID("check_estimator_hor_pos_not_stable"), + events::Log::Error, "Horizontal position unstable"); + + if (reporter.mavlink_log_pub()) { + mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: horizontal position unstable"); + } + } else if (!context.isArmed() && estimator_status.pre_flt_fail_innov_height) { /* EVENT */ @@ -208,82 +222,6 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor } } - // check vertical position innovation test ratio - if (!context.isArmed() && (estimator_status.hgt_test_ratio > _param_com_arm_ekf_hgt.get())) { - /* EVENT - * @description - * - * Test ratio: {1:.3}, limit: {2:.3}. - * - * This check can be configured via COM_ARM_EKF_HGT parameter. - * - */ - reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate, - events::ID("check_estimator_hgt_est_err"), - events::Log::Error, "Height estimate error", estimator_status.hgt_test_ratio, _param_com_arm_ekf_hgt.get()); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: height estimate error"); - } - } - - // check velocity innovation test ratio - if (!context.isArmed() && (estimator_status.vel_test_ratio > _param_com_arm_ekf_vel.get())) { - /* EVENT - * @description - * - * Test ratio: {1:.3}, limit: {2:.3}. - * - * This check can be configured via COM_ARM_EKF_VEL parameter. - * - */ - reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate, - events::ID("check_estimator_vel_est_err"), - events::Log::Error, "Velocity estimate error", estimator_status.vel_test_ratio, _param_com_arm_ekf_vel.get()); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: velocity estimate error"); - } - } - - // check horizontal position innovation test ratio - if (!context.isArmed() && (estimator_status.pos_test_ratio > _param_com_arm_ekf_pos.get())) { - /* EVENT - * @description - * - * Test ratio: {1:.3}, limit: {2:.3}. - * - * This check can be configured via COM_ARM_EKF_POS parameter. - * - */ - reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate, - events::ID("check_estimator_pos_est_err"), - events::Log::Error, "Position estimate error", estimator_status.pos_test_ratio, _param_com_arm_ekf_pos.get()); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: position estimate error"); - } - } - - // check magnetometer innovation test ratio - if (!context.isArmed() && (estimator_status.mag_test_ratio > _param_com_arm_ekf_yaw.get())) { - /* EVENT - * @description - * - * Test ratio: {1:.3}, limit: {2:.3}. - * - * This check can be configured via COM_ARM_EKF_YAW parameter. - * - */ - reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate, - events::ID("check_estimator_yaw_est_err"), - events::Log::Error, "Yaw estimate error", estimator_status.mag_test_ratio, _param_com_arm_ekf_yaw.get()); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Yaw estimate error"); - } - } - // If GPS aiding is required, declare fault condition if the required GPS quality checks are failing if (_param_sys_has_gps.get()) { const bool ekf_gps_fusion = estimator_status.control_mode_flags & (1 << estimator_status_s::CS_GPS); @@ -767,7 +705,7 @@ void EstimatorChecks::lowPositionAccuracy(const Context &context, Report &report } void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_flt_fail_innov_heading, - bool pre_flt_fail_innov_vel_horiz, + bool pre_flt_fail_innov_vel_horiz, bool pre_flt_fail_innov_pos_horiz, const vehicle_local_position_s &lpos, const sensor_gps_s &vehicle_gps_position, failsafe_flags_s &failsafe_flags, Report &reporter) { @@ -797,7 +735,7 @@ void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_f bool v_xy_valid = lpos.v_xy_valid && !_nav_test_failed; if (!context.isArmed()) { - if (pre_flt_fail_innov_heading || pre_flt_fail_innov_vel_horiz) { + if (pre_flt_fail_innov_heading || pre_flt_fail_innov_pos_horiz) { xy_valid = false; } diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp index c900e95b8a0d..6578776ee99d 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp @@ -66,7 +66,9 @@ class EstimatorChecks : public HealthAndArmingCheckBase const vehicle_local_position_s &lpos); void checkGps(const Context &context, Report &reporter, const sensor_gps_s &vehicle_gps_position) const; void lowPositionAccuracy(const Context &context, Report &reporter, const vehicle_local_position_s &lpos) const; - void setModeRequirementFlags(const Context &context, bool pre_flt_fail_innov_heading, bool pre_flt_fail_innov_vel_horiz, + + void setModeRequirementFlags(const Context &context, bool pre_flt_fail_innov_heading, + bool pre_flt_fail_innov_vel_horiz, bool pre_flt_fail_innov_pos_horiz, const vehicle_local_position_s &lpos, const sensor_gps_s &vehicle_gps_position, failsafe_flags_s &failsafe_flags, Report &reporter); @@ -108,10 +110,6 @@ class EstimatorChecks : public HealthAndArmingCheckBase DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, (ParamInt) _param_sens_imu_mode, (ParamInt) _param_com_arm_mag_str, - (ParamFloat) _param_com_arm_ekf_hgt, - (ParamFloat) _param_com_arm_ekf_vel, - (ParamFloat) _param_com_arm_ekf_pos, - (ParamFloat) _param_com_arm_ekf_yaw, (ParamBool) _param_com_arm_wo_gps, (ParamBool) _param_sys_has_gps, (ParamFloat) _param_com_pos_fs_eph, diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index e9d5f4de3acc..a462c8ae898c 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -358,50 +358,6 @@ PARAM_DEFINE_INT32(COM_OBL_RC_ACT, 0); */ PARAM_DEFINE_FLOAT(COM_OBC_LOSS_T, 5.0f); -/** - * Maximum EKF position innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_POS, 0.5f); - -/** - * Maximum EKF velocity innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_VEL, 0.5f); - -/** - * Maximum EKF height innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_HGT, 1.0f); - -/** - * Maximum EKF yaw innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_YAW, 0.5f); - /** * Maximum accelerometer inconsistency between IMU units that will allow arming * diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index c4d0d1162584..a71c1b06e611 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -31,8 +31,6 @@ # ############################################################################# -add_subdirectory(Utility) - option(EKF2_SYMFORCE_GEN "ekf2 generate symforce output" OFF) # Symforce code generation TODO:fixme @@ -254,7 +252,6 @@ px4_add_module( geo hysteresis perf - EKF2Utility px4_work_queue world_magnetic_model diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 2a5b7ab317d5..51212ebef13d 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -396,7 +396,8 @@ class Ekf final : public EstimatorInterface float getHeadingInnovationTestRatio() const; - float getVelocityInnovationTestRatio() const; + float getHorizontalVelocityInnovationTestRatio() const; + float getVerticalVelocityInnovationTestRatio() const; float getHorizontalPositionInnovationTestRatio() const; float getVerticalPositionInnovationTestRatio() const; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 8d25dfffdbd6..8c2a2c5511d0 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -319,7 +319,7 @@ void Ekf::resetAccelBias() float Ekf::getHeadingInnovationTestRatio() const { // return the largest heading innovation test ratio - float test_ratio = 0.f; + float test_ratio = -1.f; #if defined(CONFIG_EKF2_MAGNETOMETER) @@ -347,10 +347,14 @@ float Ekf::getHeadingInnovationTestRatio() const #endif // CONFIG_EKF2_EXTERNAL_VISION - return sqrtf(test_ratio); + if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { + return sqrtf(test_ratio); + } + + return NAN; } -float Ekf::getVelocityInnovationTestRatio() const +float Ekf::getHorizontalVelocityInnovationTestRatio() const { // return the largest velocity innovation test ratio float test_ratio = -1.f; @@ -358,7 +362,7 @@ float Ekf::getVelocityInnovationTestRatio() const #if defined(CONFIG_EKF2_GNSS) if (_control_status.flags.gps) { - for (int i = 0; i < 3; i++) { + for (int i = 0; i < 2; i++) { // only xy test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_vel.test_ratio_filtered[i])); } } @@ -368,7 +372,7 @@ float Ekf::getVelocityInnovationTestRatio() const #if defined(CONFIG_EKF2_EXTERNAL_VISION) if (_control_status.flags.ev_vel) { - for (int i = 0; i < 3; i++) { + for (int i = 0; i < 2; i++) { // only xy test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_vel.test_ratio_filtered[i])); } } @@ -392,6 +396,34 @@ float Ekf::getVelocityInnovationTestRatio() const return NAN; } +float Ekf::getVerticalVelocityInnovationTestRatio() const +{ + // return the largest velocity innovation test ratio + float test_ratio = -1.f; + +#if defined(CONFIG_EKF2_GNSS) + + if (_control_status.flags.gps) { + test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_vel.test_ratio_filtered[2])); + } + +#endif // CONFIG_EKF2_GNSS + +#if defined(CONFIG_EKF2_EXTERNAL_VISION) + + if (_control_status.flags.ev_vel) { + test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_vel.test_ratio_filtered[2])); + } + +#endif // CONFIG_EKF2_EXTERNAL_VISION + + if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { + return sqrtf(test_ratio); + } + + return NAN; +} + float Ekf::getHorizontalPositionInnovationTestRatio() const { // return the largest position innovation test ratio @@ -511,21 +543,35 @@ float Ekf::getSyntheticSideslipInnovationTestRatio() const float Ekf::getHeightAboveGroundInnovationTestRatio() const { - float test_ratio = -1.f; + // return the combined HAGL innovation test ratio + float hagl_sum = 0.f; + int n_hagl_sources = 0; #if defined(CONFIG_EKF2_TERRAIN) + +# if defined(CONFIG_EKF2_OPTICAL_FLOW) + + if (_control_status.flags.opt_flow_terrain) { + hagl_sum += sqrtf(math::max(fabsf(_aid_src_optical_flow.test_ratio_filtered[0]), + _aid_src_optical_flow.test_ratio_filtered[1])); + n_hagl_sources++; + } + +# endif // CONFIG_EKF2_OPTICAL_FLOW + # if defined(CONFIG_EKF2_RANGE_FINDER) if (_control_status.flags.rng_terrain) { - // return the terrain height innovation test ratio - test_ratio = math::max(test_ratio, fabsf(_aid_src_rng_hgt.test_ratio_filtered)); + hagl_sum += sqrtf(fabsf(_aid_src_rng_hgt.test_ratio_filtered)); + n_hagl_sources++; } # endif // CONFIG_EKF2_RANGE_FINDER + #endif // CONFIG_EKF2_TERRAIN - if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) { - return sqrtf(test_ratio); + if (n_hagl_sources > 0) { + return math::max(hagl_sum / static_cast(n_hagl_sources), FLT_MIN); } return NAN; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 005e303e74b8..929e3125fa3c 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1333,43 +1333,6 @@ void EKF2::PublishInnovations(const hrt_abstime ×tamp) innovations.timestamp = _replay_mode ? timestamp : hrt_absolute_time(); _estimator_innovations_pub.publish(innovations); - - // calculate noise filtered velocity innovations which are used for pre-flight checking - if (_ekf.control_status_prev_flags().in_air != _ekf.control_status_flags().in_air) { - // fully reset on takeoff or landing - _preflt_checker.reset(); - } - - if (!_ekf.control_status_flags().in_air) { - // TODO: move to run before publications - _preflt_checker.setUsingGpsAiding(_ekf.control_status_flags().gps); -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - _preflt_checker.setUsingFlowAiding(_ekf.control_status_flags().opt_flow); -#endif // CONFIG_EKF2_OPTICAL_FLOW - -#if defined(CONFIG_EKF2_TERRAIN) && defined(CONFIG_EKF2_OPTICAL_FLOW) - // set dist bottom to scale flow innovation - const float dist_bottom = _ekf.getHagl(); - _preflt_checker.setDistBottom(dist_bottom); -#endif // CONFIG_EKF2_TERRAIN && CONFIG_EKF2_OPTICAL_FLOW - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - _preflt_checker.setUsingEvPosAiding(_ekf.control_status_flags().ev_pos); - _preflt_checker.setUsingEvVelAiding(_ekf.control_status_flags().ev_vel); - _preflt_checker.setUsingEvHgtAiding(_ekf.control_status_flags().ev_hgt); -#endif // CONFIG_EKF2_EXTERNAL_VISION -#if defined(CONFIG_EKF2_BAROMETER) - _preflt_checker.setUsingBaroHgtAiding(_ekf.control_status_flags().baro_hgt); -#endif // CONFIG_EKF2_BAROMETER - _preflt_checker.setUsingGpsHgtAiding(_ekf.control_status_flags().gps_hgt); -#if defined(CONFIG_EKF2_RANGE_FINDER) - _preflt_checker.setUsingRngHgtAiding(_ekf.control_status_flags().rng_hgt); -#endif // CONFIG_EKF2_RANGE_FINDER - - _preflt_checker.setVehicleCanObserveHeadingInFlight(_ekf.control_status_flags().fixed_wing); - - _preflt_checker.update(_ekf.get_dt_ekf_avg(), innovations); - } } void EKF2::PublishInnovationTestRatios(const hrt_abstime ×tamp) @@ -1816,8 +1779,24 @@ void EKF2::PublishStatus(const hrt_abstime ×tamp) status.control_mode_flags = _ekf.control_status().value; status.filter_fault_flags = _ekf.fault_status().value; + // vel_test_ratio + float vel_xy_test_ratio = _ekf.getHorizontalVelocityInnovationTestRatio(); + float vel_z_test_ratio = _ekf.getVerticalVelocityInnovationTestRatio(); + + if (PX4_ISFINITE(vel_xy_test_ratio) && PX4_ISFINITE(vel_z_test_ratio)) { + status.vel_test_ratio = math::max(vel_xy_test_ratio, vel_z_test_ratio); + + } else if (PX4_ISFINITE(vel_xy_test_ratio)) { + status.vel_test_ratio = vel_xy_test_ratio; + + } else if (PX4_ISFINITE(vel_z_test_ratio)) { + status.vel_test_ratio = vel_z_test_ratio; + + } else { + status.vel_test_ratio = NAN; + } + status.mag_test_ratio = _ekf.getHeadingInnovationTestRatio(); - status.vel_test_ratio = _ekf.getVelocityInnovationTestRatio(); status.pos_test_ratio = _ekf.getHorizontalPositionInnovationTestRatio(); status.hgt_test_ratio = _ekf.getVerticalPositionInnovationTestRatio(); status.tas_test_ratio = _ekf.getAirspeedInnovationTestRatio(); @@ -1836,10 +1815,13 @@ void EKF2::PublishStatus(const hrt_abstime ×tamp) status.time_slip = _last_time_slip_us * 1e-6f; - status.pre_flt_fail_innov_heading = _preflt_checker.hasHeadingFailed(); - status.pre_flt_fail_innov_vel_horiz = _preflt_checker.hasHorizVelFailed(); - status.pre_flt_fail_innov_vel_vert = _preflt_checker.hasVertVelFailed(); - status.pre_flt_fail_innov_height = _preflt_checker.hasHeightFailed(); + static constexpr float kMinTestRatioPreflight = 0.5f; + status.pre_flt_fail_innov_heading = (kMinTestRatioPreflight < status.mag_test_ratio); + status.pre_flt_fail_innov_height = (kMinTestRatioPreflight < status.hgt_test_ratio); + status.pre_flt_fail_innov_pos_horiz = (kMinTestRatioPreflight < status.pos_test_ratio); + status.pre_flt_fail_innov_vel_horiz = (kMinTestRatioPreflight < vel_xy_test_ratio); + status.pre_flt_fail_innov_vel_vert = (kMinTestRatioPreflight < vel_z_test_ratio); + status.pre_flt_fail_mag_field_disturbed = _ekf.control_status_flags().mag_field_disturbed; status.accel_device_id = _device_id_accel; diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 8b832d60ccd8..326b0833a4e4 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -42,7 +42,6 @@ #define EKF2_HPP #include "EKF/ekf.h" -#include "Utility/PreFlightChecker.hpp" #include "EKF2Selector.hpp" @@ -478,8 +477,6 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem uORB::PublicationMulti _estimator_aid_src_gravity_pub{ORB_ID(estimator_aid_src_gravity)}; #endif // CONFIG_EKF2_GRAVITY_FUSION - PreFlightChecker _preflt_checker; - Ekf _ekf; parameters *_params; ///< pointer to ekf parameter struct (located in _ekf class instance) diff --git a/src/modules/ekf2/Utility/CMakeLists.txt b/src/modules/ekf2/Utility/CMakeLists.txt deleted file mode 100644 index 7a635acebe7c..000000000000 --- a/src/modules/ekf2/Utility/CMakeLists.txt +++ /dev/null @@ -1,45 +0,0 @@ -############################################################################ -# -# Copyright (c) 2019 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(EKF2Utility - PreFlightChecker.cpp -) - -target_include_directories(EKF2Utility - PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) - -target_link_libraries(EKF2Utility PRIVATE mathlib) - -px4_add_unit_gtest(SRC PreFlightCheckerTest.cpp LINKLIBS EKF2Utility) diff --git a/src/modules/ekf2/Utility/InnovationLpf.hpp b/src/modules/ekf2/Utility/InnovationLpf.hpp deleted file mode 100644 index 89964b0d7161..000000000000 --- a/src/modules/ekf2/Utility/InnovationLpf.hpp +++ /dev/null @@ -1,79 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019 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. - * - ****************************************************************************/ - -/** - * First order "alpha" IIR digital filter with input saturation - */ - -#include - -class InnovationLpf final -{ -public: - InnovationLpf() = default; - ~InnovationLpf() = default; - - void reset(float val = 0.f) { _x = val; } - - /** - * Update the filter with a new value and returns the filtered state - * The new value is constained by the limit set in setSpikeLimit - * @param val new input - * @param alpha normalized weight of the new input - * @param spike_limit the amplitude of the saturation at the input of the filter - * @return filtered output - */ - float update(float val, float alpha, float spike_limit) - { - float val_constrained = math::constrain(val, -spike_limit, spike_limit); - float beta = 1.f - alpha; - - _x = beta * _x + alpha * val_constrained; - - return _x; - } - - /** - * Helper function to compute alpha from dt and the inverse of tau - * @param dt sampling time in seconds - * @param tau_inv inverse of the time constant of the filter - * @return alpha, the normalized weight of a new measurement - */ - static float computeAlphaFromDtAndTauInv(float dt, float tau_inv) - { - return math::constrain(dt * tau_inv, 0.f, 1.f); - } - -private: - float _x{}; ///< current state of the filter -}; diff --git a/src/modules/ekf2/Utility/PreFlightChecker.cpp b/src/modules/ekf2/Utility/PreFlightChecker.cpp deleted file mode 100644 index 1ac4b2dd2629..000000000000 --- a/src/modules/ekf2/Utility/PreFlightChecker.cpp +++ /dev/null @@ -1,180 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file PreFlightCheckHelper.cpp - * Class handling the EKF2 innovation pre flight checks - */ - -#include "PreFlightChecker.hpp" - -void PreFlightChecker::update(const float dt, const estimator_innovations_s &innov) -{ - const float alpha = InnovationLpf::computeAlphaFromDtAndTauInv(dt, _innov_lpf_tau_inv); - - _has_heading_failed = preFlightCheckHeadingFailed(innov, alpha); - _has_horiz_vel_failed = preFlightCheckHorizVelFailed(innov, alpha); - _has_vert_vel_failed = preFlightCheckVertVelFailed(innov, alpha); - _has_height_failed = preFlightCheckHeightFailed(innov, alpha); -} - -bool PreFlightChecker::preFlightCheckHeadingFailed(const estimator_innovations_s &innov, const float alpha) -{ - const float heading_test_limit = selectHeadingTestLimit(); - const float heading_innov_spike_lim = 2.0f * heading_test_limit; - - const float heading_innov_lpf = _filter_heading_innov.update(innov.heading, alpha, heading_innov_spike_lim); - - return checkInnovFailed(heading_innov_lpf, innov.heading, heading_test_limit, heading_innov_spike_lim); -} - -float PreFlightChecker::selectHeadingTestLimit() -{ - // Select the max allowed heading innovaton depending on whether we are not aiding navigation using - // observations in the NE reference frame and if the vehicle can use GPS course to realign in flight (fixedwing sideslip fusion). - const bool is_ne_aiding = _is_using_gps_aiding || _is_using_ev_pos_aiding; - - return (is_ne_aiding && !_can_observe_heading_in_flight) - ? _nav_heading_innov_test_lim // more restrictive test limit - : _heading_innov_test_lim; // less restrictive test limit -} - -bool PreFlightChecker::preFlightCheckHorizVelFailed(const estimator_innovations_s &innov, const float alpha) -{ - bool has_failed = false; - - if (_is_using_gps_aiding || _is_using_ev_vel_aiding) { - const Vector2f vel_ne_innov = Vector2f(fmaxf(fabsf(innov.gps_hvel[0]), fabsf(innov.ev_hvel[0])), - fmaxf(fabsf(innov.gps_hvel[1]), fabsf(innov.ev_hvel[1]))); - Vector2f vel_ne_innov_lpf; - vel_ne_innov_lpf(0) = _filter_vel_n_innov.update(vel_ne_innov(0), alpha, _vel_innov_spike_lim); - vel_ne_innov_lpf(1) = _filter_vel_e_innov.update(vel_ne_innov(1), alpha, _vel_innov_spike_lim); - has_failed |= checkInnov2DFailed(vel_ne_innov_lpf, vel_ne_innov, _vel_innov_test_lim, _vel_innov_spike_lim); - } - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - - if (_is_using_flow_aiding) { - const Vector2f flow_innov = Vector2f(innov.flow) * _flow_dist_bottom; - Vector2f flow_innov_lpf; - flow_innov_lpf(0) = _filter_flow_x_innov.update(flow_innov(0), alpha, _flow_innov_spike_lim); - flow_innov_lpf(1) = _filter_flow_y_innov.update(flow_innov(1), alpha, _flow_innov_spike_lim); - has_failed |= checkInnov2DFailed(flow_innov_lpf, flow_innov, _flow_innov_test_lim, 5.f * _flow_innov_spike_lim); - } - -#endif // CONFIG_EKF2_OPTICAL_FLOW - return has_failed; -} - -bool PreFlightChecker::preFlightCheckVertVelFailed(const estimator_innovations_s &innov, const float alpha) -{ - const float vel_d_innov = fmaxf(fabsf(innov.gps_vvel), fabs(innov.ev_vvel)); // only temporary solution - const float vel_d_innov_lpf = _filter_vel_d_innov.update(vel_d_innov, alpha, _vel_innov_spike_lim); - return checkInnovFailed(vel_d_innov_lpf, vel_d_innov, _vel_innov_test_lim, _vel_innov_spike_lim); -} - -bool PreFlightChecker::preFlightCheckHeightFailed(const estimator_innovations_s &innov, const float alpha) -{ - bool has_failed = false; - - if (_is_using_baro_hgt_aiding) { - const float baro_hgt_innov_lpf = _filter_baro_hgt_innov.update(innov.baro_vpos, alpha, _hgt_innov_spike_lim); - has_failed |= checkInnovFailed(baro_hgt_innov_lpf, innov.baro_vpos, _hgt_innov_test_lim, _hgt_innov_spike_lim); - } - - if (_is_using_gps_hgt_aiding) { - const float gps_hgt_innov_lpf = _filter_gps_hgt_innov.update(innov.gps_vpos, alpha, _hgt_innov_spike_lim); - has_failed |= checkInnovFailed(gps_hgt_innov_lpf, innov.gps_vpos, _hgt_innov_test_lim, _hgt_innov_spike_lim); - } - -#if defined(CONFIG_EKF2_RANGE_FINDER) - - if (_is_using_rng_hgt_aiding) { - const float rng_hgt_innov_lpf = _filter_rng_hgt_innov.update(innov.rng_vpos, alpha, _hgt_innov_spike_lim); - has_failed |= checkInnovFailed(rng_hgt_innov_lpf, innov.rng_vpos, _hgt_innov_test_lim, _hgt_innov_spike_lim); - } - -#endif // CONFIG_EKF2_RANGE_FINDER - - if (_is_using_ev_hgt_aiding) { - const float ev_hgt_innov_lpf = _filter_ev_hgt_innov.update(innov.ev_vpos, alpha, _hgt_innov_spike_lim); - has_failed |= checkInnovFailed(ev_hgt_innov_lpf, innov.ev_vpos, _hgt_innov_test_lim, _hgt_innov_spike_lim); - } - - return has_failed; -} - -bool PreFlightChecker::checkInnovFailed(const float innov_lpf, const float innov, const float test_limit, - const float spike_limit) -{ - return fabsf(innov_lpf) > test_limit || fabsf(innov) > spike_limit; -} - -bool PreFlightChecker::checkInnov2DFailed(const Vector2f &innov_lpf, const Vector2f &innov, const float test_limit, - const float spike_limit) -{ - return innov_lpf.norm_squared() > sq(test_limit) - || innov.norm_squared() > sq(spike_limit); -} - -void PreFlightChecker::reset() -{ - _is_using_gps_aiding = false; - _is_using_ev_pos_aiding = false; - _is_using_ev_vel_aiding = false; - _is_using_baro_hgt_aiding = false; - _is_using_gps_hgt_aiding = false; - _is_using_ev_hgt_aiding = false; - _has_heading_failed = false; - _has_horiz_vel_failed = false; - _has_vert_vel_failed = false; - _has_height_failed = false; - _filter_vel_n_innov.reset(); - _filter_vel_e_innov.reset(); - _filter_vel_d_innov.reset(); - _filter_baro_hgt_innov.reset(); - _filter_gps_hgt_innov.reset(); - _filter_ev_hgt_innov.reset(); - _filter_heading_innov.reset(); - -#if defined(CONFIG_EKF2_RANGE_FINDER) - _is_using_rng_hgt_aiding = false; - _filter_rng_hgt_innov.reset(); -#endif // CONFIG_EKF2_RANGE_FINDER - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - _is_using_flow_aiding = false; - _filter_flow_x_innov.reset(); - _filter_flow_y_innov.reset(); -#endif // CONFIG_EKF2_OPTICAL_FLOW -} diff --git a/src/modules/ekf2/Utility/PreFlightChecker.hpp b/src/modules/ekf2/Utility/PreFlightChecker.hpp deleted file mode 100644 index a4fe6ab482a1..000000000000 --- a/src/modules/ekf2/Utility/PreFlightChecker.hpp +++ /dev/null @@ -1,211 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file PreFlightChecker.hpp - * Class handling the EKF2 innovation pre flight checks - * - * First call the update(...) function and then get the results - * using the hasXxxFailed() getters - */ - -#ifndef EKF2_PREFLIGHTCHECKER_HPP -#define EKF2_PREFLIGHTCHECKER_HPP - -#include -#include - -#include - -#include "InnovationLpf.hpp" - -using matrix::Vector2f; - -class PreFlightChecker -{ -public: - PreFlightChecker() = default; - ~PreFlightChecker() = default; - - /* - * Reset all the internal states of the class to their default value - */ - void reset(); - - /* - * Update the internal states - * @param dt the sampling time - * @param innov the ekf2_innovation_s struct containing the current innovations - */ - void update(float dt, const estimator_innovations_s &innov); - - /* - * If set to true, the checker will use a less conservative heading innovation check - */ - void setVehicleCanObserveHeadingInFlight(bool val) { _can_observe_heading_in_flight = val; } - - void setUsingGpsAiding(bool val) { _is_using_gps_aiding = val; } -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - void setUsingFlowAiding(bool val) { _is_using_flow_aiding = val; } - void setDistBottom(float dist_bottom) { _flow_dist_bottom = dist_bottom; } -#endif // CONFIG_EKF2_OPTICAL_FLOW - void setUsingEvPosAiding(bool val) { _is_using_ev_pos_aiding = val; } - void setUsingEvVelAiding(bool val) { _is_using_ev_vel_aiding = val; } - - void setUsingBaroHgtAiding(bool val) { _is_using_baro_hgt_aiding = val; } - void setUsingGpsHgtAiding(bool val) { _is_using_gps_hgt_aiding = val; } -#if defined(CONFIG_EKF2_RANGE_FINDER) - void setUsingRngHgtAiding(bool val) { _is_using_rng_hgt_aiding = val; } -#endif // CONFIG_EKF2_RANGE_FINDER - void setUsingEvHgtAiding(bool val) { _is_using_ev_hgt_aiding = val; } - - bool hasHeadingFailed() const { return _has_heading_failed; } - bool hasHorizVelFailed() const { return _has_horiz_vel_failed; } - bool hasVertVelFailed() const { return _has_vert_vel_failed; } - bool hasHeightFailed() const { return _has_height_failed; } - - /* - * Overall state of the pre fligh checks - * @return true if any of the check failed - */ - bool hasFailed() const { return hasHorizFailed() || hasVertFailed(); } - - /* - * Horizontal checks overall result - * @return true if one of the horizontal checks failed - */ - bool hasHorizFailed() const { return _has_heading_failed || _has_horiz_vel_failed; } - - /* - * Vertical checks overall result - * @return true if one of the vertical checks failed - */ - bool hasVertFailed() const { return _has_vert_vel_failed || _has_height_failed; } - - /* - * Check if the innovation fails the test - * To pass the test, the following conditions should be true: - * innov_lpf <= test_limit - * innov <= spike_limit - * @param innov_lpf the low-pass filtered innovation - * @param innov the current unfiltered innovation - * @param test_limit the magnitude test limit for innov_lpf - * @param spike_limit the magnitude test limit for innov - * @return true if the check failed the test, false otherwise - */ - static bool checkInnovFailed(float innov_lpf, float innov, float test_limit, float spike_limit); - - /* - * Check if the a innovation of a 2D vector fails the test - * To pass the test, the following conditions should be true: - * innov_lpf <= test_limit - * innov <= spike_limit - * @param innov_lpf the low-pass filtered innovation - * @param innov the current unfiltered innovation - * @param test_limit the magnitude test limit for innov_lpf - * @param spike_limit the magnitude test limit for innov - * @return true if the check failed the test, false otherwise - */ - static bool checkInnov2DFailed(const Vector2f &innov_lpf, const Vector2f &innov, float test_limit, float spike_limit); - - static constexpr float sq(float var) { return var * var; } - -private: - bool preFlightCheckHeadingFailed(const estimator_innovations_s &innov, float alpha); - float selectHeadingTestLimit(); - - bool preFlightCheckHorizVelFailed(const estimator_innovations_s &innov, float alpha); - bool preFlightCheckVertVelFailed(const estimator_innovations_s &innov, float alpha); - bool preFlightCheckHeightFailed(const estimator_innovations_s &innov, float alpha); - - bool _has_heading_failed{}; - bool _has_horiz_vel_failed{}; - bool _has_vert_vel_failed{}; - bool _has_height_failed{}; - - bool _can_observe_heading_in_flight{}; - bool _is_using_gps_aiding{}; - bool _is_using_ev_pos_aiding{}; - bool _is_using_ev_vel_aiding{}; - - bool _is_using_baro_hgt_aiding{}; - bool _is_using_gps_hgt_aiding{}; - bool _is_using_ev_hgt_aiding{}; - - // Low-pass filters for innovation pre-flight checks - InnovationLpf _filter_vel_n_innov; ///< Preflight low pass filter N axis velocity innovations (m/sec) - InnovationLpf _filter_vel_e_innov; ///< Preflight low pass filter E axis velocity innovations (m/sec) - InnovationLpf _filter_vel_d_innov; ///< Preflight low pass filter D axis velocity innovations (m/sec) - InnovationLpf _filter_heading_innov; ///< Preflight low pass filter heading innovation magntitude (rad) - - // Preflight low pass filter height innovation (m) - InnovationLpf _filter_baro_hgt_innov; - InnovationLpf _filter_gps_hgt_innov; - InnovationLpf _filter_ev_hgt_innov; - -#if defined(CONFIG_EKF2_RANGE_FINDER) - bool _is_using_rng_hgt_aiding {}; - InnovationLpf _filter_rng_hgt_innov; -#endif // CONFIG_EKF2_RANGE_FINDER - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - bool _is_using_flow_aiding {}; - float _flow_dist_bottom {}; - InnovationLpf _filter_flow_x_innov; ///< Preflight low pass filter optical flow innovation (rad) - InnovationLpf _filter_flow_y_innov; ///< Preflight low pass filter optical flow innovation (rad) - - // Maximum permissible flow innovation to pass pre-flight checks - static constexpr float _flow_innov_test_lim = 0.5f; - - // Preflight flow innovation spike limit (rad) - static constexpr float _flow_innov_spike_lim = 2.0f * _flow_innov_test_lim; -#endif // CONFIG_EKF2_OPTICAL_FLOW - - // Preflight low pass filter time constant inverse (1/sec) - static constexpr float _innov_lpf_tau_inv = 0.2f; - // Maximum permissible velocity innovation to pass pre-flight checks (m/sec) - static constexpr float _vel_innov_test_lim = 0.5f; - // Maximum permissible height innovation to pass pre-flight checks (m) - static constexpr float _hgt_innov_test_lim = 1.5f; - // Maximum permissible yaw innovation to pass pre-flight checks when aiding inertial nav using NE frame observations (rad) - static constexpr float _nav_heading_innov_test_lim = 0.25f; - // Maximum permissible yaw innovation to pass pre-flight checks when not aiding inertial nav using NE frame observations (rad) - static constexpr float _heading_innov_test_lim = 0.52f; - - // Preflight velocity innovation spike limit (m/sec) - static constexpr float _vel_innov_spike_lim = 2.0f * _vel_innov_test_lim; - // Preflight position innovation spike limit (m) - static constexpr float _hgt_innov_spike_lim = 2.0f * _hgt_innov_test_lim; - -}; -#endif // !EKF2_PREFLIGHTCHECKER_HPP diff --git a/src/modules/ekf2/Utility/PreFlightCheckerTest.cpp b/src/modules/ekf2/Utility/PreFlightCheckerTest.cpp deleted file mode 100644 index 16e1beddf5e8..000000000000 --- a/src/modules/ekf2/Utility/PreFlightCheckerTest.cpp +++ /dev/null @@ -1,97 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2019 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. - * - ****************************************************************************/ - -/** - * Test code for PreFlightChecker class - * Run this test only using make tests TESTFILTER=PreFlightChecker - */ - -#include - -#include "PreFlightChecker.hpp" - -class PreFlightCheckerTest : public ::testing::Test -{ -}; - -TEST_F(PreFlightCheckerTest, testInnovFailed) -{ - const float test_limit = 1.0; ///< is the limit for innovation_lpf - const float spike_limit = 2.f * test_limit; ///< is the limit for innovation_lpf - const float innovations[9] = {0.0, 1.5, 2.5, -1.5, -2.5, 1.5, -1.5, -2.5, -2.5}; - const float innovations_lpf[9] = {0.0, 0.9, 0.9, -0.9, -0.9, 1.1, -1.1, -1.1, 1.1}; - const bool expected_result[9] = {false, false, true, false, true, true, true, true, true}; - - for (int i = 0; i < 9; i++) { - EXPECT_EQ(PreFlightChecker::checkInnovFailed(innovations_lpf[i], innovations[i], test_limit, spike_limit), - expected_result[i]); - } - - // Smaller test limit, all the checks should fail except the first - EXPECT_FALSE(PreFlightChecker::checkInnovFailed(innovations_lpf[0], innovations[0], 0.0, 0.0)); - - for (int i = 1; i < 9; i++) { - EXPECT_TRUE(PreFlightChecker::checkInnovFailed(innovations_lpf[i], innovations[i], 0.0, 0.0)); - } - - // Larger test limit, none of the checks should fail - for (int i = 0; i < 9; i++) { - EXPECT_FALSE(PreFlightChecker::checkInnovFailed(innovations_lpf[i], innovations[i], 2.0, 4.0)); - } -} - -TEST_F(PreFlightCheckerTest, testInnov2dFailed) -{ - const float test_limit = 1.0; - const float spike_limit = 2.0; - Vector2f innovations[4] = {{0.0, 0.0}, {0.0, 0.0}, {0.0, -2.5}, {1.5, -1.5}}; - Vector2f innovations_lpf[4] = {{0.0, 0.0}, {1.1, 0.0}, {0.5, 0.5}, {1.0, -1.0}}; - const bool expected_result[4] = {false, true, true, true}; - - for (int i = 0; i < 4; i++) { - EXPECT_EQ(PreFlightChecker::checkInnov2DFailed(innovations_lpf[i], innovations[i], test_limit, spike_limit), - expected_result[i]); - } - - // Smaller test limit, all the checks should fail except the first - EXPECT_FALSE(PreFlightChecker::checkInnov2DFailed(innovations[0], innovations_lpf[0], 0.0, 0.0)); - - for (int i = 1; i < 4; i++) { - EXPECT_TRUE(PreFlightChecker::checkInnov2DFailed(innovations_lpf[i], innovations[i], 0.0, 0.0)); - } - - // Larger test limit, none of the checks should fail - for (int i = 0; i < 4; i++) { - EXPECT_FALSE(PreFlightChecker::checkInnov2DFailed(innovations_lpf[i], innovations[i], 1.42, 2.84)); - } -} From ca9948a84d7b6aa8d66a8abeed001ec15a2d587e Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 17 Jul 2024 10:26:39 -0400 Subject: [PATCH 513/652] msgs/EstimatorStatus.msg rename mag_test_ratio -> hdg_test_ratio - this is used for more than just mag --- Tools/ecl_ekf/analysis/metrics.py | 2 +- Tools/ecl_ekf/plotting/pdf_report.py | 2 +- msg/EstimatorStatus.msg | 2 +- src/drivers/ins/vectornav/VectorNav.cpp | 2 +- src/modules/airspeed_selector/AirspeedValidator.cpp | 6 +++--- src/modules/airspeed_selector/AirspeedValidator.hpp | 4 ++-- src/modules/airspeed_selector/airspeed_selector_main.cpp | 2 +- src/modules/ekf2/EKF2.cpp | 4 ++-- src/modules/mavlink/streams/ESTIMATOR_STATUS.hpp | 2 +- 9 files changed, 13 insertions(+), 13 deletions(-) diff --git a/Tools/ecl_ekf/analysis/metrics.py b/Tools/ecl_ekf/analysis/metrics.py index d435f88af9f7..47a8bb412e4e 100644 --- a/Tools/ecl_ekf/analysis/metrics.py +++ b/Tools/ecl_ekf/analysis/metrics.py @@ -54,7 +54,7 @@ def calculate_sensor_metrics( # calculates peak, mean, percentage above 0.5 std, and percentage above std metrics for # estimator status variables for signal, result_id in [('hgt_test_ratio', 'hgt'), - ('mag_test_ratio', 'mag'), + ('hdg_test_ratio', 'mag'), ('vel_test_ratio', 'vel'), ('pos_test_ratio', 'pos'), ('tas_test_ratio', 'tas'), diff --git a/Tools/ecl_ekf/plotting/pdf_report.py b/Tools/ecl_ekf/plotting/pdf_report.py index 029589ba56ed..35821fbc4697 100644 --- a/Tools/ecl_ekf/plotting/pdf_report.py +++ b/Tools/ecl_ekf/plotting/pdf_report.py @@ -160,7 +160,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str # plot normalised innovation test levels # define variables to plot - variables = [['mag_test_ratio'], ['vel_test_ratio', 'pos_test_ratio'], ['hgt_test_ratio']] + variables = [['hdg_test_ratio'], ['vel_test_ratio', 'pos_test_ratio'], ['hgt_test_ratio']] y_labels = ['mag', 'vel, pos', 'hgt'] legend = [['mag'], ['vel', 'pos'], ['hgt']] if np.amax(estimator_status['hagl_test_ratio']) > 0.0: # plot hagl test ratio, if applicable diff --git a/msg/EstimatorStatus.msg b/msg/EstimatorStatus.msg index 0b479b1545b4..dd62bc4aca3f 100644 --- a/msg/EstimatorStatus.msg +++ b/msg/EstimatorStatus.msg @@ -71,7 +71,7 @@ uint32 filter_fault_flags # Bitmask to indicate EKF internal faults float32 pos_horiz_accuracy # 1-Sigma estimated horizontal position accuracy relative to the estimators origin (m) float32 pos_vert_accuracy # 1-Sigma estimated vertical position accuracy relative to the estimators origin (m) -float32 mag_test_ratio # low-pass filtered ratio of the largest magnetometer innovation component to the innovation test limit +float32 hdg_test_ratio # low-pass filtered ratio of the largest heading innovation component to the innovation test limit float32 vel_test_ratio # low-pass filtered ratio of the largest velocity innovation component to the innovation test limit float32 pos_test_ratio # low-pass filtered ratio of the largest horizontal position innovation component to the innovation test limit float32 hgt_test_ratio # low-pass filtered ratio of the vertical position innovation to the innovation test limit diff --git a/src/drivers/ins/vectornav/VectorNav.cpp b/src/drivers/ins/vectornav/VectorNav.cpp index cbe7ab535257..85dd4c1846af 100644 --- a/src/drivers/ins/vectornav/VectorNav.cpp +++ b/src/drivers/ins/vectornav/VectorNav.cpp @@ -368,7 +368,7 @@ void VectorNav::sensorCallback(VnUartPacket *packet) test_ratio = 0.1f; } - estimator_status.mag_test_ratio = test_ratio; + estimator_status.hdg_test_ratio = test_ratio; estimator_status.vel_test_ratio = test_ratio; estimator_status.pos_test_ratio = test_ratio; estimator_status.hgt_test_ratio = test_ratio; diff --git a/src/modules/airspeed_selector/AirspeedValidator.cpp b/src/modules/airspeed_selector/AirspeedValidator.cpp index 4ebacdbeb804..acdc88ef2219 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.cpp +++ b/src/modules/airspeed_selector/AirspeedValidator.cpp @@ -58,7 +58,7 @@ AirspeedValidator::update_airspeed_validator(const airspeed_validator_update_dat update_in_fixed_wing_flight(input_data.in_fixed_wing_flight); check_airspeed_data_stuck(input_data.timestamp); check_load_factor(input_data.accel_z); - check_airspeed_innovation(input_data.timestamp, input_data.vel_test_ratio, input_data.mag_test_ratio, + check_airspeed_innovation(input_data.timestamp, input_data.vel_test_ratio, input_data.hdg_test_ratio, input_data.ground_velocity, input_data.gnss_valid); check_first_principle(input_data.timestamp, input_data.fixed_wing_tecs_throttle, input_data.fixed_wing_tecs_throttle_trim, input_data.tecs_timestamp, input_data.q_att); @@ -214,7 +214,7 @@ AirspeedValidator::check_airspeed_data_stuck(uint64_t time_now) void AirspeedValidator::check_airspeed_innovation(uint64_t time_now, float estimator_status_vel_test_ratio, - float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool gnss_valid) + float estimator_status_hdg_test_ratio, const matrix::Vector3f &vI, bool gnss_valid) { // Check normalised innovation levels with requirement for continuous data and use of hysteresis // to prevent false triggering. @@ -228,7 +228,7 @@ AirspeedValidator::check_airspeed_innovation(uint64_t time_now, float estimator_ _innovations_check_failed = false; _aspd_innov_integ_state = 0.f; - } else if (!gnss_valid || estimator_status_vel_test_ratio > 1.f || estimator_status_mag_test_ratio > 1.f) { + } else if (!gnss_valid || estimator_status_vel_test_ratio > 1.f || estimator_status_hdg_test_ratio > 1.f) { //nav velocity data is likely not good //don't run the test but don't reset the check if it had previously failed when nav velocity data was still likely good _aspd_innov_integ_state = 0.f; diff --git a/src/modules/airspeed_selector/AirspeedValidator.hpp b/src/modules/airspeed_selector/AirspeedValidator.hpp index 19c3cc88d1b1..74f5747989f6 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.hpp +++ b/src/modules/airspeed_selector/AirspeedValidator.hpp @@ -66,7 +66,7 @@ struct airspeed_validator_update_data { float air_temperature_celsius; float accel_z; float vel_test_ratio; - float mag_test_ratio; + float hdg_test_ratio; bool in_fixed_wing_flight; float fixed_wing_tecs_throttle; float fixed_wing_tecs_throttle_trim; @@ -213,7 +213,7 @@ class AirspeedValidator void update_CAS_TAS(float air_pressure_pa, float air_temperature_celsius); void check_airspeed_data_stuck(uint64_t timestamp); void check_airspeed_innovation(uint64_t timestamp, float estimator_status_vel_test_ratio, - float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool gnss_valid); + float estimator_status_hdg_test_ratio, const matrix::Vector3f &vI, bool gnss_valid); void check_load_factor(float accel_z); void check_first_principle(const uint64_t timestamp, const float throttle, const float throttle_trim, const uint64_t tecs_timestamp, const Quatf &att_q); diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index a3f8bcbc2351..1880d5ab3c4d 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -370,7 +370,7 @@ AirspeedModule::Run() input_data.air_pressure_pa = _vehicle_air_data.baro_pressure_pa; input_data.accel_z = _accel.xyz[2]; input_data.vel_test_ratio = _estimator_status.vel_test_ratio; - input_data.mag_test_ratio = _estimator_status.mag_test_ratio; + input_data.hdg_test_ratio = _estimator_status.hdg_test_ratio; input_data.tecs_timestamp = _tecs_status.timestamp; input_data.fixed_wing_tecs_throttle = _tecs_status.throttle_sp; input_data.fixed_wing_tecs_throttle_trim = _tecs_status.throttle_trim; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 929e3125fa3c..b5d5dda1ce09 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1796,7 +1796,7 @@ void EKF2::PublishStatus(const hrt_abstime ×tamp) status.vel_test_ratio = NAN; } - status.mag_test_ratio = _ekf.getHeadingInnovationTestRatio(); + status.hdg_test_ratio = _ekf.getHeadingInnovationTestRatio(); status.pos_test_ratio = _ekf.getHorizontalPositionInnovationTestRatio(); status.hgt_test_ratio = _ekf.getVerticalPositionInnovationTestRatio(); status.tas_test_ratio = _ekf.getAirspeedInnovationTestRatio(); @@ -1816,7 +1816,7 @@ void EKF2::PublishStatus(const hrt_abstime ×tamp) status.time_slip = _last_time_slip_us * 1e-6f; static constexpr float kMinTestRatioPreflight = 0.5f; - status.pre_flt_fail_innov_heading = (kMinTestRatioPreflight < status.mag_test_ratio); + status.pre_flt_fail_innov_heading = (kMinTestRatioPreflight < status.hdg_test_ratio); status.pre_flt_fail_innov_height = (kMinTestRatioPreflight < status.hgt_test_ratio); status.pre_flt_fail_innov_pos_horiz = (kMinTestRatioPreflight < status.pos_test_ratio); status.pre_flt_fail_innov_vel_horiz = (kMinTestRatioPreflight < vel_xy_test_ratio); diff --git a/src/modules/mavlink/streams/ESTIMATOR_STATUS.hpp b/src/modules/mavlink/streams/ESTIMATOR_STATUS.hpp index 3764940c312e..0a27a90eb093 100644 --- a/src/modules/mavlink/streams/ESTIMATOR_STATUS.hpp +++ b/src/modules/mavlink/streams/ESTIMATOR_STATUS.hpp @@ -80,7 +80,7 @@ class MavlinkStreamEstimatorStatus : public MavlinkStream est_msg.vel_ratio = est.vel_test_ratio; est_msg.pos_horiz_ratio = est.pos_test_ratio; est_msg.pos_vert_ratio = est.hgt_test_ratio; - est_msg.mag_ratio = est.mag_test_ratio; + est_msg.mag_ratio = est.hdg_test_ratio; est_msg.hagl_ratio = est.hagl_test_ratio; est_msg.tas_ratio = est.tas_test_ratio; est_msg.pos_horiz_accuracy = est.pos_horiz_accuracy; From 1b9f1b78e5287da9b5537f0e8cebff181a99e911 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Fri, 19 Jul 2024 14:33:08 +0200 Subject: [PATCH 514/652] Added support for resetting wind states to external observation (#23277) * added support for resetting wind states to external observation Signed-off-by: RomanBapst * moved wind related functions into separate file Signed-off-by: RomanBapst * added VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE Signed-off-by: RomanBapst * correctly compute variances Signed-off-by: RomanBapst * ekf2: implement wind reset Signed-off-by: RomanBapst * only allow VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE during wind dead-reckoning and increase horizontal velocity variance to allow velocity states to move towards solution that is aligned with the newly set wind Signed-off-by: RomanBapst * only reset wind on ground * still use wind reset using airspeed when it wasn't initialized * exclude func for rover, change reset interface * handle wind reset in drag-fusion * replace state reset with variance reset in sideslip/drag fusion * remove resetWind function --------- Signed-off-by: RomanBapst Co-authored-by: Marco Hauswirth --- msg/VehicleCommand.msg | 1 + src/modules/ekf2/CMakeLists.txt | 4 + src/modules/ekf2/EKF/CMakeLists.txt | 4 + .../aid_sources/airspeed/airspeed_fusion.cpp | 11 ++- .../ekf2/EKF/aid_sources/drag/drag_fusion.cpp | 6 +- .../aid_sources/sideslip/sideslip_fusion.cpp | 22 ++--- src/modules/ekf2/EKF/common.h | 1 + src/modules/ekf2/EKF/covariance.cpp | 18 +--- src/modules/ekf2/EKF/ekf.h | 18 +++- src/modules/ekf2/EKF/ekf_helper.cpp | 26 ------ .../EKF/python/ekf_derivation/derivation.py | 15 +++ ...it_and_cov_from_wind_speed_and_direction.h | 61 ++++++++++++ src/modules/ekf2/EKF/wind.cpp | 92 +++++++++++++++++++ src/modules/ekf2/EKF2.cpp | 11 +++ 14 files changed, 231 insertions(+), 59 deletions(-) create mode 100644 src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_wind_init_and_cov_from_wind_speed_and_direction.h create mode 100644 src/modules/ekf2/EKF/wind.cpp diff --git a/msg/VehicleCommand.msg b/msg/VehicleCommand.msg index b147bef09208..0c1ce85d5fa8 100644 --- a/msg/VehicleCommand.msg +++ b/msg/VehicleCommand.msg @@ -102,6 +102,7 @@ uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibrati uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # external reset of estimator global position when deadreckoning +uint16 VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE = 43004 # PX4 vehicle commands (beyond 16 bit mavlink commands) uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index a71c1b06e611..35c6a7b77962 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -214,6 +214,10 @@ if(CONFIG_EKF2_TERRAIN) list(APPEND EKF_SRCS EKF/terrain_control.cpp) endif() +if(CONFIG_EKF2_WIND) + list(APPEND EKF_SRCS EKF/wind.cpp) +endif () + add_subdirectory(EKF) px4_add_module( diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index f404817ef4e1..954123b250f5 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -138,6 +138,10 @@ if(CONFIG_EKF2_TERRAIN) list(APPEND EKF_SRCS terrain_control.cpp) endif() +if(CONFIG_EKF2_WIND) + list(APPEND EKF_SRCS wind.cpp) +endif () + include_directories(${CMAKE_CURRENT_SOURCE_DIR}) add_library(ecl_EKF ${EKF_SRCS} diff --git a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp index 46dc33e491fd..5cfb1210795d 100644 --- a/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/airspeed/airspeed_fusion.cpp @@ -62,6 +62,10 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) _control_status.flags.wind = false; } + if (_control_status.flags.wind && _external_wind_init) { + _external_wind_init = false; + } + #if defined(CONFIG_EKF2_GNSS) // clear yaw estimator airspeed (updated later with true airspeed if airspeed fusion is active) @@ -128,10 +132,11 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) if (_control_status.flags.inertial_dead_reckoning && !is_airspeed_consistent) { resetVelUsingAirspeed(airspeed_sample); - } else if (!_control_status.flags.wind || getWindVelocityVariance().longerThan(_params.initial_wind_uncertainty)) { - // If starting wind state estimation, reset the wind states and covariances before fusing any data - // Also catch the case where sideslip fusion enabled wind estimation recently and didn't converge yet. + } else if (!_external_wind_init + && (!_control_status.flags.wind + || getWindVelocityVariance().longerThan(sq(_params.initial_wind_uncertainty)))) { resetWindUsingAirspeed(airspeed_sample); + _aid_src_airspeed.time_last_fuse = _time_delayed_us; } _control_status.flags.wind = true; diff --git a/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp index 439cbdb44651..41c7dc2f12c8 100644 --- a/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/drag/drag_fusion.cpp @@ -48,9 +48,11 @@ void Ekf::controlDragFusion(const imuSample &imu_delayed) if ((_params.drag_ctrl > 0) && _drag_buffer) { if (!_control_status.flags.wind && !_control_status.flags.fake_pos && _control_status.flags.in_air) { - // reset the wind states and covariances when starting drag accel fusion _control_status.flags.wind = true; - resetWindToZero(); + + if (!_external_wind_init) { + resetWindCov(); + } } dragSample drag_sample; diff --git a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp index f7365b733370..193af436f329 100644 --- a/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/sideslip/sideslip_fusion.cpp @@ -64,16 +64,12 @@ void Ekf::controlBetaFusion(const imuSample &imu_delayed) updateSideslip(_aid_src_sideslip); _innov_check_fail_status.flags.reject_sideslip = _aid_src_sideslip.innovation_rejected; - // If starting wind state estimation, reset the wind states and covariances before fusing any data - if (!_control_status.flags.wind) { - // activate the wind states + if (fuseSideslip(_aid_src_sideslip)) { _control_status.flags.wind = true; - // reset the timeout timers to prevent repeated resets - _aid_src_sideslip.time_last_fuse = imu_delayed.time_us; - resetWindToZero(); - } - fuseSideslip(_aid_src_sideslip); + } else if (!_external_wind_init && !_control_status.flags.wind) { + resetWindCov(); + } } } } @@ -96,10 +92,10 @@ void Ekf::updateSideslip(estimator_aid_source1d_s &aid_src) const math::max(_params.beta_innov_gate, 1.f)); // innovation gate } -void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) +bool Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) { if (sideslip.innovation_rejected) { - return; + return false; } // determine if we need the sideslip fusion to correct states other than wind @@ -114,7 +110,7 @@ void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) const char *action_string = nullptr; if (update_wind_only) { - resetWind(); + resetWindCov(); action_string = "wind"; } else { @@ -125,7 +121,7 @@ void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) ECL_ERR("sideslip badly conditioned - %s covariance reset", action_string); - return; + return false; } _fault_status.flags.bad_sideslip = false; @@ -150,4 +146,6 @@ void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) if (is_fused) { sideslip.time_last_fuse = _time_delayed_us; } + + return is_fused; } diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 2e317cd71fac..6294310bbfc2 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -640,6 +640,7 @@ bool yaw_aligned_to_imu_gps : bool reset_hgt_to_ev : 1; ///< 16 - true when the vertical position state is reset to the ev measurement bool reset_pos_to_ext_obs : 1; ///< 17 - true when horizontal position was reset to an external observation while deadreckoning + bool reset_wind_to_ext_obs : 1; ///< 18 - true when wind states were reset to an external observation } flags; uint32_t value; }; diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 58e83b3bd757..28decbc0d1d1 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -200,15 +200,15 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_WIND) - if (_control_status.flags.wind) { - // wind vel: add process noise - float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, - 1.f) * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); + // wind vel: add process noise + if (!_external_wind_init) { + float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) + * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt; for (unsigned index = 0; index < State::wind_vel.dof; index++) { const unsigned i = State::wind_vel.idx + index; - P(i, i) += wind_vel_process_noise; + P(i, i) = fminf(P(i, i) + wind_vel_process_noise, sq(_params.initial_wind_uncertainty)); } } @@ -348,11 +348,3 @@ void Ekf::resetMagCov() P.uncorrelateCovarianceSetVariance(State::mag_B.idx, sq(_params.mag_noise)); } #endif // CONFIG_EKF2_MAGNETOMETER - -#if defined(CONFIG_EKF2_WIND) -void Ekf::resetWindCov() -{ - // start with a small initial uncertainty to improve the initial estimate - P.uncorrelateCovarianceSetVariance(State::wind_vel.idx, sq(_params.initial_wind_uncertainty)); -} -#endif // CONFIG_EKF2_WIND diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 51212ebef13d..f3f055434e62 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -526,6 +526,18 @@ class Ekf final : public EstimatorInterface bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation); + /** + * @brief Resets the wind states to an external observation + * + * @param wind_speed The wind speed in m/s + * @param wind_direction The azimuth (from true north) to where the wind is heading in radians + * @param wind_speed_accuracy The 1 sigma accuracy of the wind speed estimate in m/s + * @param wind_direction_accuracy The 1 sigma accuracy of the wind direction estimate in radians + */ + void resetWindToExternalObservation(float wind_speed, float wind_direction, float wind_speed_accuracy, + float wind_direction_accuracy); + bool _external_wind_init{false}; + void updateParameters(); friend class AuxGlobalPosition; @@ -782,7 +794,7 @@ class Ekf final : public EstimatorInterface // fuse synthetic zero sideslip measurement void updateSideslip(estimator_aid_source1d_s &_aid_src_sideslip) const; - void fuseSideslip(estimator_aid_source1d_s &_aid_src_sideslip); + bool fuseSideslip(estimator_aid_source1d_s &_aid_src_sideslip); #endif // CONFIG_EKF2_SIDESLIP #if defined(CONFIG_EKF2_DRAG_FUSION) @@ -808,6 +820,8 @@ class Ekf final : public EstimatorInterface void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var); void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const float pos_var = NAN) { resetHorizontalPositionTo(new_horz_pos, Vector2f(pos_var, pos_var)); } + void resetWindTo(const Vector2f &wind, const Vector2f &wind_var); + bool isHeightResetRequired() const; void resetVerticalPositionTo(float new_vert_pos, float new_vert_pos_var = NAN); @@ -1095,8 +1109,6 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) - // perform a reset of the wind states and related covariances - void resetWind(); void resetWindCov(); void resetWindToZero(); #endif // CONFIG_EKF2_WIND diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 8c2a2c5511d0..d88f7c400d92 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -864,32 +864,6 @@ void Ekf::updateGroundEffect() } #endif // CONFIG_EKF2_BAROMETER -#if defined(CONFIG_EKF2_WIND) -void Ekf::resetWind() -{ -#if defined(CONFIG_EKF2_AIRSPEED) - - if (_control_status.flags.fuse_aspd && isRecent(_airspeed_sample_delayed.time_us, 1e6)) { - resetWindUsingAirspeed(_airspeed_sample_delayed); - return; - } - -#endif // CONFIG_EKF2_AIRSPEED - - resetWindToZero(); -} - -void Ekf::resetWindToZero() -{ - ECL_INFO("reset wind to zero"); - - // If we don't have an airspeed measurement, then assume the wind is zero - _state.wind_vel.setZero(); - - resetWindCov(); -} - -#endif // CONFIG_EKF2_WIND void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed) { diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py index a206ea62954c..df08b048ee50 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py @@ -314,6 +314,20 @@ def compute_wind_init_and_cov_from_airspeed( wind = wind.subs({sideslip: 0.0}) return (wind, P) +def compute_wind_init_and_cov_from_wind_speed_and_direction( + wind_speed: sf.Scalar, + wind_direction: sf.Scalar, + wind_speed_var: sf.Scalar, + wind_direction_var: sf.Scalar +)-> (sf.V2, sf.V2): + wind = sf.V2(wind_speed * sf.cos(wind_direction), wind_speed * sf.sin(wind_direction)) + H = wind.jacobian([wind_speed, wind_direction]) + R = sf.Matrix.diag([wind_speed_var, wind_direction_var]) + + P = H * R * H.T + P_diag = sf.V2(P[0,0], P[1,1]) + return (wind, P_diag) + def predict_sideslip( state: State, epsilon: sf.Scalar @@ -721,6 +735,7 @@ def compute_gravity_z_innov_var_and_h( generate_px4_function(compute_sideslip_h_and_k, output_names=["H", "K"]) generate_px4_function(compute_sideslip_innov_and_innov_var, output_names=["innov", "innov_var"]) generate_px4_function(compute_wind_init_and_cov_from_airspeed, output_names=["wind", "P_wind"]) + generate_px4_function(compute_wind_init_and_cov_from_wind_speed_and_direction, output_names=["wind", "P_wind"]) generate_px4_function(compute_yaw_innov_var_and_h, output_names=["innov_var", "H"]) generate_px4_function(compute_flow_xy_innov_var_and_hx, output_names=["innov_var", "H"]) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_wind_init_and_cov_from_wind_speed_and_direction.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_wind_init_and_cov_from_wind_speed_and_direction.h new file mode 100644 index 000000000000..d0af79dc7aec --- /dev/null +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_wind_init_and_cov_from_wind_speed_and_direction.h @@ -0,0 +1,61 @@ +// ----------------------------------------------------------------------------- +// This file was autogenerated by symforce from template: +// function/FUNCTION.h.jinja +// Do NOT modify by hand. +// ----------------------------------------------------------------------------- + +#pragma once + +#include + +namespace sym { + +/** + * This function was autogenerated from a symbolic function. Do not modify by hand. + * + * Symbolic function: compute_wind_init_and_cov_from_wind_speed_and_direction + * + * Args: + * wind_speed: Scalar + * wind_direction: Scalar + * wind_speed_var: Scalar + * wind_direction_var: Scalar + * + * Outputs: + * wind: Matrix21 + * P_wind: Matrix21 + */ +template +void ComputeWindInitAndCovFromWindSpeedAndDirection( + const Scalar wind_speed, const Scalar wind_direction, const Scalar wind_speed_var, + const Scalar wind_direction_var, matrix::Matrix* const wind = nullptr, + matrix::Matrix* const P_wind = nullptr) { + // Total ops: 14 + + // Input arrays + + // Intermediate terms (5) + const Scalar _tmp0 = std::cos(wind_direction); + const Scalar _tmp1 = std::sin(wind_direction); + const Scalar _tmp2 = std::pow(_tmp0, Scalar(2)); + const Scalar _tmp3 = std::pow(_tmp1, Scalar(2)); + const Scalar _tmp4 = wind_direction_var * std::pow(wind_speed, Scalar(2)); + + // Output terms (2) + if (wind != nullptr) { + matrix::Matrix& _wind = (*wind); + + _wind(0, 0) = _tmp0 * wind_speed; + _wind(1, 0) = _tmp1 * wind_speed; + } + + if (P_wind != nullptr) { + matrix::Matrix& _p_wind = (*P_wind); + + _p_wind(0, 0) = _tmp2 * wind_speed_var + _tmp3 * _tmp4; + _p_wind(1, 0) = _tmp2 * _tmp4 + _tmp3 * wind_speed_var; + } +} // NOLINT(readability/fn_size) + +// NOLINTNEXTLINE(readability/fn_size) +} // namespace sym diff --git a/src/modules/ekf2/EKF/wind.cpp b/src/modules/ekf2/EKF/wind.cpp new file mode 100644 index 000000000000..ca3e8abc8b0b --- /dev/null +++ b/src/modules/ekf2/EKF/wind.cpp @@ -0,0 +1,92 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file wind.cpp + * Helper functions for wind states + */ + +#include "ekf.h" +#include + +void Ekf::resetWindToExternalObservation(float wind_speed, float wind_direction, float wind_speed_accuracy, + float wind_direction_accuracy) +{ + if (!_control_status.flags.in_air) { + + const float wind_speed_constrained = math::max(wind_speed, 0.0f); + const float wind_direction_var = sq(wind_direction_accuracy); + const float wind_speed_var = sq(wind_speed_accuracy); + + Vector2f wind; + Vector2f wind_var; + + sym::ComputeWindInitAndCovFromWindSpeedAndDirection(wind_speed_constrained, wind_direction, wind_speed_var, + wind_direction_var, &wind, &wind_var); + + ECL_INFO("reset wind states to external observation"); + _information_events.flags.reset_wind_to_ext_obs = true; + _external_wind_init = true; + + resetWindTo(wind, wind_var); + + } +} + +void Ekf::resetWindTo(const Vector2f &wind, const Vector2f &wind_var) +{ + _state.wind_vel = wind; + + if (PX4_ISFINITE(wind_var(0))) { + P.uncorrelateCovarianceSetVariance<1>(State::wind_vel.idx, + math::min(sq(_params.initial_wind_uncertainty), wind_var(0))); + } + + if (PX4_ISFINITE(wind_var(1))) { + P.uncorrelateCovarianceSetVariance<1>(State::wind_vel.idx + 1, + math::min(sq(_params.initial_wind_uncertainty), wind_var(1))); + } +} + +void Ekf::resetWindCov() +{ + // start with a small initial uncertainty to improve the initial estimate + P.uncorrelateCovarianceSetVariance(State::wind_vel.idx, sq(_params.initial_wind_uncertainty)); +} + +void Ekf::resetWindToZero() +{ + ECL_INFO("reset wind to zero"); + _state.wind_vel.setZero(); + resetWindCov(); +} diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index b5d5dda1ce09..ac98b9584f0b 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -561,6 +561,17 @@ void EKF2::Run() command_ack.timestamp = hrt_absolute_time(); _vehicle_command_ack_pub.publish(command_ack); } + + if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE) { +#if defined(CONFIG_EKF2_WIND) + // wind direction is given as azimuth where wind blows FROM + // PX4 backend expects direction where wind blows TO + const float wind_direction_rad = wrap_pi(math::radians(vehicle_command.param3) + M_PI_F); + const float wind_direction_accuracy_rad = math::radians(vehicle_command.param4); + _ekf.resetWindToExternalObservation(vehicle_command.param1, wind_direction_rad, vehicle_command.param2, + wind_direction_accuracy_rad); +#endif // CONFIG_EKF2_WIND + } } } From fe3cd4b0cb40474a632b1513b577cd09fe5fef1d Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 22 May 2024 14:26:50 +0200 Subject: [PATCH 515/652] Add check for missing or duplicate newlines at the end of files --- .github/workflows/checks.yml | 1 + Makefile | 8 ++++++-- Tools/astyle/check_newlines.sh | 19 +++++++++++++++++++ 3 files changed, 26 insertions(+), 2 deletions(-) create mode 100755 Tools/astyle/check_newlines.sh diff --git a/.github/workflows/checks.yml b/.github/workflows/checks.yml index d977aee7c13b..a2d7aa5f97a8 100644 --- a/.github/workflows/checks.yml +++ b/.github/workflows/checks.yml @@ -16,6 +16,7 @@ jobs: matrix: check: [ "check_format", + "check_newlines", "tests", "tests_coverage", "px4_fmu-v2_default stack_check", diff --git a/Makefile b/Makefile index 2d4116d73b0a..fe8580402dab 100644 --- a/Makefile +++ b/Makefile @@ -379,9 +379,9 @@ doxygen: @$(PX4_MAKE) -C "$(SRC_DIR)"/build/doxygen @touch "$(SRC_DIR)"/build/doxygen/Documentation/.nojekyll -# Astyle +# Style # -------------------------------------------------------------------- -.PHONY: check_format format +.PHONY: check_format format check_newlines check_format: $(call colorecho,'Checking formatting with astyle') @@ -392,6 +392,10 @@ format: $(call colorecho,'Formatting with astyle') @"$(SRC_DIR)"/Tools/astyle/check_code_style_all.sh --fix +check_newlines: + $(call colorecho,'Checking for missing or duplicate newlines at the end of files') + @"$(SRC_DIR)"/Tools/astyle/check_newlines.sh + # Testing # -------------------------------------------------------------------- .PHONY: tests tests_coverage tests_mission tests_mission_coverage tests_offboard tests_avoidance diff --git a/Tools/astyle/check_newlines.sh b/Tools/astyle/check_newlines.sh new file mode 100755 index 000000000000..516047693576 --- /dev/null +++ b/Tools/astyle/check_newlines.sh @@ -0,0 +1,19 @@ +#!/usr/bin/env bash + +return_value=0 + +# Check if there are files checked in that don't end in a newline (POSIX requirement) +git grep --cached -Il '' | xargs -L1 bash -c 'if test "$(tail -c 1 "$0")"; then echo "No new line at end of $0"; exit 1; fi' + +if [ $? -ne 0 ]; then + return_value=1 +fi + +# Check if there are files checked in that have duplicate newlines at the end (fail trailing whitespace checks) +git grep --cached -Il '' | xargs -L1 bash -c 'if tail -c 2 "$0" | ( read x && read y && [ x"$x" = x ] && [ x"$y" = x ]); then echo "Multiple newlines at the end of $0"; exit 1; fi' + +if [ $? -ne 0 ]; then + return_value=1 +fi + +exit $return_value From 7f14110bb116c9ce950915e026424f2c350f0b6b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 21 May 2024 16:57:24 +0200 Subject: [PATCH 516/652] Fix missing newlines at the end of files --- .vscode/cmake-kits.json | 2 +- Tools/ecl_ekf/batch_process_logdata_ekf.py | 2 +- Tools/models/sdp3x_pitot_model.py | 2 +- Tools/msg/templates/uorb/msg.json.em | 2 +- Tools/px4airframes/__init__.py | 2 +- Tools/test_keys/rsa2048.pem | 2 +- Tools/test_keys/test_keys.json | 2 +- boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp | 2 +- boards/modalai/voxl2/cmake/init.cmake | 2 +- boards/modalai/voxl2/scripts/patch-gazebo.sh | 2 +- boards/modalai/voxl2/src/board_config.h | 2 +- msg/DatamanRequest.msg | 2 +- msg/DebugArray.msg | 2 +- msg/InputRc.msg | 2 +- msg/ParameterSetValueResponse.msg | 2 +- platforms/nuttx/src/bootloader/common/bl.c | 2 +- platforms/nuttx/src/bootloader/common/bl.h | 2 +- platforms/nuttx/src/px4/common/CMakeLists.txt | 2 +- platforms/nuttx/src/px4/nxp/imxrt/board_hw_info/CMakeLists.txt | 2 +- platforms/qurt/src/px4/qurt_log.cpp | 2 +- src/drivers/actuators/voxl_esc/module.yaml | 2 +- src/drivers/cdcacm_autostart/Kconfig | 2 +- src/drivers/cdcacm_autostart/cdcacm_autostart_params.c | 2 +- src/drivers/voxl2_io/Kconfig | 2 +- src/lib/parameters/parameters_primary.cpp | 2 +- src/modules/fw_att_control/FixedwingAttitudeControl.cpp | 2 +- 26 files changed, 26 insertions(+), 26 deletions(-) diff --git a/.vscode/cmake-kits.json b/.vscode/cmake-kits.json index a7d7e14b60ae..517c8c6d5269 100644 --- a/.vscode/cmake-kits.json +++ b/.vscode/cmake-kits.json @@ -2,4 +2,4 @@ { "name": "PX4 detect" } -] \ No newline at end of file +] diff --git a/Tools/ecl_ekf/batch_process_logdata_ekf.py b/Tools/ecl_ekf/batch_process_logdata_ekf.py index 9d41431a104d..d118c655eb76 100755 --- a/Tools/ecl_ekf/batch_process_logdata_ekf.py +++ b/Tools/ecl_ekf/batch_process_logdata_ekf.py @@ -84,4 +84,4 @@ def main() -> None: if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/Tools/models/sdp3x_pitot_model.py b/Tools/models/sdp3x_pitot_model.py index 44c013fdc88d..864823d6634d 100644 --- a/Tools/models/sdp3x_pitot_model.py +++ b/Tools/models/sdp3x_pitot_model.py @@ -107,4 +107,4 @@ ##plt.plot(airspeed_corrected,(airspeed_corrected-airspeed_raw)/airspeed_corrected) ##plt.xlabel('airspeed [m/s]') ##plt.ylabel('relative error [-]') -##plt.show() \ No newline at end of file +##plt.show() diff --git a/Tools/msg/templates/uorb/msg.json.em b/Tools/msg/templates/uorb/msg.json.em index 31be5d61aa7e..81d6bbbc4f58 100644 --- a/Tools/msg/templates/uorb/msg.json.em +++ b/Tools/msg/templates/uorb/msg.json.em @@ -47,4 +47,4 @@ for field in spec.parsed_fields(): "main_orb_id": @( all_topics.index(name_snake_case) if name_snake_case in all_topics else -1 ), "dependencies": @( json.dumps(list(set(dependencies))) ), "name": "@( spec.full_name )" -} \ No newline at end of file +} diff --git a/Tools/px4airframes/__init__.py b/Tools/px4airframes/__init__.py index 43e82d26433b..be02bd2190b3 100644 --- a/Tools/px4airframes/__init__.py +++ b/Tools/px4airframes/__init__.py @@ -1 +1 @@ -__all__ = ["srcscanner", "srcparser", "xmlout", "rcout"] \ No newline at end of file +__all__ = ["srcscanner", "srcparser", "xmlout", "rcout"] diff --git a/Tools/test_keys/rsa2048.pem b/Tools/test_keys/rsa2048.pem index e2ee0e61bfde..21445d8d6466 100644 --- a/Tools/test_keys/rsa2048.pem +++ b/Tools/test_keys/rsa2048.pem @@ -24,4 +24,4 @@ q8jVArPNQT4R2erSmKmIGTRkLMG7CzUmwk1taHdSvzcmUyL4uYc5QBSubxat6gWh +a85AoGBAKgfnjjVoAWWvqEDLpfGPmE8lW+RaS7i5ff6QsSBx7uTEnHq6RNHuVnN et4pR87yIENeG8jMBiDCj8AGDtUNt9Ps9vWCPrf9HSOYoBUk+gZagU/9N+RBpuCM egoxtxIHM7HI+XIer+ZnZpVpgr+EoCaL7avx6k/susLQb7tqSBt1 ------END RSA PRIVATE KEY----- \ No newline at end of file +-----END RSA PRIVATE KEY----- diff --git a/Tools/test_keys/test_keys.json b/Tools/test_keys/test_keys.json index 127a5be598d5..0421279c87b9 100644 --- a/Tools/test_keys/test_keys.json +++ b/Tools/test_keys/test_keys.json @@ -1 +1 @@ -{"date": "Tue Nov 3 13:02:09 2020", "public": "4db0c20105552a3cd7fbaf5cba7ab0811b3663db28525edb1436f2578d02b7fd", "private": "734d597e7d8ab0a1d0d64b95083aa6bee34b46b9e6e76dac1e363af114f12d15"} \ No newline at end of file +{"date": "Tue Nov 3 13:02:09 2020", "public": "4db0c20105552a3cd7fbaf5cba7ab0811b3663db28525edb1436f2578d02b7fd", "private": "734d597e7d8ab0a1d0d64b95083aa6bee34b46b9e6e76dac1e363af114f12d15"} diff --git a/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp b/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp index cf7e9283428b..93ad304a9719 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp +++ b/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.cpp @@ -314,4 +314,4 @@ int elrs_led_main(int argc, char *argv[]) } return 0; -} \ No newline at end of file +} diff --git a/boards/modalai/voxl2/cmake/init.cmake b/boards/modalai/voxl2/cmake/init.cmake index e5a4daad5f8b..357d1d45ec1d 100644 --- a/boards/modalai/voxl2/cmake/init.cmake +++ b/boards/modalai/voxl2/cmake/init.cmake @@ -31,4 +31,4 @@ # ############################################################################ -include_directories(${PX4_BOARD_DIR}/libfc-sensor-api/inc) \ No newline at end of file +include_directories(${PX4_BOARD_DIR}/libfc-sensor-api/inc) diff --git a/boards/modalai/voxl2/scripts/patch-gazebo.sh b/boards/modalai/voxl2/scripts/patch-gazebo.sh index 9e8b22cf60d9..bb31b99b1241 100755 --- a/boards/modalai/voxl2/scripts/patch-gazebo.sh +++ b/boards/modalai/voxl2/scripts/patch-gazebo.sh @@ -10,4 +10,4 @@ cd - cd Tools/simulation/gazebo-classic/sitl_gazebo-classic/models/iris_vision patch < ../../../../../../boards/modalai/voxl2/gazebo-docker/patch/iris_vision.patch -cd - \ No newline at end of file +cd - diff --git a/boards/modalai/voxl2/src/board_config.h b/boards/modalai/voxl2/src/board_config.h index a83f28966bfe..9bc7247e9d61 100644 --- a/boards/modalai/voxl2/src/board_config.h +++ b/boards/modalai/voxl2/src/board_config.h @@ -52,4 +52,4 @@ #define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_VOXL2 #define VOXL_ESC_DEFAULT_PORT "2" -#define VOXL2_IO_DEFAULT_PORT "2" \ No newline at end of file +#define VOXL2_IO_DEFAULT_PORT "2" diff --git a/msg/DatamanRequest.msg b/msg/DatamanRequest.msg index f819771a4528..b65386cc1562 100644 --- a/msg/DatamanRequest.msg +++ b/msg/DatamanRequest.msg @@ -5,4 +5,4 @@ uint8 request_type # id/read/write/clear uint8 item # dm_item_t uint32 index uint8[56] data -uint32 data_length \ No newline at end of file +uint32 data_length diff --git a/msg/DebugArray.msg b/msg/DebugArray.msg index 4763a0f5a0ee..0c79d61dfed4 100644 --- a/msg/DebugArray.msg +++ b/msg/DebugArray.msg @@ -2,4 +2,4 @@ uint8 ARRAY_SIZE = 58 uint64 timestamp # time since system start (microseconds) uint16 id # unique ID of debug array, used to discriminate between arrays char[10] name # name of the debug array (max. 10 characters) -float32[58] data # data \ No newline at end of file +float32[58] data # data diff --git a/msg/InputRc.msg b/msg/InputRc.msg index db4b3de233f5..782477407e33 100644 --- a/msg/InputRc.msg +++ b/msg/InputRc.msg @@ -37,4 +37,4 @@ uint8 input_source # Input source uint16[18] values # measured pulse widths for each of the supported channels int8 link_quality # link quality. Percentage 0-100%. -1 = invalid -float32 rssi_dbm # Actual rssi in units of dBm. NaN = invalid \ No newline at end of file +float32 rssi_dbm # Actual rssi in units of dBm. NaN = invalid diff --git a/msg/ParameterSetValueResponse.msg b/msg/ParameterSetValueResponse.msg index 09f8e3084a80..0bf94a190bf2 100644 --- a/msg/ParameterSetValueResponse.msg +++ b/msg/ParameterSetValueResponse.msg @@ -6,4 +6,4 @@ uint16 parameter_index uint8 ORB_QUEUE_LENGTH = 4 -# TOPICS parameter_set_value_response parameter_remote_set_value_response parameter_primary_set_value_response \ No newline at end of file +# TOPICS parameter_set_value_response parameter_remote_set_value_response parameter_primary_set_value_response diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 28b8485a12aa..f67356be701a 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -1137,4 +1137,4 @@ bootloader(unsigned timeout) continue; #endif } -} \ No newline at end of file +} diff --git a/platforms/nuttx/src/bootloader/common/bl.h b/platforms/nuttx/src/bootloader/common/bl.h index 377164a28ec9..080bc47e0f33 100644 --- a/platforms/nuttx/src/bootloader/common/bl.h +++ b/platforms/nuttx/src/bootloader/common/bl.h @@ -138,4 +138,4 @@ extern void cout(uint8_t *buf, unsigned len); #if !defined(APP_VECTOR_OFFSET) # define APP_VECTOR_OFFSET 0 #endif -#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t)) \ No newline at end of file +#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t)) diff --git a/platforms/nuttx/src/px4/common/CMakeLists.txt b/platforms/nuttx/src/px4/common/CMakeLists.txt index f6c25c26f320..c74810b03a88 100644 --- a/platforms/nuttx/src/px4/common/CMakeLists.txt +++ b/platforms/nuttx/src/px4/common/CMakeLists.txt @@ -83,4 +83,4 @@ add_subdirectory(srgbled) if (DEFINED PX4_CRYPTO) add_library(px4_random nuttx_random.c) target_link_libraries(px4_random PRIVATE nuttx_crypto) -endif() \ No newline at end of file +endif() diff --git a/platforms/nuttx/src/px4/nxp/imxrt/board_hw_info/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/imxrt/board_hw_info/CMakeLists.txt index cc1563990c4a..1bc35a48eb70 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/board_hw_info/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/imxrt/board_hw_info/CMakeLists.txt @@ -34,4 +34,4 @@ px4_add_library(arch_board_hw_info board_hw_rev_ver.c ) -target_link_libraries(arch_board_hw_info PRIVATE arch_adc crc) \ No newline at end of file +target_link_libraries(arch_board_hw_info PRIVATE arch_adc crc) diff --git a/platforms/qurt/src/px4/qurt_log.cpp b/platforms/qurt/src/px4/qurt_log.cpp index 239f9e52b87f..bc6bf2b44ac1 100644 --- a/platforms/qurt/src/px4/qurt_log.cpp +++ b/platforms/qurt/src/px4/qurt_log.cpp @@ -45,4 +45,4 @@ extern "C" void qurt_log_to_apps(int level, const char *message) else { ch->send_message("slpi_debug", strlen(message) + 1, (uint8_t *) message); } } -} \ No newline at end of file +} diff --git a/src/drivers/actuators/voxl_esc/module.yaml b/src/drivers/actuators/voxl_esc/module.yaml index 1e227ae0b71d..c3bb1f4e6ed3 100644 --- a/src/drivers/actuators/voxl_esc/module.yaml +++ b/src/drivers/actuators/voxl_esc/module.yaml @@ -38,4 +38,4 @@ parameters: reboot_required: true num_instances: 1 instance_start: 1 - default: 0 \ No newline at end of file + default: 0 diff --git a/src/drivers/cdcacm_autostart/Kconfig b/src/drivers/cdcacm_autostart/Kconfig index aabfaad4838e..575d7a31fd18 100644 --- a/src/drivers/cdcacm_autostart/Kconfig +++ b/src/drivers/cdcacm_autostart/Kconfig @@ -3,4 +3,4 @@ menuconfig DRIVERS_CDCACM_AUTOSTART default n depends on MODULES_MAVLINK ---help--- - Enable support for cdcacm_autostart \ No newline at end of file + Enable support for cdcacm_autostart diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c b/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c index 3dcc16ad2f4f..20d436ba0601 100644 --- a/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c @@ -65,4 +65,4 @@ PARAM_DEFINE_INT32(SYS_USB_AUTO, 2); * * @group CDCACM */ -PARAM_DEFINE_INT32(USB_MAV_MODE, 2); \ No newline at end of file +PARAM_DEFINE_INT32(USB_MAV_MODE, 2); diff --git a/src/drivers/voxl2_io/Kconfig b/src/drivers/voxl2_io/Kconfig index 15964deeeb90..622cad470d06 100644 --- a/src/drivers/voxl2_io/Kconfig +++ b/src/drivers/voxl2_io/Kconfig @@ -2,4 +2,4 @@ menuconfig DRIVERS_VOXL2_IO bool "voxl2_io" default n ---help--- - Enable support for voxl2_io \ No newline at end of file + Enable support for voxl2_io diff --git a/src/lib/parameters/parameters_primary.cpp b/src/lib/parameters/parameters_primary.cpp index 02de11e608d0..3d61fe167a15 100644 --- a/src/lib/parameters/parameters_primary.cpp +++ b/src/lib/parameters/parameters_primary.cpp @@ -311,4 +311,4 @@ void param_primary_reset_all() void param_primary_get_counters(struct param_primary_counters *cnt) { *cnt = param_primary_counters; -} \ No newline at end of file +} diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp index be4aaf9b23e4..b08fc895ab9c 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp @@ -479,4 +479,4 @@ fw_att_control is the fixed wing attitude controller. extern "C" __EXPORT int fw_att_control_main(int argc, char *argv[]) { return FixedwingAttitudeControl::main(argc, argv); -} \ No newline at end of file +} From f2bca92221301493e0b87b5aa50efca231b518b5 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 22 May 2024 14:21:56 +0200 Subject: [PATCH 517/652] Fix duplicate newlines at the end of files --- .github/workflows/deploy_all.yml | 1 - .../init.d-posix/airframes/10017_jmavsim_iris | 1 - .../10018_gazebo-classic_iris_foggy_lidar | 1 - .../airframes/10019_gazebo-classic_omnicopter | 1 - .../airframes/10030_gazebo-classic_px4vision | 1 - .../1012_gazebo-classic_iris_rplidar | 1 - .../airframes/1013_gazebo-classic_iris_vision | 1 - .../1021_gazebo-classic_uuv_hippocampus | 1 - .../1022_gazebo-classic_uuv_bluerov2_heavy | 1 - .../airframes/1030_gazebo-classic_plane | 2 - .../1032_gazebo-classic_plane_catapult | 1 - .../init.d-posix/airframes/1033_jsbsim_rascal | 1 - .../airframes/1035_gazebo-classic_techpod | 1 - .../init.d-posix/airframes/1036_jsbsim_malolo | 1 - .../airframes/1037_gazebo-classic_believer | 1 - .../1040_gazebo-classic_standard_vtol | 1 - .../airframes/1041_gazebo-classic_tailsitter | 1 - .../1043_gazebo-classic_standard_vtol_drop | 1 - .../airframes/1060_gazebo-classic_rover | 1 - .../airframes/1062_flightgear_tf-r1 | 1 - .../airframes/1070_gazebo-classic_boat | 1 - .../airframes/17001_flightgear_tf-g1 | 1 - .../airframes/17002_flightgear_tf-g2 | 1 - .../airframes/2507_gazebo-classic_cloudship | 1 - .../6011_gazebo-classic_typhoon_h480 | 1 - .../init.d-posix/airframes/8011_gz_omnicopter | 1 - .../init.d/airframes/11001_hexa_cox | 1 - .../init.d/airframes/13014_vtol_babyshark | 2 - .../airframes/14001_generic_mc_with_tilt | 1 - .../init.d/airframes/16001_helicopter | 2 - .../init.d/airframes/18001_TF-B1 | 1 - .../init.d/airframes/2106_albatross | 2 - .../init.d/airframes/24001_dodeca_cox | 1 - .../init.d/airframes/2507_cloudship | 1 - .../airframes/50000_generic_ground_vehicle | 2 - .../init.d/airframes/60000_uuv_generic | 1 - .../init.d/airframes/6001_hexa_x | 2 - .../init.d/airframes/6002_draco_r | 1 - .../init.d/airframes/7001_hexa_+ | 2 - .../init.d/airframes/8001_octo_x | 2 - .../init.d/airframes/9001_octo_+ | 1 - Tools/Matlab/ellipsoid_fit.m | 14 +- Tools/cryptotools.py | 1 - Tools/ecl_ekf/analyse_logdata_ekf.py | 4 - Tools/mavlink_shell.py | 1 - Tools/mavlink_ulog_streaming.py | 1 - Tools/serial/generate_config.py | 1 - Tools/serial/rc.serial.jinja | 1 - Tools/serial/serial_params.c.jinja | 1 - Tools/upload_log.py | 1 - Tools/validate_json.py | 1 - Tools/validate_yaml.py | 1 - boards/airmind/mindpx-v2/src/i2c.cpp | 1 - boards/airmind/mindpx-v2/src/usb.c | 1 - boards/atl/mantis-edu/upload.sh | 1 - boards/av/x-v1/nuttx-config/include/board.h | 1 - boards/beaglebone/blue/src/board_pwm_out.cpp | 1 - boards/bitcraze/crazyflie/src/usb.c | 1 - boards/bitcraze/crazyflie21/src/usb.c | 1 - .../cubeorange/init/rc.board_sensors | 1 - .../cubeorangeplus/init/rc.board_sensors | 1 - .../cubeyellow/init/rc.board_sensors | 1 - boards/emlid/navio2/init/rc.board_defaults | 1 - boards/emlid/navio2/src/board_pwm_out.cpp | 1 - boards/flywoo/gn-f405/init/rc.board_extras | 2 - .../can-rtk-gps/nuttx-config/include/board.h | 1 - .../nuttx-config/include/board_dma_map.h | 1 - boards/holybro/kakutef7/init/rc.board_extras | 1 - .../kakutef7/nuttx-config/include/board.h | 1 - .../nuttx-config/include/board_dma_map.h | 1 - boards/holybro/kakutef7/src/led.c | 1 - .../holybro/kakuteh7/init/rc.board_defaults | 1 - boards/holybro/kakuteh7/init/rc.board_extras | 1 - .../kakuteh7/nuttx-config/include/board.h | 1 - .../nuttx-config/include/board_dma_map.h | 1 - .../holybro/kakuteh7mini/init/rc.board_extras | 1 - .../kakuteh7mini/nuttx-config/include/board.h | 1 - .../nuttx-config/include/board_dma_map.h | 1 - .../holybro/kakuteh7v2/init/rc.board_extras | 1 - .../kakuteh7v2/nuttx-config/include/board.h | 1 - .../nuttx-config/include/board_dma_map.h | 1 - boards/matek/h743-mini/init/rc.board_extras | 2 - boards/matek/h743-slim/init/rc.board_extras | 1 - boards/matek/h743/init/rc.board_extras | 1 - boards/modalai/fc-v2/scripts/run_docker.sh | 1 - .../src/drivers/elrs_led/elrs_led.h | 3 - .../src/drivers/ghst_rc/ghst_rc.hpp | 1 - .../src/drivers/ghst_rc/module.yaml | 1 - .../src/drivers/spektrum_rc/CMakeLists.txt | 1 - .../mro/x21-777/nuttx-config/include/board.h | 1 - boards/nxp/fmuk66-v3/init/rc.board_defaults | 1 - boards/omnibus/f4sd/init/rc.board_extras | 2 - boards/px4/fmu-v4/src/usb.c | 1 - boards/px4/fmu-v4pro/src/timer_config.cpp | 1 - .../raspberrypi/pico/init/rc.board_defaults | 1 - boards/raspberrypi/pico/src/usb.c | 1 - boards/siyi/n7/nuttx-config/include/board.h | 3 - .../n7/nuttx-config/include/board_dma_map.h | 1 - .../smartap-airlink/init/rc.board_sensors | 1 - .../spracing/h7extreme/init/rc.board_extras | 2 - .../spracing/h7extreme/nuttx-config/Kconfig | 5 +- .../spracing/h7extreme/src/timer_config.cpp | 1 - boards/uvify/core/src/usb.c | 1 - cmake/doxygen.cmake | 1 - .../python_src/px4_it/util/manual_input.py | 1 - .../python_src/px4_it/util/px4_test_helper.py | 1 - msg/Buffer128.msg | 1 - msg/FailsafeFlags.msg | 2 - msg/MessageFormatResponse.msg | 1 - msg/ModeCompleted.msg | 1 - platforms/common/external_reset_lockout.cpp | 1 - .../external_reset_lockout.h | 3 - .../common/include/px4_platform_common/log.h | 1 - platforms/common/module.cpp | 1 - platforms/common/uORB/uORB.h | 1 - platforms/common/work_queue/dq_addlast.c | 1 - platforms/common/work_queue/dq_rem.c | 1 - platforms/common/work_queue/dq_remfirst.c | 1 - platforms/common/work_queue/queue.c | 2 - platforms/common/work_queue/sq_addlast.c | 1 - platforms/common/work_queue/sq_remfirst.c | 1 - .../nuttx/Debug/jtrace_debug_ozone.jdebug | 475 +++++++++--------- platforms/nuttx/src/px4/CMakeLists.txt | 2 - .../px4/common/gpio/mcp23009/CMakeLists.txt | 1 - .../src/px4/common/include/px4_platform/adc.h | 1 - .../common/include/px4_platform/micro_hal.h | 1 - .../nuttx/src/px4/common/usr_mcu_version.cpp | 1 - platforms/nuttx/src/px4/nxp/CMakeLists.txt | 2 - .../nuttx/src/px4/nxp/k66/CMakeLists.txt | 3 - .../src/px4/nxp/k66/include/px4_arch/adc.h | 1 - .../px4/nxp/k66/include/px4_arch/io_timer.h | 2 - .../src/px4/nxp/kinetis/hrt/CMakeLists.txt | 1 - .../px4/nxp/kinetis/include/px4_arch/adc.h | 2 - .../src/px4/rpi/rp2040/include/px4_arch/adc.h | 1 - .../include/px4_arch/i2c_hw_description.h | 1 - .../px4/rpi/rpi_common/include/px4_arch/adc.h | 1 - platforms/nuttx/src/px4/stm/CMakeLists.txt | 2 - .../stm/stm32_common/include/px4_arch/adc.h | 1 - .../include/px4_arch/px4io_serial.h | 1 - .../px4/stm/stm32f1/include/px4_arch/dshot.h | 1 - .../nuttx/src/px4/stm/stm32f1/io_timer.h | 2 - .../nuttx/src/px4/stm/stm32f3/CMakeLists.txt | 2 - .../px4/stm/stm32f3/include/px4_arch/adc.h | 1 - .../stm/stm32f3/include/px4_arch/io_timer.h | 2 - .../stm/stm32f3/include/px4_arch/micro_hal.h | 1 - .../nuttx/src/px4/stm/stm32f4/CMakeLists.txt | 1 - .../px4/stm/stm32f4/include/px4_arch/adc.h | 1 - .../px4/stm/stm32f4/include/px4_arch/dshot.h | 1 - .../include/px4_arch/i2c_hw_description.h | 1 - .../stm/stm32f4/include/px4_arch/micro_hal.h | 1 - .../stm32f4/include/px4_arch/px4io_serial.h | 1 - .../stm/stm32f4/px4io_serial/px4io_serial.cpp | 1 - .../px4/stm/stm32f7/include/px4_arch/adc.h | 1 - .../px4/stm/stm32f7/include/px4_arch/dshot.h | 1 - .../stm/stm32f7/include/px4_arch/io_timer.h | 2 - .../stm/stm32f7/include/px4_arch/micro_hal.h | 1 - .../stm32f7/include/px4_arch/px4io_serial.h | 1 - .../stm/stm32f7/px4io_serial/px4io_serial.cpp | 1 - platforms/posix/include/hrt_work.h | 1 - platforms/posix/include/queue.h | 1 - platforms/posix/src/px4/CMakeLists.txt | 1 - .../lockstep_scheduler/lockstep_components.h | 1 - .../src/px4/common/px4_daemon/CMakeLists.txt | 1 - .../posix/src/px4/common/px4_daemon/client.h | 1 - .../posix/src/px4/common/px4_daemon/history.h | 1 - .../posix/src/px4/common/px4_daemon/pxh.h | 1 - .../posix/src/px4/common/px4_daemon/server.h | 1 - .../px4/common/px4_daemon/sock_protocol.cpp | 1 - .../src/px4/common/px4_daemon/sock_protocol.h | 1 - .../posix/src/px4/common/px4_posix_impl.cpp | 1 - .../posix/src/px4/generic/CMakeLists.txt | 2 - .../src/px4/generic/generic/CMakeLists.txt | 2 - .../generic/include/px4_arch/micro_hal.h | 1 - .../generic/tone_alarm/ToneAlarmInterface.cpp | 1 - platforms/qurt/include/px4_arch/micro_hal.h | 1 - platforms/qurt/include/queue.h | 1 - .../px4/common/include/px4_platform/cpuload.h | 1 - platforms/ros2/include/hrt_work.h | 1 - platforms/ros2/include/queue.h | 1 - platforms/ros2/src/px4/CMakeLists.txt | 1 - .../generic/include/px4_arch/micro_hal.h | 1 - posix-configs/rpi/px4_hil.config | 1 - .../actuators/voxl_esc/voxl_esc_params.c | 1 - src/drivers/adc/ads1115/ads1115_params.c | 1 - src/drivers/barometer/bmp581/bmp581_i2c.cpp | 1 - .../camera_trigger/camera_trigger_params.c | 1 - .../differential_pressure/asp5033/ASP5033.hpp | 1 - .../lightware_laser_i2c/CMakeLists.txt | 1 - .../lightware_laser_serial/module.yaml | 1 - .../distance_sensor/tfmini/module.yaml | 1 - src/drivers/dshot/DShotTelemetry.cpp | 1 - src/drivers/gnss/septentrio/README.md | 2 +- src/drivers/gps/CMakeLists.txt | 2 +- src/drivers/gps/module.yaml | 1 - src/drivers/gps/params.c | 2 +- .../imu/nxp/fxos8701cq/fxos8701cq_spi.cpp | 1 - .../vectornav/libvnc/include/vn/math/matrix.h | 1 - .../magnetometer/hmc5883/CMakeLists.txt | 1 - src/drivers/osd/atxxxx/symbols.h | 1 - .../MessageDisplay/MessageDisplayTest.cpp | 1 - src/drivers/osd/msp_osd/MspV1.hpp | 1 - src/drivers/osd/msp_osd/msp_defines.h | 1 - src/drivers/osd/msp_osd/msp_osd.hpp | 1 - src/drivers/pwm_out/module.yaml | 1 - src/drivers/rc_input/ghst_telemetry.cpp | 1 - src/drivers/rc_input/module.yaml | 1 - src/drivers/rpi_rc_in/CMakeLists.txt | 1 - src/drivers/rpi_rc_in/rpi_rc_in.cpp | 1 - src/drivers/telemetry/bst/CMakeLists.txt | 1 - .../telemetry/frsky_telemetry/CMakeLists.txt | 1 - .../telemetry/frsky_telemetry/module.yaml | 1 - .../hott/hott_sensors/CMakeLists.txt | 1 - .../telemetry/hott/hott_telemetry/module.yaml | 1 - src/drivers/telemetry/iridiumsbd/module.yaml | 1 - src/drivers/test_ppm/CMakeLists.txt | 1 - src/drivers/voxl2_io/module.yaml | 1 - src/drivers/voxl2_io/voxl2_io_params.c | 1 - src/lib/heatshrink/CMakeLists.txt | 1 - src/lib/heatshrink/heatshrink_encode.py | 1 - src/lib/matrix/matrix/Dual.hpp | 1 - src/lib/metadata/CMakeLists.txt | 1 - src/lib/parameters/autosave.cpp | 1 - src/lib/parameters/parameters_primary.h | 1 - src/lib/parameters/px4params/jsonout.py | 1 - src/lib/rc/ghst.cpp | 1 - src/lib/rc/rc_tests/RCTest.cpp | 3 - src/lib/tecs/TECS.hpp | 1 - .../version/get_git_tag_or_branch_version.sh | 1 - src/lib/version/version.c | 1 - src/lib/version/version.h | 1 - .../geo_magnetic_tables.hpp | 2 - .../attitude_estimator_q/CMakeLists.txt | 1 - .../HealthAndArmingChecks.hpp | 1 - .../HealthAndArmingChecksTest.cpp | 1 - .../HealthAndArmingChecks/checks/escCheck.cpp | 1 - .../checks/estimatorCheck.cpp | 1 - src/modules/commander/ModeUtil/CMakeLists.txt | 1 - .../commander/factory_calibration_storage.cpp | 1 - src/modules/commander/failsafe/failsafe.h | 1 - src/modules/commander/failsafe/framework.h | 1 - .../failsafe/parse_flags_from_msg.py | 1 - src/modules/commander/lm_fit.cpp | 1 - src/modules/commander/px4_custom_mode.h | 1 - src/modules/commander/worker_thread.hpp | 1 - .../ActuatorEffectivenessRoverAckermann.cpp | 1 - .../aid_sources/magnetometer/mag_control.cpp | 1 - src/modules/gimbal/CMakeLists.txt | 1 - src/modules/gimbal/output.cpp | 1 - .../CMSIS/Core/Include/cmsis_compiler.h | 1 - .../CMSIS/DSP/Include/arm_common_tables.h | 1 - src/modules/land_detector/CMakeLists.txt | 1 - .../landing_target_estimator/CMakeLists.txt | 1 - src/modules/mavlink/module.yaml | 1 - src/modules/mc_att_control/mc_att_control.hpp | 1 - src/modules/px4iofirmware/serial.cpp | 1 - src/modules/simulation/gz_bridge/parameters.c | 1 - src/modules/vtol_att_control/CMakeLists.txt | 1 - src/systemcmds/actuator_test/CMakeLists.txt | 1 - src/systemcmds/dumpfile/CMakeLists.txt | 1 - src/systemcmds/led_control/CMakeLists.txt | 1 - src/systemcmds/mtd/CMakeLists.txt | 1 - src/systemcmds/nshterm/CMakeLists.txt | 1 - src/systemcmds/reboot/CMakeLists.txt | 1 - src/systemcmds/reflect/CMakeLists.txt | 1 - src/systemcmds/sd_bench/CMakeLists.txt | 1 - src/systemcmds/serial_test/.gitignore | 1 - src/systemcmds/tests/test_file2.c | 1 - src/systemcmds/topic_listener/CMakeLists.txt | 1 - src/systemcmds/usb_connected/CMakeLists.txt | 1 - src/templates/template_module/CMakeLists.txt | 1 - .../template_module/template_module.h | 1 - test/mavsdk_tests/catch2/catch.hpp | 1 - .../test_multicopter_failure_injection.cpp | 1 - validation/module_schema.yaml | 2 - 274 files changed, 248 insertions(+), 560 deletions(-) diff --git a/.github/workflows/deploy_all.yml b/.github/workflows/deploy_all.yml index b4b6ebc814ea..3f1a4c0049b1 100644 --- a/.github/workflows/deploy_all.yml +++ b/.github/workflows/deploy_all.yml @@ -54,4 +54,3 @@ jobs: AWS_REGION: 'us-west-1' SOURCE_DIR: 'build/${{ matrix.target }}/_metadata/' DEST_DIR: 'Firmware/${{ env.version }}/${{ matrix.target }}/' - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10017_jmavsim_iris b/ROMFS/px4fmu_common/init.d-posix/airframes/10017_jmavsim_iris index fbf554091555..4cd88cc111df 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10017_jmavsim_iris +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10017_jmavsim_iris @@ -29,4 +29,3 @@ param set-default PWM_MAIN_FUNC1 101 param set-default PWM_MAIN_FUNC2 102 param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10018_gazebo-classic_iris_foggy_lidar b/ROMFS/px4fmu_common/init.d-posix/airframes/10018_gazebo-classic_iris_foggy_lidar index 161a32492009..c929125c47f7 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10018_gazebo-classic_iris_foggy_lidar +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10018_gazebo-classic_iris_foggy_lidar @@ -30,4 +30,3 @@ param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 param set-default EKF2_RNG_A_HMAX 10 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10019_gazebo-classic_omnicopter b/ROMFS/px4fmu_common/init.d-posix/airframes/10019_gazebo-classic_omnicopter index 36bed6a03bc6..765d3c9b0c89 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10019_gazebo-classic_omnicopter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10019_gazebo-classic_omnicopter @@ -94,4 +94,3 @@ param set-default CA_METHOD 0 # disable attitude failure detection param set-default FD_FAIL_P 0 param set-default FD_FAIL_R 0 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10030_gazebo-classic_px4vision b/ROMFS/px4fmu_common/init.d-posix/airframes/10030_gazebo-classic_px4vision index b82481b7c9e5..f2abb94e2333 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10030_gazebo-classic_px4vision +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10030_gazebo-classic_px4vision @@ -12,4 +12,3 @@ param set-default PWM_MAIN_FUNC1 101 param set-default PWM_MAIN_FUNC2 102 param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1012_gazebo-classic_iris_rplidar b/ROMFS/px4fmu_common/init.d-posix/airframes/1012_gazebo-classic_iris_rplidar index 3fd2ef636f4d..952be680bf4c 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1012_gazebo-classic_iris_rplidar +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1012_gazebo-classic_iris_rplidar @@ -30,4 +30,3 @@ param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 param set-default LPE_FUSION 242 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1013_gazebo-classic_iris_vision b/ROMFS/px4fmu_common/init.d-posix/airframes/1013_gazebo-classic_iris_vision index df11976012a3..de17714dff8f 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1013_gazebo-classic_iris_vision +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1013_gazebo-classic_iris_vision @@ -18,4 +18,3 @@ param set-default LPE_FUSION 132 # AEQ: External heading set to use vision input param set-default ATT_EXT_HDG_M 1 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1021_gazebo-classic_uuv_hippocampus b/ROMFS/px4fmu_common/init.d-posix/airframes/1021_gazebo-classic_uuv_hippocampus index f6f07d700ef7..59c009bed966 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1021_gazebo-classic_uuv_hippocampus +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1021_gazebo-classic_uuv_hippocampus @@ -41,4 +41,3 @@ param set-default PWM_MAIN_FUNC1 101 param set-default PWM_MAIN_FUNC2 102 param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_gazebo-classic_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_gazebo-classic_uuv_bluerov2_heavy index 0c6c802f8d21..6f742e4fe88c 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_gazebo-classic_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_gazebo-classic_uuv_bluerov2_heavy @@ -61,4 +61,3 @@ param set-default PWM_MAIN_FUNC5 105 param set-default PWM_MAIN_FUNC6 106 param set-default PWM_MAIN_FUNC7 107 param set-default PWM_MAIN_FUNC8 108 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane b/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane index f203ee14cc48..dc45a34029bf 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane @@ -68,5 +68,3 @@ param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_FUNC8 203 param set-default PWM_MAIN_FUNC9 206 param set-default PWM_MAIN_REV 256 - - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult b/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult index f8fd54636649..7963669c858a 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult @@ -71,4 +71,3 @@ param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_FUNC8 203 param set-default PWM_MAIN_FUNC9 206 param set-default PWM_MAIN_REV 256 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal b/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal index f4d9ce42e096..ef9df5af984e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1033_jsbsim_rascal @@ -55,4 +55,3 @@ param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_FUNC8 203 param set-default PWM_MAIN_FUNC9 206 param set-default PWM_MAIN_REV 256 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1035_gazebo-classic_techpod b/ROMFS/px4fmu_common/init.d-posix/airframes/1035_gazebo-classic_techpod index a8b29db64c6b..68bb1420949d 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1035_gazebo-classic_techpod +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1035_gazebo-classic_techpod @@ -54,4 +54,3 @@ param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_FUNC8 203 param set-default PWM_MAIN_FUNC9 206 param set-default PWM_MAIN_REV 256 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo b/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo index f4d9ce42e096..ef9df5af984e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1036_jsbsim_malolo @@ -55,4 +55,3 @@ param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_FUNC8 203 param set-default PWM_MAIN_FUNC9 206 param set-default PWM_MAIN_REV 256 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1037_gazebo-classic_believer b/ROMFS/px4fmu_common/init.d-posix/airframes/1037_gazebo-classic_believer index 83f63cec3842..0a8343a4c889 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1037_gazebo-classic_believer +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1037_gazebo-classic_believer @@ -62,4 +62,3 @@ param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_FUNC8 203 param set-default PWM_MAIN_FUNC9 206 param set-default PWM_MAIN_REV 256 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol index 0e25b5633037..2324f9588571 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol @@ -78,4 +78,3 @@ param set-default VT_FWD_THRUST_EN 4 param set-default VT_FWD_THRUST_SC 1 param set-default VT_F_TRANS_THR 0.75 param set-default VT_TYPE 2 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter index 8a3d5d1a4965..a803fcee3cde 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter @@ -75,4 +75,3 @@ param set-default VT_F_TRANS_DUR 1.5 param set-default VT_TYPE 0 param set-default WV_EN 0 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop b/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop index 29f09dc47c9d..eadf0d4e0249 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop @@ -88,4 +88,3 @@ param set-default PWM_MAIN_FUNC11 422 param set-default RC_MAP_AUX1 8 param set-default RC_MAP_AUX2 9 param set-default RC_MAP_AUX3 10 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_gazebo-classic_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/1060_gazebo-classic_rover index ab8d12109205..920d022f2107 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_gazebo-classic_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1060_gazebo-classic_rover @@ -31,4 +31,3 @@ param set-default PWM_MAIN_FUNC1 201 param set-default PWM_MAIN_FUNC2 201 param set-default PWM_MAIN_FUNC6 101 param set-default PWM_MAIN_FUNC7 101 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1062_flightgear_tf-r1 b/ROMFS/px4fmu_common/init.d-posix/airframes/1062_flightgear_tf-r1 index f3a6cd1aded5..75cbe5b5dfaf 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1062_flightgear_tf-r1 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1062_flightgear_tf-r1 @@ -38,4 +38,3 @@ param set-default PWM_MAIN_FUNC1 201 param set-default PWM_MAIN_FUNC2 201 param set-default PWM_MAIN_FUNC6 101 param set-default PWM_MAIN_FUNC7 101 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1070_gazebo-classic_boat b/ROMFS/px4fmu_common/init.d-posix/airframes/1070_gazebo-classic_boat index 01ada36f3510..fce37ecde279 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1070_gazebo-classic_boat +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1070_gazebo-classic_boat @@ -41,4 +41,3 @@ param set-default CA_R_REV 3 param set-default PWM_MAIN_FUNC1 101 param set-default PWM_MAIN_FUNC2 102 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/17001_flightgear_tf-g1 b/ROMFS/px4fmu_common/init.d-posix/airframes/17001_flightgear_tf-g1 index 9c9b2c7f6312..dd3b5759bab0 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/17001_flightgear_tf-g1 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/17001_flightgear_tf-g1 @@ -64,4 +64,3 @@ param set-default PWM_MAIN_FUNC4 203 param set-default PWM_MAIN_FUNC5 407 param set-default PWM_MAIN_FUNC6 408 param set-default PWM_MAIN_FUNC7 409 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/17002_flightgear_tf-g2 b/ROMFS/px4fmu_common/init.d-posix/airframes/17002_flightgear_tf-g2 index 74b6d2a31679..ffb9ef2235e5 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/17002_flightgear_tf-g2 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/17002_flightgear_tf-g2 @@ -69,4 +69,3 @@ param set-default PWM_MAIN_FUNC4 203 param set-default PWM_MAIN_FUNC5 407 param set-default PWM_MAIN_FUNC6 408 param set-default PWM_MAIN_FUNC7 409 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/2507_gazebo-classic_cloudship b/ROMFS/px4fmu_common/init.d-posix/airframes/2507_gazebo-classic_cloudship index 153247203da6..b0eb3bbddc8f 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/2507_gazebo-classic_cloudship +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/2507_gazebo-classic_cloudship @@ -36,4 +36,3 @@ param set-default PWM_MAIN_FUNC1 101 param set-default PWM_MAIN_FUNC2 102 param set-default PWM_MAIN_FUNC3 201 param set-default PWM_MAIN_FUNC4 103 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 index 0174411c73a6..f75374b15c64 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 @@ -63,4 +63,3 @@ param set-default PWM_MAIN_FUNC9 422 # Landing gear param set-default PWM_MAIN_FUNC10 400 param set-default PWM_MAIN_FUNC11 400 - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/8011_gz_omnicopter b/ROMFS/px4fmu_common/init.d-posix/airframes/8011_gz_omnicopter index 707df1bba118..b43b61025c2e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/8011_gz_omnicopter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/8011_gz_omnicopter @@ -119,4 +119,3 @@ param set-default CA_METHOD 0 # disable attitude failure detection param set-default FD_FAIL_P 0 param set-default FD_FAIL_R 0 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox index 5424cbf9a27e..754d048ef89d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox @@ -44,4 +44,3 @@ param set-default CA_ROTOR4_KM -0.05 param set-default CA_ROTOR5_PX 0.25 param set-default CA_ROTOR5_PY -0.433 param set-default CA_ROTOR5_PZ 0.05 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark index cc8db21732a1..ee98e2c889ea 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark +++ b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark @@ -119,5 +119,3 @@ param set-default PWM_MAIN_TIM0 50 param set-default PWM_MAIN_DIS1 1500 param set-default PWM_MAIN_DIS2 1500 param set-default PWM_MAIN_DIS4 1500 - - diff --git a/ROMFS/px4fmu_common/init.d/airframes/14001_generic_mc_with_tilt b/ROMFS/px4fmu_common/init.d/airframes/14001_generic_mc_with_tilt index 3eb558c46e78..9bd320f85c22 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/14001_generic_mc_with_tilt +++ b/ROMFS/px4fmu_common/init.d/airframes/14001_generic_mc_with_tilt @@ -32,4 +32,3 @@ param set-default CA_SV_TL0_MAXA 45 param set-default CA_SV_TL0_MINA -45 param set-default CA_SV_TL0_TD 90 param set-default CA_SV_TL_COUNT 1 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter index 36f1a68f1472..de21a8821668 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter +++ b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter @@ -24,5 +24,3 @@ param set-default MC_PITCHRATE_D 0 param set-default MC_PITCHRATE_FF 0.1 param set-default CA_AIRFRAME 10 - - diff --git a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 index 90965eeb32db..d657af7d57bd 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 +++ b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 @@ -23,4 +23,3 @@ param set-default MAV_0_MODE 1 param set-default MAV_0_CONFIG 102 param set-default GPS_UBX_DYNMODEL 8 param set-default SER_TEL2_BAUD 9600 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/2106_albatross b/ROMFS/px4fmu_common/init.d/airframes/2106_albatross index feac59e94ef5..e27d146e0301 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2106_albatross +++ b/ROMFS/px4fmu_common/init.d/airframes/2106_albatross @@ -72,5 +72,3 @@ param set-default PWM_MAIN_DIS5 1000 param set-default PWM_MAIN_DIS6 1500 param set-default PWM_MAIN_DIS7 1500 param set-default PWM_MAIN_DIS8 1500 - - diff --git a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox index 23944e9e0ccf..f894d47d74fd 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox @@ -66,4 +66,3 @@ param set-default CA_ROTOR11_PX -0.344 param set-default CA_ROTOR11_PY -0.25 param set-default CA_ROTOR11_PZ -0.05 param set-default CA_ROTOR11_KM -0.05 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship b/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship index 65ecfe25eb0a..82abd7e55d24 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship +++ b/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship @@ -38,4 +38,3 @@ param set-default CA_SV_CS_COUNT 1 param set-default CA_SV_CS0_TRQ_P 1 param set-default CA_R_REV 7 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle index ba4598ce832d..5ae6b09f4a8d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle +++ b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle @@ -48,5 +48,3 @@ param set-default PWM_MAIN_FUNC1 201 param set-default PWM_MAIN_FUNC2 201 param set-default PWM_MAIN_FUNC6 101 param set-default PWM_MAIN_FUNC7 101 - - diff --git a/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic b/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic index 3a9ceaa5d95f..aecf862113d7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic +++ b/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic @@ -42,4 +42,3 @@ param set-default CA_ROTOR3_KM 0 param set-default CA_ROTOR3_PX 0 param set-default CA_ROTOR3_PY -0.3 param set-default CA_ROTOR3_PZ 0.3 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x b/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x index ec8720d1dc34..016671a5f570 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x +++ b/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x @@ -31,5 +31,3 @@ param set-default CA_ROTOR4_PY 0.25 param set-default CA_ROTOR5_PX -0.43 param set-default CA_ROTOR5_PY -0.25 param set-default CA_ROTOR5_KM -0.05 - - diff --git a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r index e0eefa351bd8..7d641c272dac 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r +++ b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r @@ -123,4 +123,3 @@ param set-default PWM_MAIN_FUNC6 106 param set-default PWM_MAIN_TIM0 -1 param set-default PWM_MAIN_TIM1 -1 param set-default PWM_MAIN_TIM2 -1 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ index b22afec00ea1..872e0bb941f4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ @@ -31,5 +31,3 @@ param set-default CA_ROTOR4_PY -0.43 param set-default CA_ROTOR5_PX -0.25 param set-default CA_ROTOR5_PY 0.43 param set-default CA_ROTOR5_KM -0.05 - - diff --git a/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x b/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x index 19c112b3066a..4f2d13b24cca 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x +++ b/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x @@ -36,5 +36,3 @@ param set-default CA_ROTOR6_PY -0.46 param set-default CA_ROTOR7_KM -0.05 param set-default CA_ROTOR7_PX -0.19 param set-default CA_ROTOR7_PY 0.46 - - diff --git a/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ b/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ index 53dba8b799d4..98e45f9bef50 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ @@ -36,4 +36,3 @@ param set-default CA_ROTOR6_PY -0.5 param set-default CA_ROTOR7_KM -0.05 param set-default CA_ROTOR7_PX 0 param set-default CA_ROTOR7_PY 0.5 - diff --git a/Tools/Matlab/ellipsoid_fit.m b/Tools/Matlab/ellipsoid_fit.m index d288aa382136..ead7e6d7c355 100644 --- a/Tools/Matlab/ellipsoid_fit.m +++ b/Tools/Matlab/ellipsoid_fit.m @@ -45,7 +45,7 @@ % * center - ellispoid center coordinates [xc; yc; zc] % * ax - ellipsoid radii [a; b; c] % * evecs - ellipsoid radii directions as columns of the 3x3 matrix -% * v - the 9 parameters describing the ellipsoid algebraically: +% * v - the 9 parameters describing the ellipsoid algebraically: % Ax^2 + By^2 + Cz^2 + 2Dxy + 2Exz + 2Fyz + 2Gx + 2Hy + 2Iz = 1 % % Author: @@ -59,7 +59,7 @@ if flag == 2 && nargin == 2 equals = 'xy'; end - + if size( X, 2 ) ~= 3 error( 'Input data must have three columns!' ); else @@ -69,7 +69,7 @@ end % need nine or more data points -if length( x ) < 9 && flag == 0 +if length( x ) < 9 && flag == 0 error( 'Must have at least 9 points to fit a unique ellipsoid' ); end if length( x ) < 6 && flag == 1 @@ -91,7 +91,7 @@ 2 * x .* z, ... 2 * y .* z, ... 2 * x, ... - 2 * y, ... + 2 * y, ... 2 * z ]; % ndatapoints x 9 ellipsoid parameters elseif flag == 1 % fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1 @@ -99,7 +99,7 @@ y .* y, ... z .* z, ... 2 * x, ... - 2 * y, ... + 2 * y, ... 2 * z ]; % ndatapoints x 6 ellipsoid parameters elseif flag == 2 % fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1, @@ -127,7 +127,7 @@ % fit sphere in the form A(x^2 + y^2 + z^2) + 2Gx + 2Hy + 2Iz = 1 D = [ x .* x + y .* y + z .* z, ... 2 * x, ... - 2 * y, ... + 2 * y, ... 2 * z ]; % ndatapoints x 4 sphere parameters end @@ -170,5 +170,3 @@ radii = ( sqrt( gam ./ v( 1:3 ) ) )'; evecs = eye( 3 ); end - - diff --git a/Tools/cryptotools.py b/Tools/cryptotools.py index 6e4bd42d63e5..f452bea444f5 100755 --- a/Tools/cryptotools.py +++ b/Tools/cryptotools.py @@ -170,4 +170,3 @@ def generate_key(key_file): fs.write(f.read()) except: pass - diff --git a/Tools/ecl_ekf/analyse_logdata_ekf.py b/Tools/ecl_ekf/analyse_logdata_ekf.py index f0c33cfc8e41..98e7c23b9304 100644 --- a/Tools/ecl_ekf/analyse_logdata_ekf.py +++ b/Tools/ecl_ekf/analyse_logdata_ekf.py @@ -139,7 +139,3 @@ def find_checks_that_apply( innov_fail_checks.append('ofy') return sensor_checks, innov_fail_checks - - - - diff --git a/Tools/mavlink_shell.py b/Tools/mavlink_shell.py index 35c8d130ed5a..7dd3675bc1b1 100755 --- a/Tools/mavlink_shell.py +++ b/Tools/mavlink_shell.py @@ -243,4 +243,3 @@ def erase_last_n_chars(N): if __name__ == '__main__': main() - diff --git a/Tools/mavlink_ulog_streaming.py b/Tools/mavlink_ulog_streaming.py index c0ff6fe15dc3..2b21f1032741 100755 --- a/Tools/mavlink_ulog_streaming.py +++ b/Tools/mavlink_ulog_streaming.py @@ -282,4 +282,3 @@ def main(): if __name__ == '__main__': main() - diff --git a/Tools/serial/generate_config.py b/Tools/serial/generate_config.py index 099091dfe470..dc9c2762f9e5 100755 --- a/Tools/serial/generate_config.py +++ b/Tools/serial/generate_config.py @@ -330,4 +330,3 @@ def parse_yaml_serial_config(yaml_config): fid.write(template.render(serial_devices=serial_devices, ethernet_configuration=ethernet_configuration, commands=commands, serial_ports=serial_ports)) - diff --git a/Tools/serial/rc.serial.jinja b/Tools/serial/rc.serial.jinja index 753f2af75023..3ff8d62b811c 100644 --- a/Tools/serial/rc.serial.jinja +++ b/Tools/serial/rc.serial.jinja @@ -30,4 +30,3 @@ unset PRT unset PRT_F unset BAUD_PARAM unset MAV_ARGS - diff --git a/Tools/serial/serial_params.c.jinja b/Tools/serial/serial_params.c.jinja index 13cee1e896ea..cdc6e999a51a 100644 --- a/Tools/serial/serial_params.c.jinja +++ b/Tools/serial/serial_params.c.jinja @@ -70,4 +70,3 @@ PARAM_DEFINE_INT32({{ command.port_param_name }}, {{ command.default_port }}); {% endfor -%} {% endif %} - diff --git a/Tools/upload_log.py b/Tools/upload_log.py index d39a792cea87..a13f1b14b07c 100755 --- a/Tools/upload_log.py +++ b/Tools/upload_log.py @@ -125,4 +125,3 @@ def main(): if __name__ == '__main__': main() - diff --git a/Tools/validate_json.py b/Tools/validate_json.py index b80dad3198be..2c53ef815baa 100755 --- a/Tools/validate_json.py +++ b/Tools/validate_json.py @@ -50,4 +50,3 @@ except: print("JSON validation for {:} failed (schema: {:})".format(json_file, schema_file)) raise - diff --git a/Tools/validate_yaml.py b/Tools/validate_yaml.py index 3a2d022bfc88..e7b9a25fd838 100755 --- a/Tools/validate_yaml.py +++ b/Tools/validate_yaml.py @@ -65,4 +65,3 @@ def load_yaml_file(file_name): print(validator.errors) print("") raise Exception("Validation of {:} failed".format(yaml_file)) - diff --git a/boards/airmind/mindpx-v2/src/i2c.cpp b/boards/airmind/mindpx-v2/src/i2c.cpp index 5802883bfa13..2b708954d559 100644 --- a/boards/airmind/mindpx-v2/src/i2c.cpp +++ b/boards/airmind/mindpx-v2/src/i2c.cpp @@ -37,4 +37,3 @@ constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { initI2CBusInternal(1), initI2CBusExternal(2), }; - diff --git a/boards/airmind/mindpx-v2/src/usb.c b/boards/airmind/mindpx-v2/src/usb.c index 93a008cf0f48..a714f2f6f1c1 100644 --- a/boards/airmind/mindpx-v2/src/usb.c +++ b/boards/airmind/mindpx-v2/src/usb.c @@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) { uinfo("resume: %d\n", resume); } - diff --git a/boards/atl/mantis-edu/upload.sh b/boards/atl/mantis-edu/upload.sh index 98e2a0686ae5..d1df5cc5fd22 100755 --- a/boards/atl/mantis-edu/upload.sh +++ b/boards/atl/mantis-edu/upload.sh @@ -8,4 +8,3 @@ echo "uploading: $PX4_BINARY_FILE" PX4_BINARY_FILE_SIZE=$(stat -c%s "$PX4_BINARY_FILE") curl -v -F "image=@$PX4_BINARY_FILE" -H "Expect:" -H "File-Size:$PX4_BINARY_FILE_SIZE" http://192.168.42.1/cgi-bin/upload - diff --git a/boards/av/x-v1/nuttx-config/include/board.h b/boards/av/x-v1/nuttx-config/include/board.h index a1cdc1635def..b9a18e9a3b88 100644 --- a/boards/av/x-v1/nuttx-config/include/board.h +++ b/boards/av/x-v1/nuttx-config/include/board.h @@ -374,4 +374,3 @@ * SDMMC1_D2 PC10 * SDMMC1_D3 PC11 */ - diff --git a/boards/beaglebone/blue/src/board_pwm_out.cpp b/boards/beaglebone/blue/src/board_pwm_out.cpp index 5b728ddfbcdc..d65bea2a76f7 100644 --- a/boards/beaglebone/blue/src/board_pwm_out.cpp +++ b/boards/beaglebone/blue/src/board_pwm_out.cpp @@ -81,4 +81,3 @@ int BBBlueRcPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs) return ret; } - diff --git a/boards/bitcraze/crazyflie/src/usb.c b/boards/bitcraze/crazyflie/src/usb.c index 29bae3dcf9c5..fcd52fd07530 100644 --- a/boards/bitcraze/crazyflie/src/usb.c +++ b/boards/bitcraze/crazyflie/src/usb.c @@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) { uinfo("resume: %d\n", resume); } - diff --git a/boards/bitcraze/crazyflie21/src/usb.c b/boards/bitcraze/crazyflie21/src/usb.c index 29bae3dcf9c5..fcd52fd07530 100644 --- a/boards/bitcraze/crazyflie21/src/usb.c +++ b/boards/bitcraze/crazyflie21/src/usb.c @@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) { uinfo("resume: %d\n", resume); } - diff --git a/boards/cubepilot/cubeorange/init/rc.board_sensors b/boards/cubepilot/cubeorange/init/rc.board_sensors index e84edf7e2ff6..42ba25df2153 100644 --- a/boards/cubepilot/cubeorange/init/rc.board_sensors +++ b/boards/cubepilot/cubeorange/init/rc.board_sensors @@ -12,4 +12,3 @@ icm20948 -s -b 4 -R 10 -M start # SPI1 ms5611 -s -b 1 start icm20649 -s -b 1 start - diff --git a/boards/cubepilot/cubeorangeplus/init/rc.board_sensors b/boards/cubepilot/cubeorangeplus/init/rc.board_sensors index 2b08f2976417..7782e73d6aea 100644 --- a/boards/cubepilot/cubeorangeplus/init/rc.board_sensors +++ b/boards/cubepilot/cubeorangeplus/init/rc.board_sensors @@ -37,4 +37,3 @@ else fi ms5611 -s -b 1 start - diff --git a/boards/cubepilot/cubeyellow/init/rc.board_sensors b/boards/cubepilot/cubeyellow/init/rc.board_sensors index e84edf7e2ff6..42ba25df2153 100644 --- a/boards/cubepilot/cubeyellow/init/rc.board_sensors +++ b/boards/cubepilot/cubeyellow/init/rc.board_sensors @@ -12,4 +12,3 @@ icm20948 -s -b 4 -R 10 -M start # SPI1 ms5611 -s -b 1 start icm20649 -s -b 1 start - diff --git a/boards/emlid/navio2/init/rc.board_defaults b/boards/emlid/navio2/init/rc.board_defaults index 65348c4f846e..5d576dd74711 100644 --- a/boards/emlid/navio2/init/rc.board_defaults +++ b/boards/emlid/navio2/init/rc.board_defaults @@ -5,4 +5,3 @@ param set-default BAT1_V_DIV 10.177939394 param set-default BAT1_A_PER_V 15.391030303 - diff --git a/boards/emlid/navio2/src/board_pwm_out.cpp b/boards/emlid/navio2/src/board_pwm_out.cpp index bd6d7a6dc758..c93c6186655e 100644 --- a/boards/emlid/navio2/src/board_pwm_out.cpp +++ b/boards/emlid/navio2/src/board_pwm_out.cpp @@ -153,4 +153,3 @@ int NavioSysfsPWMOut::pwm_write_sysfs(char *path, int value) return 0; } - diff --git a/boards/flywoo/gn-f405/init/rc.board_extras b/boards/flywoo/gn-f405/init/rc.board_extras index 159a0008e9d3..911b4b4c61b0 100644 --- a/boards/flywoo/gn-f405/init/rc.board_extras +++ b/boards/flywoo/gn-f405/init/rc.board_extras @@ -7,5 +7,3 @@ if ! param compare OSD_ATXXXX_CFG 0 then atxxxx start -s fi - - diff --git a/boards/freefly/can-rtk-gps/nuttx-config/include/board.h b/boards/freefly/can-rtk-gps/nuttx-config/include/board.h index 0dbed5a97966..73f22444d1b3 100644 --- a/boards/freefly/can-rtk-gps/nuttx-config/include/board.h +++ b/boards/freefly/can-rtk-gps/nuttx-config/include/board.h @@ -264,4 +264,3 @@ #define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ #define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PC12 */ #define GPIO_SPI3_SCK GPIO_SPI3_SCK_1 /* PB3 */ - diff --git a/boards/freefly/can-rtk-gps/nuttx-config/include/board_dma_map.h b/boards/freefly/can-rtk-gps/nuttx-config/include/board_dma_map.h index ca0d10189fe8..7e9aa79709b4 100644 --- a/boards/freefly/can-rtk-gps/nuttx-config/include/board_dma_map.h +++ b/boards/freefly/can-rtk-gps/nuttx-config/include/board_dma_map.h @@ -99,4 +99,3 @@ // AVAILABLE // DMA1, Stream 5 // AVAILABLE // DMA1, Stream 6 // DMAMAP_USART1_TX USART1_TX // DMA1, Stream 7, Channel 5 - diff --git a/boards/holybro/kakutef7/init/rc.board_extras b/boards/holybro/kakutef7/init/rc.board_extras index 309ed17768f9..5822cd29458d 100644 --- a/boards/holybro/kakutef7/init/rc.board_extras +++ b/boards/holybro/kakutef7/init/rc.board_extras @@ -10,4 +10,3 @@ fi # DShot telemetry is always on UART7 dshot telemetry /dev/ttyS5 - diff --git a/boards/holybro/kakutef7/nuttx-config/include/board.h b/boards/holybro/kakutef7/nuttx-config/include/board.h index aae28ec8ebc7..e622f1590516 100644 --- a/boards/holybro/kakutef7/nuttx-config/include/board.h +++ b/boards/holybro/kakutef7/nuttx-config/include/board.h @@ -304,4 +304,3 @@ * OTG_FS_DP PA12 * VBUS PA8 */ - diff --git a/boards/holybro/kakutef7/nuttx-config/include/board_dma_map.h b/boards/holybro/kakutef7/nuttx-config/include/board_dma_map.h index c095f53105c9..5ef86fa68548 100644 --- a/boards/holybro/kakutef7/nuttx-config/include/board_dma_map.h +++ b/boards/holybro/kakutef7/nuttx-config/include/board_dma_map.h @@ -99,4 +99,3 @@ // DMAMAP_TIM1_UP // DMA2, Stream 5, Channel 6 (DSHOT) // AVAILABLE // DMA1, Stream 6 // AVAILABLE // DMA1, Stream 7 - diff --git a/boards/holybro/kakutef7/src/led.c b/boards/holybro/kakutef7/src/led.c index 5169b86d2288..05f02573f116 100644 --- a/boards/holybro/kakutef7/src/led.c +++ b/boards/holybro/kakutef7/src/led.c @@ -105,4 +105,3 @@ __EXPORT void led_toggle(int led) { phy_set_led(led, !phy_get_led(led)); } - diff --git a/boards/holybro/kakuteh7/init/rc.board_defaults b/boards/holybro/kakuteh7/init/rc.board_defaults index 4ca8626ebe61..f9f3ca7d5004 100644 --- a/boards/holybro/kakuteh7/init/rc.board_defaults +++ b/boards/holybro/kakuteh7/init/rc.board_defaults @@ -31,4 +31,3 @@ param set-default EKF2_IMU_CTRL 7 param set-default CBRK_BUZZER 782090 param set-default IMU_GYRO_RATEMAX 2000 - diff --git a/boards/holybro/kakuteh7/init/rc.board_extras b/boards/holybro/kakuteh7/init/rc.board_extras index 256633f33c9d..3423728dab9f 100644 --- a/boards/holybro/kakuteh7/init/rc.board_extras +++ b/boards/holybro/kakuteh7/init/rc.board_extras @@ -10,4 +10,3 @@ fi # DShot telemetry is always on UART7 dshot telemetry /dev/ttyS5 - diff --git a/boards/holybro/kakuteh7/nuttx-config/include/board.h b/boards/holybro/kakuteh7/nuttx-config/include/board.h index 4d3ed5eb4766..0c96869f01d1 100644 --- a/boards/holybro/kakuteh7/nuttx-config/include/board.h +++ b/boards/holybro/kakuteh7/nuttx-config/include/board.h @@ -416,4 +416,3 @@ # define PROBE_INIT(mask) # define PROBE(n,s) # define PROBE_MARK(n) - diff --git a/boards/holybro/kakuteh7/nuttx-config/include/board_dma_map.h b/boards/holybro/kakuteh7/nuttx-config/include/board_dma_map.h index 1954ce3e6806..d23e0d412072 100644 --- a/boards/holybro/kakuteh7/nuttx-config/include/board_dma_map.h +++ b/boards/holybro/kakuteh7/nuttx-config/include/board_dma_map.h @@ -37,4 +37,3 @@ #define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */ #define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2 */ - diff --git a/boards/holybro/kakuteh7mini/init/rc.board_extras b/boards/holybro/kakuteh7mini/init/rc.board_extras index 256633f33c9d..3423728dab9f 100644 --- a/boards/holybro/kakuteh7mini/init/rc.board_extras +++ b/boards/holybro/kakuteh7mini/init/rc.board_extras @@ -10,4 +10,3 @@ fi # DShot telemetry is always on UART7 dshot telemetry /dev/ttyS5 - diff --git a/boards/holybro/kakuteh7mini/nuttx-config/include/board.h b/boards/holybro/kakuteh7mini/nuttx-config/include/board.h index 4d3ed5eb4766..0c96869f01d1 100644 --- a/boards/holybro/kakuteh7mini/nuttx-config/include/board.h +++ b/boards/holybro/kakuteh7mini/nuttx-config/include/board.h @@ -416,4 +416,3 @@ # define PROBE_INIT(mask) # define PROBE(n,s) # define PROBE_MARK(n) - diff --git a/boards/holybro/kakuteh7mini/nuttx-config/include/board_dma_map.h b/boards/holybro/kakuteh7mini/nuttx-config/include/board_dma_map.h index 1954ce3e6806..d23e0d412072 100644 --- a/boards/holybro/kakuteh7mini/nuttx-config/include/board_dma_map.h +++ b/boards/holybro/kakuteh7mini/nuttx-config/include/board_dma_map.h @@ -37,4 +37,3 @@ #define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */ #define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2 */ - diff --git a/boards/holybro/kakuteh7v2/init/rc.board_extras b/boards/holybro/kakuteh7v2/init/rc.board_extras index 256633f33c9d..3423728dab9f 100644 --- a/boards/holybro/kakuteh7v2/init/rc.board_extras +++ b/boards/holybro/kakuteh7v2/init/rc.board_extras @@ -10,4 +10,3 @@ fi # DShot telemetry is always on UART7 dshot telemetry /dev/ttyS5 - diff --git a/boards/holybro/kakuteh7v2/nuttx-config/include/board.h b/boards/holybro/kakuteh7v2/nuttx-config/include/board.h index 4d3ed5eb4766..0c96869f01d1 100644 --- a/boards/holybro/kakuteh7v2/nuttx-config/include/board.h +++ b/boards/holybro/kakuteh7v2/nuttx-config/include/board.h @@ -416,4 +416,3 @@ # define PROBE_INIT(mask) # define PROBE(n,s) # define PROBE_MARK(n) - diff --git a/boards/holybro/kakuteh7v2/nuttx-config/include/board_dma_map.h b/boards/holybro/kakuteh7v2/nuttx-config/include/board_dma_map.h index 1954ce3e6806..d23e0d412072 100644 --- a/boards/holybro/kakuteh7v2/nuttx-config/include/board_dma_map.h +++ b/boards/holybro/kakuteh7v2/nuttx-config/include/board_dma_map.h @@ -37,4 +37,3 @@ #define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */ #define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2 */ - diff --git a/boards/matek/h743-mini/init/rc.board_extras b/boards/matek/h743-mini/init/rc.board_extras index a39b81bdc223..66e293646417 100644 --- a/boards/matek/h743-mini/init/rc.board_extras +++ b/boards/matek/h743-mini/init/rc.board_extras @@ -10,7 +10,5 @@ atxxxx start -s - # DShot telemetry is always on UART7 # dshot telemetry /dev/ttyS5 - diff --git a/boards/matek/h743-slim/init/rc.board_extras b/boards/matek/h743-slim/init/rc.board_extras index a39b81bdc223..bba363769ce9 100644 --- a/boards/matek/h743-slim/init/rc.board_extras +++ b/boards/matek/h743-slim/init/rc.board_extras @@ -13,4 +13,3 @@ atxxxx start -s # DShot telemetry is always on UART7 # dshot telemetry /dev/ttyS5 - diff --git a/boards/matek/h743/init/rc.board_extras b/boards/matek/h743/init/rc.board_extras index a39b81bdc223..bba363769ce9 100644 --- a/boards/matek/h743/init/rc.board_extras +++ b/boards/matek/h743/init/rc.board_extras @@ -13,4 +13,3 @@ atxxxx start -s # DShot telemetry is always on UART7 # dshot telemetry /dev/ttyS5 - diff --git a/boards/modalai/fc-v2/scripts/run_docker.sh b/boards/modalai/fc-v2/scripts/run_docker.sh index bcc39c6dcd59..4e42146ca6cb 100755 --- a/boards/modalai/fc-v2/scripts/run_docker.sh +++ b/boards/modalai/fc-v2/scripts/run_docker.sh @@ -2,4 +2,3 @@ # Run this from the px4 project top level directory docker run -it --rm --privileged -v `pwd`:/usr/local/workspace px4io/px4-dev-nuttx-focal:2022-08-12 - diff --git a/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.h b/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.h index 25de041d4b8a..1c71e5e81b0e 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.h +++ b/boards/modalai/voxl2-slpi/src/drivers/elrs_led/elrs_led.h @@ -108,6 +108,3 @@ ControllerInput getKey(const std::map &map, const return ControllerInput::DEFAULT; } - - - diff --git a/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.hpp b/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.hpp index 004fa020fb43..c9fe697e62cf 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.hpp +++ b/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.hpp @@ -123,4 +123,3 @@ class GhstRc : public ModuleBase, public ModuleParams, public px4::Sched // (ParamBool) _param_rc_ghst_tel_en // ) }; - diff --git a/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/module.yaml b/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/module.yaml index 21be68b97ebe..8f3998c2b133 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/module.yaml +++ b/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/module.yaml @@ -8,4 +8,3 @@ serial_config: #depends_on_port: RC description_extended: | Ghost RC (GHST) driver. - diff --git a/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/CMakeLists.txt b/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/CMakeLists.txt index 6d8087695f0a..05097e59f28c 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/CMakeLists.txt +++ b/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/CMakeLists.txt @@ -41,4 +41,3 @@ px4_add_module( DEPENDS rc ) - diff --git a/boards/mro/x21-777/nuttx-config/include/board.h b/boards/mro/x21-777/nuttx-config/include/board.h index 04cc6c1acd62..7b2863661fbd 100644 --- a/boards/mro/x21-777/nuttx-config/include/board.h +++ b/boards/mro/x21-777/nuttx-config/include/board.h @@ -282,4 +282,3 @@ #define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 #define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 #define GPIO_SPI2_SCK GPIO_SPI2_SCK_3 - diff --git a/boards/nxp/fmuk66-v3/init/rc.board_defaults b/boards/nxp/fmuk66-v3/init/rc.board_defaults index df700b4dc350..eed00b78ecbe 100644 --- a/boards/nxp/fmuk66-v3/init/rc.board_defaults +++ b/boards/nxp/fmuk66-v3/init/rc.board_defaults @@ -8,4 +8,3 @@ param set-default BAT1_A_PER_V 15.391030303 rgbled_pwm start safety_button start - diff --git a/boards/omnibus/f4sd/init/rc.board_extras b/boards/omnibus/f4sd/init/rc.board_extras index 25e6c269a85f..e3aa0d196175 100644 --- a/boards/omnibus/f4sd/init/rc.board_extras +++ b/boards/omnibus/f4sd/init/rc.board_extras @@ -7,5 +7,3 @@ if ! param compare OSD_ATXXXX_CFG 0 then atxxxx start -s fi - - diff --git a/boards/px4/fmu-v4/src/usb.c b/boards/px4/fmu-v4/src/usb.c index 5791d52cb0f8..b96898bc8635 100644 --- a/boards/px4/fmu-v4/src/usb.c +++ b/boards/px4/fmu-v4/src/usb.c @@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) { uinfo("resume: %d\n", resume); } - diff --git a/boards/px4/fmu-v4pro/src/timer_config.cpp b/boards/px4/fmu-v4pro/src/timer_config.cpp index 5d16012f6b27..7bf538a032e8 100644 --- a/boards/px4/fmu-v4pro/src/timer_config.cpp +++ b/boards/px4/fmu-v4pro/src/timer_config.cpp @@ -49,4 +49,3 @@ constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { constexpr io_timers_channel_mapping_t io_timers_channel_mapping = initIOTimerChannelMapping(io_timers, timer_io_channels); - diff --git a/boards/raspberrypi/pico/init/rc.board_defaults b/boards/raspberrypi/pico/init/rc.board_defaults index f1a26f4a51b1..6dc2fb4121d4 100644 --- a/boards/raspberrypi/pico/init/rc.board_defaults +++ b/boards/raspberrypi/pico/init/rc.board_defaults @@ -11,4 +11,3 @@ param set-default CBRK_SUPPLY_CHK 894281 # Disable safety switch by default param set-default CBRK_IO_SAFETY 22027 - diff --git a/boards/raspberrypi/pico/src/usb.c b/boards/raspberrypi/pico/src/usb.c index bc6306ae6bc2..9278997cc8ba 100644 --- a/boards/raspberrypi/pico/src/usb.c +++ b/boards/raspberrypi/pico/src/usb.c @@ -82,4 +82,3 @@ __EXPORT void rp2040_usbsuspend(FAR struct usbdev_s *dev, bool resume) { uinfo("resume: %d\n", resume); } - diff --git a/boards/siyi/n7/nuttx-config/include/board.h b/boards/siyi/n7/nuttx-config/include/board.h index 1df145ed26db..48edff42e4ef 100644 --- a/boards/siyi/n7/nuttx-config/include/board.h +++ b/boards/siyi/n7/nuttx-config/include/board.h @@ -376,6 +376,3 @@ #define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ #define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ - - - diff --git a/boards/siyi/n7/nuttx-config/include/board_dma_map.h b/boards/siyi/n7/nuttx-config/include/board_dma_map.h index 6577106c2363..fc7d7d27da79 100644 --- a/boards/siyi/n7/nuttx-config/include/board_dma_map.h +++ b/boards/siyi/n7/nuttx-config/include/board_dma_map.h @@ -42,4 +42,3 @@ #define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */ #define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */ - diff --git a/boards/sky-drones/smartap-airlink/init/rc.board_sensors b/boards/sky-drones/smartap-airlink/init/rc.board_sensors index 5ce477bf181d..95adb36b827d 100644 --- a/boards/sky-drones/smartap-airlink/init/rc.board_sensors +++ b/boards/sky-drones/smartap-airlink/init/rc.board_sensors @@ -31,4 +31,3 @@ lis3mdl -R 2 -X start # NCP5623 Led driver rgbled_ncp5623c -X -a 0x38 start - diff --git a/boards/spracing/h7extreme/init/rc.board_extras b/boards/spracing/h7extreme/init/rc.board_extras index 25e6c269a85f..e3aa0d196175 100644 --- a/boards/spracing/h7extreme/init/rc.board_extras +++ b/boards/spracing/h7extreme/init/rc.board_extras @@ -7,5 +7,3 @@ if ! param compare OSD_ATXXXX_CFG 0 then atxxxx start -s fi - - diff --git a/boards/spracing/h7extreme/nuttx-config/Kconfig b/boards/spracing/h7extreme/nuttx-config/Kconfig index ab39ed07497e..8b3754476f0e 100644 --- a/boards/spracing/h7extreme/nuttx-config/Kconfig +++ b/boards/spracing/h7extreme/nuttx-config/Kconfig @@ -15,10 +15,9 @@ config BOARD_USE_PROBES ---help--- Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. - - + + config STM32_RAMFUNCS bool "Use stm32_board_clockconfig as ram function." default y select ARCH_HAVE_RAMFUNCS - diff --git a/boards/spracing/h7extreme/src/timer_config.cpp b/boards/spracing/h7extreme/src/timer_config.cpp index d7c83bbd9aac..88bde6223e1f 100644 --- a/boards/spracing/h7extreme/src/timer_config.cpp +++ b/boards/spracing/h7extreme/src/timer_config.cpp @@ -60,4 +60,3 @@ constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { constexpr io_timers_channel_mapping_t io_timers_channel_mapping = initIOTimerChannelMapping(io_timers, timer_io_channels); - diff --git a/boards/uvify/core/src/usb.c b/boards/uvify/core/src/usb.c index 32f853b7472a..084a49ed7895 100644 --- a/boards/uvify/core/src/usb.c +++ b/boards/uvify/core/src/usb.c @@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) { uinfo("resume: %d\n", resume); } - diff --git a/cmake/doxygen.cmake b/cmake/doxygen.cmake index a410fe39db63..d9d64232a181 100644 --- a/cmake/doxygen.cmake +++ b/cmake/doxygen.cmake @@ -59,4 +59,3 @@ if (BUILD_DOXYGEN) message("Doxygen needs to be installed to generate documentation") endif() endif() - diff --git a/integrationtests/python_src/px4_it/util/manual_input.py b/integrationtests/python_src/px4_it/util/manual_input.py index d1381d99d648..66d484381c88 100755 --- a/integrationtests/python_src/px4_it/util/manual_input.py +++ b/integrationtests/python_src/px4_it/util/manual_input.py @@ -166,4 +166,3 @@ def offboard(self, ignore_thrust=False, ignore_attitude=False, ignore_bodyrate=T self.pub_mcsp.publish(pos) rate.sleep() count = count + 1 - diff --git a/integrationtests/python_src/px4_it/util/px4_test_helper.py b/integrationtests/python_src/px4_it/util/px4_test_helper.py index 4dc8866341e8..b069b70c40f5 100644 --- a/integrationtests/python_src/px4_it/util/px4_test_helper.py +++ b/integrationtests/python_src/px4_it/util/px4_test_helper.py @@ -108,4 +108,3 @@ def bag_write(self, topic, data): rospy.logwarn("Trying to write to bag but it's already closed") finally: self.condition.release() - diff --git a/msg/Buffer128.msg b/msg/Buffer128.msg index 342aa83dbe8d..4ff939a87d07 100644 --- a/msg/Buffer128.msg +++ b/msg/Buffer128.msg @@ -6,4 +6,3 @@ uint32 MAX_BUFLEN = 128 uint8[128] data # data # TOPICS voxl2_io_data - diff --git a/msg/FailsafeFlags.msg b/msg/FailsafeFlags.msg index 44945afaead0..2cd31bf83598 100644 --- a/msg/FailsafeFlags.msg +++ b/msg/FailsafeFlags.msg @@ -55,5 +55,3 @@ bool fd_critical_failure # Critical failure (attitude/altitude limi bool fd_esc_arming_failure # ESC failed to arm bool fd_imbalanced_prop # Imbalanced propeller detected bool fd_motor_failure # Motor failure - - diff --git a/msg/MessageFormatResponse.msg b/msg/MessageFormatResponse.msg index 41ee96274985..75c1d4fe9f1e 100644 --- a/msg/MessageFormatResponse.msg +++ b/msg/MessageFormatResponse.msg @@ -8,4 +8,3 @@ char[50] topic_name # E.g. /fmu/in/vehicle_command bool success uint32 message_hash # hash over all message fields - diff --git a/msg/ModeCompleted.msg b/msg/ModeCompleted.msg index bacff4a94b45..0a20b0294e53 100644 --- a/msg/ModeCompleted.msg +++ b/msg/ModeCompleted.msg @@ -12,4 +12,3 @@ uint8 RESULT_FAILURE_OTHER = 100 # Mode failed (generic error) uint8 result # One of RESULT_* uint8 nav_state # Source mode (values in VehicleStatus) - diff --git a/platforms/common/external_reset_lockout.cpp b/platforms/common/external_reset_lockout.cpp index 63f88d2349b5..fdc0adf67bd3 100644 --- a/platforms/common/external_reset_lockout.cpp +++ b/platforms/common/external_reset_lockout.cpp @@ -59,4 +59,3 @@ void px4_indicate_external_reset_lockout(LockoutComponent component, bool enable void px4_indicate_external_reset_lockout(LockoutComponent component, bool enabled) {} #endif /* BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE */ - diff --git a/platforms/common/include/px4_platform_common/external_reset_lockout.h b/platforms/common/include/px4_platform_common/external_reset_lockout.h index b4cdf8df6cbb..3be2901ab808 100644 --- a/platforms/common/include/px4_platform_common/external_reset_lockout.h +++ b/platforms/common/include/px4_platform_common/external_reset_lockout.h @@ -53,6 +53,3 @@ enum class LockoutComponent : uint8_t { * @param enabled true if compoment is in critical state */ void px4_indicate_external_reset_lockout(LockoutComponent component, bool enabled); - - - diff --git a/platforms/common/include/px4_platform_common/log.h b/platforms/common/include/px4_platform_common/log.h index 3450b7e90bf0..0b5d878ed7ae 100644 --- a/platforms/common/include/px4_platform_common/log.h +++ b/platforms/common/include/px4_platform_common/log.h @@ -446,4 +446,3 @@ __END_DECLS #define PX4_ANSI_COLOR_CYAN "\x1b[36m" #define PX4_ANSI_COLOR_GRAY "\x1B[37m" #define PX4_ANSI_COLOR_RESET "\x1b[0m" - diff --git a/platforms/common/module.cpp b/platforms/common/module.cpp index 8b474c794100..aeba6c4624fd 100644 --- a/platforms/common/module.cpp +++ b/platforms/common/module.cpp @@ -238,4 +238,3 @@ void PRINT_MODULE_USAGE_ARG(const char *values, const char *description, bool is #endif } - diff --git a/platforms/common/uORB/uORB.h b/platforms/common/uORB/uORB.h index a8964b4d27cd..ee11923b59d2 100644 --- a/platforms/common/uORB/uORB.h +++ b/platforms/common/uORB/uORB.h @@ -254,4 +254,3 @@ typedef uint8_t main_state_t; typedef uint8_t hil_state_t; typedef uint8_t navigation_state_t; typedef uint8_t switch_pos_t; - diff --git a/platforms/common/work_queue/dq_addlast.c b/platforms/common/work_queue/dq_addlast.c index 35e42d46d3a7..99272da224e8 100644 --- a/platforms/common/work_queue/dq_addlast.c +++ b/platforms/common/work_queue/dq_addlast.c @@ -70,4 +70,3 @@ void dq_addlast(dq_entry_t *node, dq_queue_t *queue) queue->tail = node; } } - diff --git a/platforms/common/work_queue/dq_rem.c b/platforms/common/work_queue/dq_rem.c index 4249daec5050..7e91045f901d 100644 --- a/platforms/common/work_queue/dq_rem.c +++ b/platforms/common/work_queue/dq_rem.c @@ -78,4 +78,3 @@ void dq_rem(dq_entry_t *node, dq_queue_t *queue) node->flink = NULL; node->blink = NULL; } - diff --git a/platforms/common/work_queue/dq_remfirst.c b/platforms/common/work_queue/dq_remfirst.c index 10394d10634b..bb5538b7cc58 100644 --- a/platforms/common/work_queue/dq_remfirst.c +++ b/platforms/common/work_queue/dq_remfirst.c @@ -78,4 +78,3 @@ dq_entry_t *dq_remfirst(dq_queue_t *queue) return ret; } - diff --git a/platforms/common/work_queue/queue.c b/platforms/common/work_queue/queue.c index b81315381e2a..dc3e3e496763 100644 --- a/platforms/common/work_queue/queue.c +++ b/platforms/common/work_queue/queue.c @@ -91,5 +91,3 @@ void sq_addfirst(sq_entry_t *node, sq_queue_t *queue) queue->head = node; } - - diff --git a/platforms/common/work_queue/sq_addlast.c b/platforms/common/work_queue/sq_addlast.c index 1a0ff88a447c..d8915204bef2 100644 --- a/platforms/common/work_queue/sq_addlast.c +++ b/platforms/common/work_queue/sq_addlast.c @@ -69,4 +69,3 @@ void sq_addlast(sq_entry_t *node, sq_queue_t *queue) queue->tail = node; } } - diff --git a/platforms/common/work_queue/sq_remfirst.c b/platforms/common/work_queue/sq_remfirst.c index 42b0b6599dba..76b16b4a43ea 100644 --- a/platforms/common/work_queue/sq_remfirst.c +++ b/platforms/common/work_queue/sq_remfirst.c @@ -73,4 +73,3 @@ sq_entry_t *sq_remfirst(sq_queue_t *queue) return ret; } - diff --git a/platforms/nuttx/Debug/jtrace_debug_ozone.jdebug b/platforms/nuttx/Debug/jtrace_debug_ozone.jdebug index 6e4b4efce568..dd540e34c213 100644 --- a/platforms/nuttx/Debug/jtrace_debug_ozone.jdebug +++ b/platforms/nuttx/Debug/jtrace_debug_ozone.jdebug @@ -3,21 +3,21 @@ * The Embedded Experts * * www.segger.com * ********************************************************************** - + File : jtrace_debug_ozone.jdebug Created : 26 Oct 2020 14:30 Ozone Version : V3.20e */ /********************************************************************* -* -* OnProjectLoad -* -* Function description -* Project load routine. Required. -* +* +* OnProjectLoad +* +* Function description +* Project load routine. Required. +* ********************************************************************** -*/ +*/ void OnProjectLoad (void) { // // Dialog-generated settings @@ -38,291 +38,290 @@ void OnProjectLoad (void) { } /********************************************************************* -* -* OnStartupComplete -* -* Function description -* Called when program execution has reached/passed -* the startup completion point. Optional. -* +* +* OnStartupComplete +* +* Function description +* Called when program execution has reached/passed +* the startup completion point. Optional. +* ********************************************************************** -*/ -//void OnStartupComplete (void) { -//} +*/ +//void OnStartupComplete (void) { +//} /********************************************************************* -* -* TargetReset -* -* Function description -* Replaces the default target device reset routine. Optional. -* -* Notes -* This example demonstrates the usage when -* debugging a RAM program on a Cortex-M target device -* +* +* TargetReset +* +* Function description +* Replaces the default target device reset routine. Optional. +* +* Notes +* This example demonstrates the usage when +* debugging a RAM program on a Cortex-M target device +* ********************************************************************** -*/ -//void TargetReset (void) { -// -// unsigned int SP; -// unsigned int PC; -// unsigned int VectorTableAddr; -// -// VectorTableAddr = Program.GetBaseAddr(); -// -// if (VectorTableAddr != 0xFFFFFFFF) { -// SP = Target.ReadU32(VectorTableAddr); -// Target.SetReg("SP", SP); -// } else { -// Util.Log("Project file error: failed to get program base"); -// } -// -// PC = Elf.GetEntryPointPC(); -// -// if (PC != 0xFFFFFFFF) { -// Target.SetReg("PC", PC); -// } else if (VectorTableAddr != 0xFFFFFFFF) { -// PC = Target.ReadU32(VectorTableAddr + 4); -// Target.SetReg("PC", PC); -//} +*/ +//void TargetReset (void) { +// +// unsigned int SP; +// unsigned int PC; +// unsigned int VectorTableAddr; +// +// VectorTableAddr = Program.GetBaseAddr(); +// +// if (VectorTableAddr != 0xFFFFFFFF) { +// SP = Target.ReadU32(VectorTableAddr); +// Target.SetReg("SP", SP); +// } else { +// Util.Log("Project file error: failed to get program base"); +// } +// +// PC = Elf.GetEntryPointPC(); +// +// if (PC != 0xFFFFFFFF) { +// Target.SetReg("PC", PC); +// } else if (VectorTableAddr != 0xFFFFFFFF) { +// PC = Target.ReadU32(VectorTableAddr + 4); +// Target.SetReg("PC", PC); +//} /********************************************************************* -* -* BeforeTargetReset -* -* Function description -* Event handler routine. Optional. -* +* +* BeforeTargetReset +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -//void BeforeTargetReset (void) { -//} +*/ +//void BeforeTargetReset (void) { +//} /********************************************************************* -* -* AfterTargetReset -* -* Function description -* Event handler routine. Optional. -* - Sets the PC register to program reset value. -* - Sets the SP register to program reset value on Cortex-M. -* +* +* AfterTargetReset +* +* Function description +* Event handler routine. Optional. +* - Sets the PC register to program reset value. +* - Sets the SP register to program reset value on Cortex-M. +* ********************************************************************** -*/ +*/ void AfterTargetReset (void) { - unsigned int SP; - unsigned int PC; - unsigned int VectorTableAddr; - - VectorTableAddr = Elf.GetBaseAddr(); - - if (VectorTableAddr == 0xFFFFFFFF) { - Util.Log("Project file error: failed to get program base"); - } else { - SP = Target.ReadU32(VectorTableAddr); - Target.SetReg("SP", SP); - - PC = Target.ReadU32(VectorTableAddr + 4); - Target.SetReg("PC", PC); + unsigned int SP; + unsigned int PC; + unsigned int VectorTableAddr; + + VectorTableAddr = Elf.GetBaseAddr(); + + if (VectorTableAddr == 0xFFFFFFFF) { + Util.Log("Project file error: failed to get program base"); + } else { + SP = Target.ReadU32(VectorTableAddr); + Target.SetReg("SP", SP); + + PC = Target.ReadU32(VectorTableAddr + 4); + Target.SetReg("PC", PC); } } /********************************************************************* -* -* DebugStart -* -* Function description -* Replaces the default debug session startup routine. Optional. -* +* +* DebugStart +* +* Function description +* Replaces the default debug session startup routine. Optional. +* ********************************************************************** -*/ -//void DebugStart (void) { -//} +*/ +//void DebugStart (void) { +//} /********************************************************************* -* -* TargetConnect -* -* Function description -* Replaces the default target IF connection routine. Optional. -* +* +* TargetConnect +* +* Function description +* Replaces the default target IF connection routine. Optional. +* ********************************************************************** -*/ -//void TargetConnect (void) { -//} +*/ +//void TargetConnect (void) { +//} /********************************************************************* -* -* BeforeTargetConnect -* -* Function description -* Event handler routine. Optional. -* +* +* BeforeTargetConnect +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -void BeforeTargetConnect (void) { +*/ +void BeforeTargetConnect (void) { Project.SetJLinkScript("FMUv6_Trace.pex"); -} +} /********************************************************************* -* -* AfterTargetConnect -* -* Function description -* Event handler routine. Optional. -* +* +* AfterTargetConnect +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -//void AfterTargetConnect (void) { -//} +*/ +//void AfterTargetConnect (void) { +//} /********************************************************************* -* -* TargetDownload -* -* Function description -* Replaces the default program download routine. Optional. -* +* +* TargetDownload +* +* Function description +* Replaces the default program download routine. Optional. +* ********************************************************************** -*/ -//void TargetDownload (void) { -//} +*/ +//void TargetDownload (void) { +//} /********************************************************************* -* -* BeforeTargetDownload -* -* Function description -* Event handler routine. Optional. -* +* +* BeforeTargetDownload +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -//void BeforeTargetDownload (void) { -//} +*/ +//void BeforeTargetDownload (void) { +//} /********************************************************************* -* -* AfterTargetDownload -* -* Function description -* Event handler routine. Optional. -* - Sets the PC register to program reset value. -* - Sets the SP register to program reset value on Cortex-M. -* +* +* AfterTargetDownload +* +* Function description +* Event handler routine. Optional. +* - Sets the PC register to program reset value. +* - Sets the SP register to program reset value on Cortex-M. +* ********************************************************************** -*/ +*/ void AfterTargetDownload (void) { - unsigned int SP; - unsigned int PC; - unsigned int VectorTableAddr; - - VectorTableAddr = Elf.GetBaseAddr(); - Util.Log("___"); - if (VectorTableAddr == 0xFFFFFFFF) { - Util.Log("Project file error: failed to get program base"); - } else { - SP = Target.ReadU32(VectorTableAddr); - Target.SetReg("SP", SP); - - PC = Target.ReadU32(VectorTableAddr + 4); - Target.SetReg("PC", PC); + unsigned int SP; + unsigned int PC; + unsigned int VectorTableAddr; + + VectorTableAddr = Elf.GetBaseAddr(); + Util.Log("___"); + if (VectorTableAddr == 0xFFFFFFFF) { + Util.Log("Project file error: failed to get program base"); + } else { + SP = Target.ReadU32(VectorTableAddr); + Target.SetReg("SP", SP); + + PC = Target.ReadU32(VectorTableAddr + 4); + Target.SetReg("PC", PC); } } /********************************************************************* -* -* BeforeTargetDisconnect -* -* Function description -* Event handler routine. Optional. -* +* +* BeforeTargetDisconnect +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -//void BeforeTargetDisconnect (void) { -//} +*/ +//void BeforeTargetDisconnect (void) { +//} /********************************************************************* -* -* AfterTargetDisconnect -* -* Function description -* Event handler routine. Optional. -* +* +* AfterTargetDisconnect +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -//void AfterTargetDisconnect (void) { -//} +*/ +//void AfterTargetDisconnect (void) { +//} /********************************************************************* -* -* AfterTargetHalt -* -* Function description -* Event handler routine. Optional. -* +* +* AfterTargetHalt +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -//void AfterTargetHalt (void) { -//} +*/ +//void AfterTargetHalt (void) { +//} /********************************************************************* -* -* BeforeTargetResume -* -* Function description -* Event handler routine. Optional. -* +* +* BeforeTargetResume +* +* Function description +* Event handler routine. Optional. +* ********************************************************************** -*/ -//void BeforeTargetResume (void) { -//} +*/ +//void BeforeTargetResume (void) { +//} /********************************************************************* -* -* OnSnapshotLoad -* -* Function description -* Called upon loading a snapshot. Optional. -* -* Additional information -* This function is used to restore the target state in cases -* where values cannot simply be written to the target. -* Typical use: GPIO clock needs to be enabled, before -* GPIO is configured. -* +* +* OnSnapshotLoad +* +* Function description +* Called upon loading a snapshot. Optional. +* +* Additional information +* This function is used to restore the target state in cases +* where values cannot simply be written to the target. +* Typical use: GPIO clock needs to be enabled, before +* GPIO is configured. +* ********************************************************************** -*/ -//void OnSnapshotLoad (void) { -//} +*/ +//void OnSnapshotLoad (void) { +//} /********************************************************************* -* -* OnSnapshotSave -* -* Function description -* Called upon saving a snapshot. Optional. -* -* Additional information -* This function is usually used to save values of the target -* state which can either not be trivially read, -* or need to be restored in a specific way or order. -* Typically use: Memory Mapped Registers, -* such as PLL and GPIO configuration. -* +* +* OnSnapshotSave +* +* Function description +* Called upon saving a snapshot. Optional. +* +* Additional information +* This function is usually used to save values of the target +* state which can either not be trivially read, +* or need to be restored in a specific way or order. +* Typically use: Memory Mapped Registers, +* such as PLL and GPIO configuration. +* ********************************************************************** -*/ -//void OnSnapshotSave (void) { -//} +*/ +//void OnSnapshotSave (void) { +//} /********************************************************************* -* -* OnError -* -* Function description -* Called when an error ocurred. Optional. -* +* +* OnError +* +* Function description +* Called when an error ocurred. Optional. +* ********************************************************************** -*/ -//void OnError (const char* sErrorMsg) { -//} - +*/ +//void OnError (const char* sErrorMsg) { +//} diff --git a/platforms/nuttx/src/px4/CMakeLists.txt b/platforms/nuttx/src/px4/CMakeLists.txt index 929788b587e2..a693422af66a 100644 --- a/platforms/nuttx/src/px4/CMakeLists.txt +++ b/platforms/nuttx/src/px4/CMakeLists.txt @@ -32,6 +32,4 @@ ############################################################################ add_subdirectory(common) - add_subdirectory(${PX4_CHIP_MANUFACTURER}) - diff --git a/platforms/nuttx/src/px4/common/gpio/mcp23009/CMakeLists.txt b/platforms/nuttx/src/px4/common/gpio/mcp23009/CMakeLists.txt index 8dc5414ad4aa..da6dac979f20 100644 --- a/platforms/nuttx/src/px4/common/gpio/mcp23009/CMakeLists.txt +++ b/platforms/nuttx/src/px4/common/gpio/mcp23009/CMakeLists.txt @@ -34,4 +34,3 @@ px4_add_library(platform_gpio_mcp23009 mcp23009.cpp ) target_link_libraries(platform_gpio_mcp23009 PRIVATE drivers__device) # device::I2C - diff --git a/platforms/nuttx/src/px4/common/include/px4_platform/adc.h b/platforms/nuttx/src/px4/common/include/px4_platform/adc.h index d7f6e85a5b94..228d609e8ee8 100644 --- a/platforms/nuttx/src/px4/common/include/px4_platform/adc.h +++ b/platforms/nuttx/src/px4/common/include/px4_platform/adc.h @@ -37,4 +37,3 @@ #else # define SYSTEM_ADC_COUNT 2 #endif - diff --git a/platforms/nuttx/src/px4/common/include/px4_platform/micro_hal.h b/platforms/nuttx/src/px4/common/include/px4_platform/micro_hal.h index 6daca09771df..670b702f922d 100644 --- a/platforms/nuttx/src/px4/common/include/px4_platform/micro_hal.h +++ b/platforms/nuttx/src/px4/common/include/px4_platform/micro_hal.h @@ -54,4 +54,3 @@ __BEGIN_DECLS #include __END_DECLS - diff --git a/platforms/nuttx/src/px4/common/usr_mcu_version.cpp b/platforms/nuttx/src/px4/common/usr_mcu_version.cpp index 1fc3f57b2dd7..64d86ee92a16 100644 --- a/platforms/nuttx/src/px4/common/usr_mcu_version.cpp +++ b/platforms/nuttx/src/px4/common/usr_mcu_version.cpp @@ -114,4 +114,3 @@ int board_get_px4_guid_formated(char *format_buffer, int size) return offset; } - diff --git a/platforms/nuttx/src/px4/nxp/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/CMakeLists.txt index ec489bf559c3..72584f3178ec 100644 --- a/platforms/nuttx/src/px4/nxp/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/CMakeLists.txt @@ -31,6 +31,4 @@ # ############################################################################ - add_subdirectory(${PX4_CHIP}) - diff --git a/platforms/nuttx/src/px4/nxp/k66/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/k66/CMakeLists.txt index 2b96e342f86a..5cacc8fcfc58 100644 --- a/platforms/nuttx/src/px4/nxp/k66/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/k66/CMakeLists.txt @@ -40,6 +40,3 @@ add_subdirectory(../kinetis/hrt hrt) add_subdirectory(../kinetis/io_pins io_pins) add_subdirectory(../kinetis/tone_alarm tone_alarm) add_subdirectory(../kinetis/version version) - - - diff --git a/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/adc.h b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/adc.h index 743deaed331c..521bcf04d6c7 100644 --- a/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/adc.h @@ -33,4 +33,3 @@ #pragma once #include "../../../kinetis/include/px4_arch/adc.h" - diff --git a/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/io_timer.h index 11661f853a71..11fbae6cbc4a 100644 --- a/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/io_timer.h @@ -32,6 +32,4 @@ ****************************************************************************/ #pragma once - #include "../../../kinetis/include/px4_arch/io_timer.h" - diff --git a/platforms/nuttx/src/px4/nxp/kinetis/hrt/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/kinetis/hrt/CMakeLists.txt index ebd97f8a42fa..3edd775b6a63 100644 --- a/platforms/nuttx/src/px4/nxp/kinetis/hrt/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/kinetis/hrt/CMakeLists.txt @@ -35,4 +35,3 @@ px4_add_library(arch_hrt hrt.c ) target_compile_options(arch_hrt PRIVATE -Wno-cast-align) # TODO: fix and enable - diff --git a/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/adc.h b/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/adc.h index 400305ebd21b..5ae5548411b5 100644 --- a/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/adc.h @@ -37,5 +37,3 @@ #define SYSTEM_ADC_BASE 0 // not used on kinetis #include - - diff --git a/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/adc.h b/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/adc.h index 234971efbdcd..d31323b9eb0e 100644 --- a/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/adc.h @@ -33,4 +33,3 @@ #pragma once #include "../../../rpi_common/include/px4_arch/adc.h" - diff --git a/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/i2c_hw_description.h b/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/i2c_hw_description.h index 9655c49558b7..908cc4e9b0a5 100644 --- a/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/i2c_hw_description.h +++ b/platforms/nuttx/src/px4/rpi/rp2040/include/px4_arch/i2c_hw_description.h @@ -33,4 +33,3 @@ #pragma once #include "../../../rpi_common/include/px4_arch/i2c_hw_description.h" - diff --git a/platforms/nuttx/src/px4/rpi/rpi_common/include/px4_arch/adc.h b/platforms/nuttx/src/px4/rpi/rpi_common/include/px4_arch/adc.h index 96aa40bc333b..ae3cfbedcf32 100644 --- a/platforms/nuttx/src/px4/rpi/rpi_common/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/rpi/rpi_common/include/px4_arch/adc.h @@ -37,4 +37,3 @@ #define SYSTEM_ADC_BASE RP2040_ADC_BASE #include - diff --git a/platforms/nuttx/src/px4/stm/CMakeLists.txt b/platforms/nuttx/src/px4/stm/CMakeLists.txt index ec489bf559c3..72584f3178ec 100644 --- a/platforms/nuttx/src/px4/stm/CMakeLists.txt +++ b/platforms/nuttx/src/px4/stm/CMakeLists.txt @@ -31,6 +31,4 @@ # ############################################################################ - add_subdirectory(${PX4_CHIP}) - diff --git a/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/adc.h b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/adc.h index 17ff58304537..1736386ce592 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/adc.h @@ -54,4 +54,3 @@ #endif #include - diff --git a/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/px4io_serial.h index 964627c636df..bf33426d3ceb 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/px4io_serial.h +++ b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/px4io_serial.h @@ -166,4 +166,3 @@ class ArchPX4IOSerial : public PX4IO_serial */ static uint8_t _io_buffer_storage[] px4_cache_aligned_data(); }; - diff --git a/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/dshot.h b/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/dshot.h index 7a7f1791bd53..417c1bccb226 100644 --- a/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/dshot.h +++ b/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/dshot.h @@ -34,4 +34,3 @@ #define px4_stm32_dmasetup stm32_dmasetup #include "../../../stm32_common/include/px4_arch/dshot.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f1/io_timer.h b/platforms/nuttx/src/px4/stm/stm32f1/io_timer.h index 2960835d2ec2..6b565c384730 100644 --- a/platforms/nuttx/src/px4/stm/stm32f1/io_timer.h +++ b/platforms/nuttx/src/px4/stm/stm32f1/io_timer.h @@ -32,6 +32,4 @@ ****************************************************************************/ #pragma once - #include "../../../stm32_common/include/px4_arch/io_timer.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f3/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32f3/CMakeLists.txt index 22c6701f946e..98f0e1b7db8f 100644 --- a/platforms/nuttx/src/px4/stm/stm32f3/CMakeLists.txt +++ b/platforms/nuttx/src/px4/stm/stm32f3/CMakeLists.txt @@ -36,5 +36,3 @@ add_subdirectory(board_critmon) add_subdirectory(../stm32_common/board_reset board_reset) add_subdirectory(../stm32_common/version version) add_subdirectory(../stm32_common/hrt hrt) - - diff --git a/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/adc.h b/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/adc.h index 9aa5b0c7aeba..6727319a5152 100644 --- a/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/adc.h @@ -33,4 +33,3 @@ #pragma once #include "../../../stm32_common/include/px4_arch/adc.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/io_timer.h index 2960835d2ec2..6b565c384730 100644 --- a/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/io_timer.h @@ -32,6 +32,4 @@ ****************************************************************************/ #pragma once - #include "../../../stm32_common/include/px4_arch/io_timer.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/micro_hal.h b/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/micro_hal.h index e43fabc2e39b..4ef37a9542f3 100644 --- a/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/micro_hal.h +++ b/platforms/nuttx/src/px4/stm/stm32f3/include/px4_arch/micro_hal.h @@ -52,4 +52,3 @@ __BEGIN_DECLS #define PX4_ADC_INTERNAL_TEMP_SENSOR_CHANNEL 16 __END_DECLS - diff --git a/platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt index 9b49f31f84cb..cc751f5d5f92 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt +++ b/platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt @@ -47,4 +47,3 @@ add_subdirectory(../stm32_common/version version) add_subdirectory(px4io_serial) add_subdirectory(watchdog) - diff --git a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/adc.h b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/adc.h index 9aa5b0c7aeba..6727319a5152 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/adc.h @@ -33,4 +33,3 @@ #pragma once #include "../../../stm32_common/include/px4_arch/adc.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/dshot.h b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/dshot.h index 449ca66b96b4..c71f84857141 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/dshot.h +++ b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/dshot.h @@ -35,4 +35,3 @@ #define px4_stm32_dmasetup stm32_dmasetup #include "../../../stm32_common/include/px4_arch/dshot.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/i2c_hw_description.h b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/i2c_hw_description.h index f125d3086e5e..dc883714e85f 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/i2c_hw_description.h +++ b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/i2c_hw_description.h @@ -33,4 +33,3 @@ #pragma once #include "../../../stm32_common/include/px4_arch/i2c_hw_description.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/micro_hal.h b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/micro_hal.h index d45a3add2b79..0844d7ed9475 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/micro_hal.h +++ b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/micro_hal.h @@ -51,4 +51,3 @@ __BEGIN_DECLS #define PX4_NUMBER_I2C_BUSES STM32_NI2C #define PX4_ADC_INTERNAL_TEMP_SENSOR_CHANNEL 18 __END_DECLS - diff --git a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/px4io_serial.h index 5898838ee4b4..714afe06eb1c 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/px4io_serial.h +++ b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/px4io_serial.h @@ -34,4 +34,3 @@ #pragma once #include "../../../stm32_common/include/px4_arch/px4io_serial.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp index 0ab41dd384a7..9f247653648f 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp +++ b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp @@ -473,4 +473,3 @@ ArchPX4IOSerial::_abort_dma() stm32_dmastop(_tx_dma); stm32_dmastop(_rx_dma); } - diff --git a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/adc.h b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/adc.h index 9aa5b0c7aeba..6727319a5152 100644 --- a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/adc.h @@ -33,4 +33,3 @@ #pragma once #include "../../../stm32_common/include/px4_arch/adc.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/dshot.h b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/dshot.h index 449ca66b96b4..c71f84857141 100644 --- a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/dshot.h +++ b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/dshot.h @@ -35,4 +35,3 @@ #define px4_stm32_dmasetup stm32_dmasetup #include "../../../stm32_common/include/px4_arch/dshot.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/io_timer.h index 2960835d2ec2..6b565c384730 100644 --- a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/io_timer.h @@ -32,6 +32,4 @@ ****************************************************************************/ #pragma once - #include "../../../stm32_common/include/px4_arch/io_timer.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/micro_hal.h b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/micro_hal.h index 82ce68f8a571..122853e81760 100644 --- a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/micro_hal.h +++ b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/micro_hal.h @@ -61,4 +61,3 @@ int stm32_flash_unlock(void); int stm32_flash_writeprotect(size_t page, bool enabled); __END_DECLS - diff --git a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/px4io_serial.h index 5898838ee4b4..714afe06eb1c 100644 --- a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/px4io_serial.h +++ b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/px4io_serial.h @@ -34,4 +34,3 @@ #pragma once #include "../../../stm32_common/include/px4_arch/px4io_serial.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp index 2899c8db3fba..68d04b8e5d9b 100644 --- a/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp +++ b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp @@ -506,4 +506,3 @@ ArchPX4IOSerial::_abort_dma() rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */ } - diff --git a/platforms/posix/include/hrt_work.h b/platforms/posix/include/hrt_work.h index 7799d3815c1a..317387ed31b2 100644 --- a/platforms/posix/include/hrt_work.h +++ b/platforms/posix/include/hrt_work.h @@ -60,4 +60,3 @@ static inline void hrt_work_unlock(void) } __END_DECLS - diff --git a/platforms/posix/include/queue.h b/platforms/posix/include/queue.h index d6315ca1723c..b0a73322cf91 100644 --- a/platforms/posix/include/queue.h +++ b/platforms/posix/include/queue.h @@ -131,4 +131,3 @@ EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue); #endif #endif /* __INCLUDE_QUEUE_H_ */ - diff --git a/platforms/posix/src/px4/CMakeLists.txt b/platforms/posix/src/px4/CMakeLists.txt index 929788b587e2..93a633982265 100644 --- a/platforms/posix/src/px4/CMakeLists.txt +++ b/platforms/posix/src/px4/CMakeLists.txt @@ -34,4 +34,3 @@ add_subdirectory(common) add_subdirectory(${PX4_CHIP_MANUFACTURER}) - diff --git a/platforms/posix/src/px4/common/lockstep_scheduler/include/lockstep_scheduler/lockstep_components.h b/platforms/posix/src/px4/common/lockstep_scheduler/include/lockstep_scheduler/lockstep_components.h index 3dc032e5a99c..15041c2b40ea 100644 --- a/platforms/posix/src/px4/common/lockstep_scheduler/include/lockstep_scheduler/lockstep_components.h +++ b/platforms/posix/src/px4/common/lockstep_scheduler/include/lockstep_scheduler/lockstep_components.h @@ -76,4 +76,3 @@ class LockstepComponents std::atomic_int _components_used_bitset{0}; std::atomic_int _components_progress_bitset{0}; }; - diff --git a/platforms/posix/src/px4/common/px4_daemon/CMakeLists.txt b/platforms/posix/src/px4/common/px4_daemon/CMakeLists.txt index e6cf9fcc7524..0e68741c181d 100644 --- a/platforms/posix/src/px4/common/px4_daemon/CMakeLists.txt +++ b/platforms/posix/src/px4/common/px4_daemon/CMakeLists.txt @@ -39,4 +39,3 @@ px4_add_library(px4_daemon server_io.cpp sock_protocol.cpp ) - diff --git a/platforms/posix/src/px4/common/px4_daemon/client.h b/platforms/posix/src/px4/common/px4_daemon/client.h index 41f4cb838192..b7883af3ebe6 100644 --- a/platforms/posix/src/px4/common/px4_daemon/client.h +++ b/platforms/posix/src/px4/common/px4_daemon/client.h @@ -85,4 +85,3 @@ class Client }; } // namespace px4_daemon - diff --git a/platforms/posix/src/px4/common/px4_daemon/history.h b/platforms/posix/src/px4/common/px4_daemon/history.h index b29ca8c53107..207c265f605a 100644 --- a/platforms/posix/src/px4/common/px4_daemon/history.h +++ b/platforms/posix/src/px4/common/px4_daemon/history.h @@ -101,4 +101,3 @@ class History }; } // namespace px4_daemon - diff --git a/platforms/posix/src/px4/common/px4_daemon/pxh.h b/platforms/posix/src/px4/common/px4_daemon/pxh.h index 45bd4b863343..39009bed11c5 100644 --- a/platforms/posix/src/px4/common/px4_daemon/pxh.h +++ b/platforms/posix/src/px4/common/px4_daemon/pxh.h @@ -103,4 +103,3 @@ class Pxh } // namespace px4_daemon - diff --git a/platforms/posix/src/px4/common/px4_daemon/server.h b/platforms/posix/src/px4/common/px4_daemon/server.h index 2932a977ff29..36f347df6764 100644 --- a/platforms/posix/src/px4/common/px4_daemon/server.h +++ b/platforms/posix/src/px4/common/px4_daemon/server.h @@ -124,4 +124,3 @@ class Server } // namespace px4_daemon - diff --git a/platforms/posix/src/px4/common/px4_daemon/sock_protocol.cpp b/platforms/posix/src/px4/common/px4_daemon/sock_protocol.cpp index 65b9e18000c4..48d154ca8534 100644 --- a/platforms/posix/src/px4/common/px4_daemon/sock_protocol.cpp +++ b/platforms/posix/src/px4/common/px4_daemon/sock_protocol.cpp @@ -48,4 +48,3 @@ std::string get_socket_path(int instance_id) } } // namespace px4_daemon - diff --git a/platforms/posix/src/px4/common/px4_daemon/sock_protocol.h b/platforms/posix/src/px4/common/px4_daemon/sock_protocol.h index f158a29b66d0..725dfe281e1e 100644 --- a/platforms/posix/src/px4/common/px4_daemon/sock_protocol.h +++ b/platforms/posix/src/px4/common/px4_daemon/sock_protocol.h @@ -45,4 +45,3 @@ namespace px4_daemon std::string get_socket_path(int instance_id); } // namespace px4_daemon - diff --git a/platforms/posix/src/px4/common/px4_posix_impl.cpp b/platforms/posix/src/px4/common/px4_posix_impl.cpp index 385c1a244551..31c1bb125cb4 100644 --- a/platforms/posix/src/px4/common/px4_posix_impl.cpp +++ b/platforms/posix/src/px4/common/px4_posix_impl.cpp @@ -97,4 +97,3 @@ void init(int argc, char *argv[], const char *app_name) } } - diff --git a/platforms/posix/src/px4/generic/CMakeLists.txt b/platforms/posix/src/px4/generic/CMakeLists.txt index ec489bf559c3..72584f3178ec 100644 --- a/platforms/posix/src/px4/generic/CMakeLists.txt +++ b/platforms/posix/src/px4/generic/CMakeLists.txt @@ -31,6 +31,4 @@ # ############################################################################ - add_subdirectory(${PX4_CHIP}) - diff --git a/platforms/posix/src/px4/generic/generic/CMakeLists.txt b/platforms/posix/src/px4/generic/generic/CMakeLists.txt index 4db79a429f8e..f99e817798ef 100644 --- a/platforms/posix/src/px4/generic/generic/CMakeLists.txt +++ b/platforms/posix/src/px4/generic/generic/CMakeLists.txt @@ -31,6 +31,4 @@ # ############################################################################ - add_subdirectory(tone_alarm) - diff --git a/platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h b/platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h index d09b73c687dd..2d85741cac90 100644 --- a/platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h +++ b/platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h @@ -33,4 +33,3 @@ #pragma once #include - diff --git a/platforms/posix/src/px4/generic/generic/tone_alarm/ToneAlarmInterface.cpp b/platforms/posix/src/px4/generic/generic/tone_alarm/ToneAlarmInterface.cpp index 61f9fc69ca24..639c16560381 100644 --- a/platforms/posix/src/px4/generic/generic/tone_alarm/ToneAlarmInterface.cpp +++ b/platforms/posix/src/px4/generic/generic/tone_alarm/ToneAlarmInterface.cpp @@ -58,4 +58,3 @@ void stop_note() } } /* namespace ToneAlarmInterface */ - diff --git a/platforms/qurt/include/px4_arch/micro_hal.h b/platforms/qurt/include/px4_arch/micro_hal.h index c23a40dbcfd6..d88e2ee29ebd 100644 --- a/platforms/qurt/include/px4_arch/micro_hal.h +++ b/platforms/qurt/include/px4_arch/micro_hal.h @@ -32,4 +32,3 @@ ****************************************************************************/ // Placeholder - diff --git a/platforms/qurt/include/queue.h b/platforms/qurt/include/queue.h index d6315ca1723c..b0a73322cf91 100644 --- a/platforms/qurt/include/queue.h +++ b/platforms/qurt/include/queue.h @@ -131,4 +131,3 @@ EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue); #endif #endif /* __INCLUDE_QUEUE_H_ */ - diff --git a/platforms/qurt/src/px4/common/include/px4_platform/cpuload.h b/platforms/qurt/src/px4/common/include/px4_platform/cpuload.h index b4c397098a40..c54221e6817d 100644 --- a/platforms/qurt/src/px4/common/include/px4_platform/cpuload.h +++ b/platforms/qurt/src/px4/common/include/px4_platform/cpuload.h @@ -34,4 +34,3 @@ #pragma once extern "C" float px4muorb_get_cpu_load(void); - diff --git a/platforms/ros2/include/hrt_work.h b/platforms/ros2/include/hrt_work.h index 2394ec09570d..7d4e17acfeb7 100644 --- a/platforms/ros2/include/hrt_work.h +++ b/platforms/ros2/include/hrt_work.h @@ -61,4 +61,3 @@ static inline void hrt_work_unlock() } __END_DECLS - diff --git a/platforms/ros2/include/queue.h b/platforms/ros2/include/queue.h index d6315ca1723c..b0a73322cf91 100644 --- a/platforms/ros2/include/queue.h +++ b/platforms/ros2/include/queue.h @@ -131,4 +131,3 @@ EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue); #endif #endif /* __INCLUDE_QUEUE_H_ */ - diff --git a/platforms/ros2/src/px4/CMakeLists.txt b/platforms/ros2/src/px4/CMakeLists.txt index bf200988a5ed..a8bb11576e96 100644 --- a/platforms/ros2/src/px4/CMakeLists.txt +++ b/platforms/ros2/src/px4/CMakeLists.txt @@ -34,4 +34,3 @@ add_subdirectory(common) add_subdirectory(${PX4_CHIP_MANUFACTURER}) - diff --git a/platforms/ros2/src/px4/generic/generic/include/px4_arch/micro_hal.h b/platforms/ros2/src/px4/generic/generic/include/px4_arch/micro_hal.h index d09b73c687dd..2d85741cac90 100644 --- a/platforms/ros2/src/px4/generic/generic/include/px4_arch/micro_hal.h +++ b/platforms/ros2/src/px4/generic/generic/include/px4_arch/micro_hal.h @@ -33,4 +33,3 @@ #pragma once #include - diff --git a/posix-configs/rpi/px4_hil.config b/posix-configs/rpi/px4_hil.config index 6554f52d4525..bdd987e80193 100644 --- a/posix-configs/rpi/px4_hil.config +++ b/posix-configs/rpi/px4_hil.config @@ -42,4 +42,3 @@ control_allocator start logger start -t -b 200 mavlink boot_complete - diff --git a/src/drivers/actuators/voxl_esc/voxl_esc_params.c b/src/drivers/actuators/voxl_esc/voxl_esc_params.c index f2719cea042b..2752d9d7448a 100644 --- a/src/drivers/actuators/voxl_esc/voxl_esc_params.c +++ b/src/drivers/actuators/voxl_esc/voxl_esc_params.c @@ -262,4 +262,3 @@ PARAM_DEFINE_INT32(VOXL_ESC_T_WARN, 0); * @max 200 */ PARAM_DEFINE_INT32(VOXL_ESC_T_OVER, 0); - diff --git a/src/drivers/adc/ads1115/ads1115_params.c b/src/drivers/adc/ads1115/ads1115_params.c index 560637db00a7..b1af67f30760 100644 --- a/src/drivers/adc/ads1115/ads1115_params.c +++ b/src/drivers/adc/ads1115/ads1115_params.c @@ -41,4 +41,3 @@ * @group Sensors */ PARAM_DEFINE_INT32(ADC_ADS1115_EN, 0); - diff --git a/src/drivers/barometer/bmp581/bmp581_i2c.cpp b/src/drivers/barometer/bmp581/bmp581_i2c.cpp index 3e4a0add5fa1..92a4d7e79d77 100644 --- a/src/drivers/barometer/bmp581/bmp581_i2c.cpp +++ b/src/drivers/barometer/bmp581/bmp581_i2c.cpp @@ -92,4 +92,3 @@ int BMP581_I2C::set_reg(uint8_t value, uint8_t addr) uint8_t cmd[2] = { (uint8_t)(addr), value}; return transfer(cmd, sizeof(cmd), nullptr, 0); } - diff --git a/src/drivers/camera_trigger/camera_trigger_params.c b/src/drivers/camera_trigger/camera_trigger_params.c index 181c212e6a2d..3841e20e5642 100644 --- a/src/drivers/camera_trigger/camera_trigger_params.c +++ b/src/drivers/camera_trigger/camera_trigger_params.c @@ -163,4 +163,3 @@ PARAM_DEFINE_INT32(TRIG_PWM_SHOOT, 1900); * @reboot_required true */ PARAM_DEFINE_INT32(TRIG_PWM_NEUTRAL, 1500); - diff --git a/src/drivers/differential_pressure/asp5033/ASP5033.hpp b/src/drivers/differential_pressure/asp5033/ASP5033.hpp index 37a9fdeb8f7e..d8c385ef3a16 100644 --- a/src/drivers/differential_pressure/asp5033/ASP5033.hpp +++ b/src/drivers/differential_pressure/asp5033/ASP5033.hpp @@ -134,4 +134,3 @@ class ASP5033 : public device::I2C, public I2CSPIDriver perf_counter_t _comms_errors{perf_alloc(PC_COUNT, MODULE_NAME": communication errors")}; perf_counter_t _fault_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": fault detected")}; }; - diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt b/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt index 657ffa105efb..a19f16d5b904 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt +++ b/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( DEPENDS drivers_rangefinder ) - diff --git a/src/drivers/distance_sensor/lightware_laser_serial/module.yaml b/src/drivers/distance_sensor/lightware_laser_serial/module.yaml index 269fe85ffd8c..6ad9eb656786 100644 --- a/src/drivers/distance_sensor/lightware_laser_serial/module.yaml +++ b/src/drivers/distance_sensor/lightware_laser_serial/module.yaml @@ -4,4 +4,3 @@ serial_config: port_config_param: name: SENS_SF0X_CFG group: Sensors - diff --git a/src/drivers/distance_sensor/tfmini/module.yaml b/src/drivers/distance_sensor/tfmini/module.yaml index 770cbe979c37..59cb6b234311 100644 --- a/src/drivers/distance_sensor/tfmini/module.yaml +++ b/src/drivers/distance_sensor/tfmini/module.yaml @@ -4,4 +4,3 @@ serial_config: port_config_param: name: SENS_TFMINI_CFG group: Sensors - diff --git a/src/drivers/dshot/DShotTelemetry.cpp b/src/drivers/dshot/DShotTelemetry.cpp index f0444bff1950..0132a9b04941 100644 --- a/src/drivers/dshot/DShotTelemetry.cpp +++ b/src/drivers/dshot/DShotTelemetry.cpp @@ -476,4 +476,3 @@ int DShotTelemetry::setBaudrate(unsigned baud) return 0; } - diff --git a/src/drivers/gnss/septentrio/README.md b/src/drivers/gnss/septentrio/README.md index 664df63a145d..7f5b83938c57 100644 --- a/src/drivers/gnss/septentrio/README.md +++ b/src/drivers/gnss/septentrio/README.md @@ -3,4 +3,4 @@ ## SBF Library The `sbf/` directory contains all the logic required to work with SBF, including message -definitions, block IDs and a simple parser for the messages used by PX4. \ No newline at end of file +definitions, block IDs and a simple parser for the messages used by PX4. diff --git a/src/drivers/gps/CMakeLists.txt b/src/drivers/gps/CMakeLists.txt index 74ee827283c3..4719e0e34e14 100644 --- a/src/drivers/gps/CMakeLists.txt +++ b/src/drivers/gps/CMakeLists.txt @@ -55,4 +55,4 @@ px4_add_module( module.yaml DEPENDS git_gps_devices - ) \ No newline at end of file + ) diff --git a/src/drivers/gps/module.yaml b/src/drivers/gps/module.yaml index 484e434d5881..1424864277fc 100644 --- a/src/drivers/gps/module.yaml +++ b/src/drivers/gps/module.yaml @@ -13,4 +13,3 @@ serial_config: group: GPS default: GPS1 label: Main GPS - diff --git a/src/drivers/gps/params.c b/src/drivers/gps/params.c index 5e5adbcfa9cd..512a5131e1c5 100644 --- a/src/drivers/gps/params.c +++ b/src/drivers/gps/params.c @@ -275,4 +275,4 @@ PARAM_DEFINE_INT32(GPS_1_GNSS, 0); * @reboot_required true * @group GPS */ -PARAM_DEFINE_INT32(GPS_2_GNSS, 0); \ No newline at end of file +PARAM_DEFINE_INT32(GPS_2_GNSS, 0); diff --git a/src/drivers/imu/nxp/fxos8701cq/fxos8701cq_spi.cpp b/src/drivers/imu/nxp/fxos8701cq/fxos8701cq_spi.cpp index 28c12b3f652a..795afdea006e 100644 --- a/src/drivers/imu/nxp/fxos8701cq/fxos8701cq_spi.cpp +++ b/src/drivers/imu/nxp/fxos8701cq/fxos8701cq_spi.cpp @@ -213,4 +213,3 @@ int FXOS8701CQ_SPI::write(unsigned reg, void *data, unsigned count) return transfer(cmd, nullptr, sizeof(cmd)); } - diff --git a/src/drivers/ins/vectornav/libvnc/include/vn/math/matrix.h b/src/drivers/ins/vectornav/libvnc/include/vn/math/matrix.h index 6bbf62b97c80..959d42314d88 100644 --- a/src/drivers/ins/vectornav/libvnc/include/vn/math/matrix.h +++ b/src/drivers/ins/vectornav/libvnc/include/vn/math/matrix.h @@ -84,4 +84,3 @@ mat3f vnm_negative_mat3f(mat3f m); #endif #endif - diff --git a/src/drivers/magnetometer/hmc5883/CMakeLists.txt b/src/drivers/magnetometer/hmc5883/CMakeLists.txt index 77b8784629dc..d8a4998eb376 100644 --- a/src/drivers/magnetometer/hmc5883/CMakeLists.txt +++ b/src/drivers/magnetometer/hmc5883/CMakeLists.txt @@ -44,4 +44,3 @@ px4_add_module( drivers_magnetometer px4_work_queue ) - diff --git a/src/drivers/osd/atxxxx/symbols.h b/src/drivers/osd/atxxxx/symbols.h index 52d5289e999d..2a20e2d9449c 100644 --- a/src/drivers/osd/atxxxx/symbols.h +++ b/src/drivers/osd/atxxxx/symbols.h @@ -116,4 +116,3 @@ #define OSD_SYMBOL_ON_M 0x9B #define OSD_SYMBOL_FLY_M 0x9C #define OSD_SYMBOL_FLIGHT_TIME 0x70 - diff --git a/src/drivers/osd/msp_osd/MessageDisplay/MessageDisplayTest.cpp b/src/drivers/osd/msp_osd/MessageDisplay/MessageDisplayTest.cpp index 08bd1f6f4d5b..1db76d01b34e 100644 --- a/src/drivers/osd/msp_osd/MessageDisplay/MessageDisplayTest.cpp +++ b/src/drivers/osd/msp_osd/MessageDisplay/MessageDisplayTest.cpp @@ -161,4 +161,3 @@ TEST_F(MessageDisplayTest, testMessageDisplayWarning) strncpy(correct, ground_truth, FULL_MSG_LENGTH); EXPECT_STREQ(message, correct); } - diff --git a/src/drivers/osd/msp_osd/MspV1.hpp b/src/drivers/osd/msp_osd/MspV1.hpp index a24491c24101..6c6ad524efd5 100644 --- a/src/drivers/osd/msp_osd/MspV1.hpp +++ b/src/drivers/osd/msp_osd/MspV1.hpp @@ -43,4 +43,3 @@ class MspV1 private: int _fd{-1}; }; - diff --git a/src/drivers/osd/msp_osd/msp_defines.h b/src/drivers/osd/msp_osd/msp_defines.h index eab7bebe521c..fb2e83a7cc28 100644 --- a/src/drivers/osd/msp_osd/msp_defines.h +++ b/src/drivers/osd/msp_osd/msp_defines.h @@ -848,4 +848,3 @@ enum betaflightDJIModesMask_e { // 0b00100000 resc // 0b01000000 acro // 0b10000000 acro - diff --git a/src/drivers/osd/msp_osd/msp_osd.hpp b/src/drivers/osd/msp_osd/msp_osd.hpp index 87918c786409..b35e7ff13554 100644 --- a/src/drivers/osd/msp_osd/msp_osd.hpp +++ b/src/drivers/osd/msp_osd/msp_osd.hpp @@ -172,4 +172,3 @@ class MspOsd : public ModuleBase, public ModuleParams, public px4::Sched char _device[64] {}; PerformanceData _performance_data{}; }; - diff --git a/src/drivers/pwm_out/module.yaml b/src/drivers/pwm_out/module.yaml index a55af5fae278..c63b4195d29a 100644 --- a/src/drivers/pwm_out/module.yaml +++ b/src/drivers/pwm_out/module.yaml @@ -30,4 +30,3 @@ actuator_output: 200: PWM 200 Hz 400: PWM 400 Hz reboot_required: true - diff --git a/src/drivers/rc_input/ghst_telemetry.cpp b/src/drivers/rc_input/ghst_telemetry.cpp index 47c1c21fa583..9a910063931a 100644 --- a/src/drivers/rc_input/ghst_telemetry.cpp +++ b/src/drivers/rc_input/ghst_telemetry.cpp @@ -136,4 +136,3 @@ bool GHSTTelemetry::send_gps2_status() return ghst_send_telemetry_gps2_status(_uart_fd, ground_speed, ground_course, num_sats, home_dist, home_dir, flags); } - diff --git a/src/drivers/rc_input/module.yaml b/src/drivers/rc_input/module.yaml index d0f9040a6ff8..bf15df092074 100644 --- a/src/drivers/rc_input/module.yaml +++ b/src/drivers/rc_input/module.yaml @@ -32,4 +32,3 @@ serial_config: description_extended: | Setting this to 'Disabled' will use a board-specific default port for RC input. - diff --git a/src/drivers/rpi_rc_in/CMakeLists.txt b/src/drivers/rpi_rc_in/CMakeLists.txt index 69ff3eb7dcba..06a106b13866 100644 --- a/src/drivers/rpi_rc_in/CMakeLists.txt +++ b/src/drivers/rpi_rc_in/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( rpi_rc_in.cpp DEPENDS ) - diff --git a/src/drivers/rpi_rc_in/rpi_rc_in.cpp b/src/drivers/rpi_rc_in/rpi_rc_in.cpp index 6e52a274c805..619e5c00f17f 100644 --- a/src/drivers/rpi_rc_in/rpi_rc_in.cpp +++ b/src/drivers/rpi_rc_in/rpi_rc_in.cpp @@ -211,4 +211,3 @@ int rpi_rc_in_main(int argc, char **argv) return 1; } - diff --git a/src/drivers/telemetry/bst/CMakeLists.txt b/src/drivers/telemetry/bst/CMakeLists.txt index c9c9e7ff798e..1bbeec9b8dd3 100644 --- a/src/drivers/telemetry/bst/CMakeLists.txt +++ b/src/drivers/telemetry/bst/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( bst.cpp DEPENDS ) - diff --git a/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt b/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt index 719227703b75..49c86518a3da 100644 --- a/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt +++ b/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt @@ -41,4 +41,3 @@ px4_add_module( MODULE_CONFIG module.yaml ) - diff --git a/src/drivers/telemetry/frsky_telemetry/module.yaml b/src/drivers/telemetry/frsky_telemetry/module.yaml index 796342de9c66..62f32aabec89 100644 --- a/src/drivers/telemetry/frsky_telemetry/module.yaml +++ b/src/drivers/telemetry/frsky_telemetry/module.yaml @@ -4,4 +4,3 @@ serial_config: port_config_param: name: TEL_FRSKY_CONFIG group: Telemetry - diff --git a/src/drivers/telemetry/hott/hott_sensors/CMakeLists.txt b/src/drivers/telemetry/hott/hott_sensors/CMakeLists.txt index e2f9ee6e7919..41e762a9824f 100644 --- a/src/drivers/telemetry/hott/hott_sensors/CMakeLists.txt +++ b/src/drivers/telemetry/hott/hott_sensors/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( hott_sensors.cpp DEPENDS ) - diff --git a/src/drivers/telemetry/hott/hott_telemetry/module.yaml b/src/drivers/telemetry/hott/hott_telemetry/module.yaml index ff50a8e3d4ee..1467a377ddb0 100644 --- a/src/drivers/telemetry/hott/hott_telemetry/module.yaml +++ b/src/drivers/telemetry/hott/hott_telemetry/module.yaml @@ -4,4 +4,3 @@ serial_config: port_config_param: name: TEL_HOTT_CONFIG group: Telemetry - diff --git a/src/drivers/telemetry/iridiumsbd/module.yaml b/src/drivers/telemetry/iridiumsbd/module.yaml index 5fa8d138c4c4..7ced65126767 100644 --- a/src/drivers/telemetry/iridiumsbd/module.yaml +++ b/src/drivers/telemetry/iridiumsbd/module.yaml @@ -12,4 +12,3 @@ serial_config: port_config_param: name: ISBD_CONFIG group: Iridium SBD - diff --git a/src/drivers/test_ppm/CMakeLists.txt b/src/drivers/test_ppm/CMakeLists.txt index dbe3b7b64828..2c9c91c5c455 100644 --- a/src/drivers/test_ppm/CMakeLists.txt +++ b/src/drivers/test_ppm/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( test_ppm.cpp DEPENDS ) - diff --git a/src/drivers/voxl2_io/module.yaml b/src/drivers/voxl2_io/module.yaml index 02aa2122e3ea..021305e955fa 100644 --- a/src/drivers/voxl2_io/module.yaml +++ b/src/drivers/voxl2_io/module.yaml @@ -10,4 +10,3 @@ actuator_output: group_label: 'PWMs' channel_label: 'PWM Channel' num_channels: 4 - diff --git a/src/drivers/voxl2_io/voxl2_io_params.c b/src/drivers/voxl2_io/voxl2_io_params.c index c718a4f62caf..704cca989e09 100644 --- a/src/drivers/voxl2_io/voxl2_io_params.c +++ b/src/drivers/voxl2_io/voxl2_io_params.c @@ -63,4 +63,3 @@ PARAM_DEFINE_INT32(VOXL2_IO_MIN, 1000); * @unit us */ PARAM_DEFINE_INT32(VOXL2_IO_MAX, 2000); - diff --git a/src/lib/heatshrink/CMakeLists.txt b/src/lib/heatshrink/CMakeLists.txt index d1ed75f06188..bd07dc825409 100644 --- a/src/lib/heatshrink/CMakeLists.txt +++ b/src/lib/heatshrink/CMakeLists.txt @@ -40,4 +40,3 @@ px4_add_library(heatshrink target_compile_options(heatshrink PRIVATE ${MAX_CUSTOM_OPT_LEVEL} -DHEATSHRINK_DYNAMIC_ALLOC=0) - diff --git a/src/lib/heatshrink/heatshrink_encode.py b/src/lib/heatshrink/heatshrink_encode.py index dc2cec88940e..01beb02c7a58 100644 --- a/src/lib/heatshrink/heatshrink_encode.py +++ b/src/lib/heatshrink/heatshrink_encode.py @@ -419,4 +419,3 @@ def encode(data, window_size, lookahead_size): if sunk == in_size: heatshrink_encoder_finish(hse) return ret - diff --git a/src/lib/matrix/matrix/Dual.hpp b/src/lib/matrix/matrix/Dual.hpp index e7eafa033129..43f1d2abd3e0 100644 --- a/src/lib/matrix/matrix/Dual.hpp +++ b/src/lib/matrix/matrix/Dual.hpp @@ -375,4 +375,3 @@ OStream &operator<<(OStream &os, const matrix::Dual &dual) } } - diff --git a/src/lib/metadata/CMakeLists.txt b/src/lib/metadata/CMakeLists.txt index a333722507cd..28f50c214af3 100644 --- a/src/lib/metadata/CMakeLists.txt +++ b/src/lib/metadata/CMakeLists.txt @@ -58,4 +58,3 @@ add_custom_command(OUTPUT ${generated_actuators_metadata_file} COMMENT "Generating actuators.json" ) add_custom_target(actuators_json DEPENDS ${generated_actuators_metadata_file}) - diff --git a/src/lib/parameters/autosave.cpp b/src/lib/parameters/autosave.cpp index a539ee484ba6..f06ff8df45aa 100644 --- a/src/lib/parameters/autosave.cpp +++ b/src/lib/parameters/autosave.cpp @@ -128,4 +128,3 @@ void ParamAutosave::Run() _retry_count = 0; } } - diff --git a/src/lib/parameters/parameters_primary.h b/src/lib/parameters/parameters_primary.h index 7994822d4c05..2d534cc24c4f 100644 --- a/src/lib/parameters/parameters_primary.h +++ b/src/lib/parameters/parameters_primary.h @@ -49,4 +49,3 @@ void param_primary_set_value(param_t param, const void *val); void param_primary_reset(param_t param); void param_primary_reset_all(); void param_primary_get_counters(struct param_primary_counters *cnt); - diff --git a/src/lib/parameters/px4params/jsonout.py b/src/lib/parameters/px4params/jsonout.py index 45f6cf291df4..e4a8b021bd19 100644 --- a/src/lib/parameters/px4params/jsonout.py +++ b/src/lib/parameters/px4params/jsonout.py @@ -146,4 +146,3 @@ def get_typed_value(value: str, type_name: str): def Save(self, filename): with codecs.open(filename, 'w', 'utf-8') as f: f.write(self.output) - diff --git a/src/lib/rc/ghst.cpp b/src/lib/rc/ghst.cpp index d3c13d7ad25c..1af68e8da01c 100644 --- a/src/lib/rc/ghst.cpp +++ b/src/lib/rc/ghst.cpp @@ -428,4 +428,3 @@ bool ghst_send_telemetry_gps2_status(int uart_fd, uint16_t ground_speed, uint16_ return write(uart_fd, buf, offset) == offset; } - diff --git a/src/lib/rc/rc_tests/RCTest.cpp b/src/lib/rc/rc_tests/RCTest.cpp index 5894bf7549db..a0f985cfe441 100644 --- a/src/lib/rc/rc_tests/RCTest.cpp +++ b/src/lib/rc/rc_tests/RCTest.cpp @@ -520,7 +520,4 @@ bool RCTest::sumdTest() return true; } - - ut_declare_test_c(rc_tests_main, RCTest) - diff --git a/src/lib/tecs/TECS.hpp b/src/lib/tecs/TECS.hpp index 3c16b97066e8..f033bf72dabf 100644 --- a/src/lib/tecs/TECS.hpp +++ b/src/lib/tecs/TECS.hpp @@ -742,4 +742,3 @@ class TECS */ void _setFastDescend(float alt_setpoint, float alt); }; - diff --git a/src/lib/version/get_git_tag_or_branch_version.sh b/src/lib/version/get_git_tag_or_branch_version.sh index a7d9c13b3346..4c8cfab62c81 100755 --- a/src/lib/version/get_git_tag_or_branch_version.sh +++ b/src/lib/version/get_git_tag_or_branch_version.sh @@ -18,4 +18,3 @@ if [ ! -f "$version_file" ]; then fi sed -n 's/.*PX4_GIT_TAG_OR_BRANCH_NAME\s*"\(.*\)".*/version=\1/p' "$version_file" - diff --git a/src/lib/version/version.c b/src/lib/version/version.c index ebf1749985d5..593c799e3331 100644 --- a/src/lib/version/version.c +++ b/src/lib/version/version.c @@ -366,4 +366,3 @@ const char *px4_firmware_oem_version_string(void) { return PX4_GIT_OEM_VERSION_STR; } - diff --git a/src/lib/version/version.h b/src/lib/version/version.h index 451393f835ed..cf6ad0ed83d4 100644 --- a/src/lib/version/version.h +++ b/src/lib/version/version.h @@ -206,4 +206,3 @@ __EXPORT uint64_t px4_os_version_binary(void); __EXPORT const char *px4_firmware_oem_version_string(void); __END_DECLS - diff --git a/src/lib/world_magnetic_model/geo_magnetic_tables.hpp b/src/lib/world_magnetic_model/geo_magnetic_tables.hpp index cba035c0e2f4..855a971406b8 100644 --- a/src/lib/world_magnetic_model/geo_magnetic_tables.hpp +++ b/src/lib/world_magnetic_model/geo_magnetic_tables.hpp @@ -138,5 +138,3 @@ static constexpr const int16_t totalintensity_table[19][37] { static constexpr float WMM_TOTALINTENSITY_SCALE_TO_NANOTESLA = 2.04183477f; static constexpr float WMM_TOTALINTENSITY_MIN_NANOTESLA = 22226.9f; // latitude: -30, longitude: -60 static constexpr float WMM_TOTALINTENSITY_MAX_NANOTESLA = 66904.8f; // latitude: -60, longitude: 130 - - diff --git a/src/modules/attitude_estimator_q/CMakeLists.txt b/src/modules/attitude_estimator_q/CMakeLists.txt index df9084fe2036..b72540872127 100644 --- a/src/modules/attitude_estimator_q/CMakeLists.txt +++ b/src/modules/attitude_estimator_q/CMakeLists.txt @@ -41,4 +41,3 @@ px4_add_module( DEPENDS world_magnetic_model ) - diff --git a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp index 9ea83999ef73..af0fd9aec5f0 100644 --- a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp +++ b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp @@ -190,4 +190,3 @@ class HealthAndArmingChecks : public ModuleParams &_vtol_checks, }; }; - diff --git a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecksTest.cpp b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecksTest.cpp index 912d3bb1293b..c06886320563 100644 --- a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecksTest.cpp +++ b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecksTest.cpp @@ -285,4 +285,3 @@ TEST_F(ReporterTest, reporting_multiple) } } } - diff --git a/src/modules/commander/HealthAndArmingChecks/checks/escCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/escCheck.cpp index cd7d716b31c8..9554c57a4f62 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/escCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/escCheck.cpp @@ -183,4 +183,3 @@ void EscChecks::checkEscStatus(const Context &context, Report &reporter, const e } } } - diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 58f8e582c982..2ede2baf6381 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -879,4 +879,3 @@ bool EstimatorChecks::checkPosVelValidity(const hrt_abstime &now, const bool dat return valid; } - diff --git a/src/modules/commander/ModeUtil/CMakeLists.txt b/src/modules/commander/ModeUtil/CMakeLists.txt index 8713e53f6bb8..98708bba2699 100644 --- a/src/modules/commander/ModeUtil/CMakeLists.txt +++ b/src/modules/commander/ModeUtil/CMakeLists.txt @@ -36,4 +36,3 @@ add_library(mode_util mode_requirements.cpp ) add_dependencies(mode_util uorb_headers prebuild_targets) - diff --git a/src/modules/commander/factory_calibration_storage.cpp b/src/modules/commander/factory_calibration_storage.cpp index 450f48c49de1..698d842cf568 100644 --- a/src/modules/commander/factory_calibration_storage.cpp +++ b/src/modules/commander/factory_calibration_storage.cpp @@ -130,4 +130,3 @@ void FactoryCalibrationStorage::cleanup() param_control_autosave(true); } } - diff --git a/src/modules/commander/failsafe/failsafe.h b/src/modules/commander/failsafe/failsafe.h index bb81dd02baeb..1c1b8bd86562 100644 --- a/src/modules/commander/failsafe/failsafe.h +++ b/src/modules/commander/failsafe/failsafe.h @@ -194,4 +194,3 @@ class Failsafe : public FailsafeBase ); }; - diff --git a/src/modules/commander/failsafe/framework.h b/src/modules/commander/failsafe/framework.h index 9f989582f7ce..4cd3ac5202c5 100644 --- a/src/modules/commander/failsafe/framework.h +++ b/src/modules/commander/failsafe/framework.h @@ -283,4 +283,3 @@ class FailsafeBase: public ModuleParams ); }; - diff --git a/src/modules/commander/failsafe/parse_flags_from_msg.py b/src/modules/commander/failsafe/parse_flags_from_msg.py index 6b1ddf24b95d..487a14e049f7 100755 --- a/src/modules/commander/failsafe/parse_flags_from_msg.py +++ b/src/modules/commander/failsafe/parse_flags_from_msg.py @@ -137,4 +137,3 @@ def __init__(self, group_name): html_template_content = html_template_content.replace(html_tag, html_conditions) with open(html_output_file, 'w') as file: file.write(html_template_content) - diff --git a/src/modules/commander/lm_fit.cpp b/src/modules/commander/lm_fit.cpp index 39eb571a794e..866fa6f07192 100644 --- a/src/modules/commander/lm_fit.cpp +++ b/src/modules/commander/lm_fit.cpp @@ -353,4 +353,3 @@ int lm_mag_fit(const float x[], const float y[], const float z[], unsigned int s return 1; } - diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h index de028bcef0fc..e4936982ff1b 100644 --- a/src/modules/commander/px4_custom_mode.h +++ b/src/modules/commander/px4_custom_mode.h @@ -232,4 +232,3 @@ static inline union px4_custom_mode get_px4_custom_mode(uint8_t nav_state) } #endif /* DEFINE_GET_PX4_CUSTOM_MODE */ - diff --git a/src/modules/commander/worker_thread.hpp b/src/modules/commander/worker_thread.hpp index 5194c6758d71..ae271c398829 100644 --- a/src/modules/commander/worker_thread.hpp +++ b/src/modules/commander/worker_thread.hpp @@ -100,4 +100,3 @@ class WorkerThread float _longitude; }; - diff --git a/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessRoverAckermann.cpp b/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessRoverAckermann.cpp index ed4d636809d3..94f5db16f36b 100644 --- a/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessRoverAckermann.cpp +++ b/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessRoverAckermann.cpp @@ -56,4 +56,3 @@ void ActuatorEffectivenessRoverAckermann::updateSetpoint(const matrix::Vector (ParamFloat) _param_com_spoolup_time ) }; - diff --git a/src/modules/px4iofirmware/serial.cpp b/src/modules/px4iofirmware/serial.cpp index ef4a18cba7e3..f945f05d4750 100644 --- a/src/modules/px4iofirmware/serial.cpp +++ b/src/modules/px4iofirmware/serial.cpp @@ -379,4 +379,3 @@ dma_reset(void) stm32_dmastart(rx_dma, rx_dma_callback, NULL, false); rCR3 |= USART_CR3_DMAR; } - diff --git a/src/modules/simulation/gz_bridge/parameters.c b/src/modules/simulation/gz_bridge/parameters.c index 8dd6022ff6a0..26f874e8933e 100644 --- a/src/modules/simulation/gz_bridge/parameters.c +++ b/src/modules/simulation/gz_bridge/parameters.c @@ -39,4 +39,3 @@ * @group UAVCAN */ PARAM_DEFINE_INT32(SIM_GZ_EN, 0); - diff --git a/src/modules/vtol_att_control/CMakeLists.txt b/src/modules/vtol_att_control/CMakeLists.txt index e6316b14593f..780217ccc6dc 100644 --- a/src/modules/vtol_att_control/CMakeLists.txt +++ b/src/modules/vtol_att_control/CMakeLists.txt @@ -40,4 +40,3 @@ px4_add_module( tailsitter.cpp standard.cpp ) - diff --git a/src/systemcmds/actuator_test/CMakeLists.txt b/src/systemcmds/actuator_test/CMakeLists.txt index a71e080b5bef..a919bf17c785 100644 --- a/src/systemcmds/actuator_test/CMakeLists.txt +++ b/src/systemcmds/actuator_test/CMakeLists.txt @@ -37,4 +37,3 @@ px4_add_module( SRCS actuator_test.cpp ) - diff --git a/src/systemcmds/dumpfile/CMakeLists.txt b/src/systemcmds/dumpfile/CMakeLists.txt index e8a7c1c5ac20..00fce2ce7bf8 100644 --- a/src/systemcmds/dumpfile/CMakeLists.txt +++ b/src/systemcmds/dumpfile/CMakeLists.txt @@ -39,4 +39,3 @@ px4_add_module( dumpfile.cpp DEPENDS ) - diff --git a/src/systemcmds/led_control/CMakeLists.txt b/src/systemcmds/led_control/CMakeLists.txt index a7396160cce1..7b742d0f5297 100644 --- a/src/systemcmds/led_control/CMakeLists.txt +++ b/src/systemcmds/led_control/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( led_control.cpp DEPENDS ) - diff --git a/src/systemcmds/mtd/CMakeLists.txt b/src/systemcmds/mtd/CMakeLists.txt index 1f2d23cb47e7..4f068d107316 100644 --- a/src/systemcmds/mtd/CMakeLists.txt +++ b/src/systemcmds/mtd/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( mtd.cpp DEPENDS ) - diff --git a/src/systemcmds/nshterm/CMakeLists.txt b/src/systemcmds/nshterm/CMakeLists.txt index 14f669c3de44..757ade306303 100644 --- a/src/systemcmds/nshterm/CMakeLists.txt +++ b/src/systemcmds/nshterm/CMakeLists.txt @@ -39,4 +39,3 @@ px4_add_module( nshterm.cpp DEPENDS ) - diff --git a/src/systemcmds/reboot/CMakeLists.txt b/src/systemcmds/reboot/CMakeLists.txt index 60f4cee88951..5987399037ef 100644 --- a/src/systemcmds/reboot/CMakeLists.txt +++ b/src/systemcmds/reboot/CMakeLists.txt @@ -39,4 +39,3 @@ px4_add_module( DEPENDS px4_platform ) - diff --git a/src/systemcmds/reflect/CMakeLists.txt b/src/systemcmds/reflect/CMakeLists.txt index 19241deaeca5..eb0e4042a72e 100644 --- a/src/systemcmds/reflect/CMakeLists.txt +++ b/src/systemcmds/reflect/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( reflect.c DEPENDS ) - diff --git a/src/systemcmds/sd_bench/CMakeLists.txt b/src/systemcmds/sd_bench/CMakeLists.txt index 9ab943a90b58..84e200eb2a28 100644 --- a/src/systemcmds/sd_bench/CMakeLists.txt +++ b/src/systemcmds/sd_bench/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( sd_bench.cpp DEPENDS ) - diff --git a/src/systemcmds/serial_test/.gitignore b/src/systemcmds/serial_test/.gitignore index ab9845d6fe4b..7d522907613e 100644 --- a/src/systemcmds/serial_test/.gitignore +++ b/src/systemcmds/serial_test/.gitignore @@ -1,3 +1,2 @@ /serial_test - diff --git a/src/systemcmds/tests/test_file2.c b/src/systemcmds/tests/test_file2.c index 6f270de7013e..606f39abf309 100644 --- a/src/systemcmds/tests/test_file2.c +++ b/src/systemcmds/tests/test_file2.c @@ -224,4 +224,3 @@ int test_file2(int argc, char *argv[]) return test_corruption(filename, write_chunk, write_size, flags); } - diff --git a/src/systemcmds/topic_listener/CMakeLists.txt b/src/systemcmds/topic_listener/CMakeLists.txt index e5f127fd1ff9..caf6201e4802 100644 --- a/src/systemcmds/topic_listener/CMakeLists.txt +++ b/src/systemcmds/topic_listener/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( SRCS listener_main.cpp ) - diff --git a/src/systemcmds/usb_connected/CMakeLists.txt b/src/systemcmds/usb_connected/CMakeLists.txt index f06ba157a9bd..0d308672bd23 100644 --- a/src/systemcmds/usb_connected/CMakeLists.txt +++ b/src/systemcmds/usb_connected/CMakeLists.txt @@ -38,4 +38,3 @@ px4_add_module( usb_connected.cpp DEPENDS ) - diff --git a/src/templates/template_module/CMakeLists.txt b/src/templates/template_module/CMakeLists.txt index ddda8ba394ed..2e8e0644c24f 100644 --- a/src/templates/template_module/CMakeLists.txt +++ b/src/templates/template_module/CMakeLists.txt @@ -37,4 +37,3 @@ px4_add_module( SRCS template_module.cpp ) - diff --git a/src/templates/template_module/template_module.h b/src/templates/template_module/template_module.h index 0212fe9a3cd0..83a5db2c2c15 100644 --- a/src/templates/template_module/template_module.h +++ b/src/templates/template_module/template_module.h @@ -87,4 +87,3 @@ class TemplateModule : public ModuleBase, public ModuleParams uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; }; - diff --git a/test/mavsdk_tests/catch2/catch.hpp b/test/mavsdk_tests/catch2/catch.hpp index db1fed3b9813..71c863abeeb8 100644 --- a/test/mavsdk_tests/catch2/catch.hpp +++ b/test/mavsdk_tests/catch2/catch.hpp @@ -17963,4 +17963,3 @@ using Catch::Detail::Approx; // end catch_reenable_warnings.h // end catch.hpp #endif // TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED - diff --git a/test/mavsdk_tests/test_multicopter_failure_injection.cpp b/test/mavsdk_tests/test_multicopter_failure_injection.cpp index 75d804813282..d553ed759639 100644 --- a/test/mavsdk_tests/test_multicopter_failure_injection.cpp +++ b/test/mavsdk_tests/test_multicopter_failure_injection.cpp @@ -51,4 +51,3 @@ TEST_CASE("Failure Injection - Reject mid-air when it is disabled", "[multicopte std::chrono::seconds until_disarmed_timeout = std::chrono::seconds(180); tester.wait_until_disarmed(until_disarmed_timeout); } - diff --git a/validation/module_schema.yaml b/validation/module_schema.yaml index 827087174e8a..1e1baa103707 100644 --- a/validation/module_schema.yaml +++ b/validation/module_schema.yaml @@ -590,5 +590,3 @@ mixer: minlength: 3 maxlength: 3 type: number - - From f8bebd9e41e913f4045de8be060f52a4dab5df27 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Thu, 18 Jul 2024 13:34:56 +0200 Subject: [PATCH 518/652] ackermann: implement pure pursuit lib --- msg/RoverAckermannGuidanceStatus.msg | 1 - src/modules/rover_ackermann/CMakeLists.txt | 1 + .../RoverAckermannGuidance.cpp | 88 +++---------------- .../RoverAckermannGuidance.hpp | 13 +-- 4 files changed, 13 insertions(+), 90 deletions(-) diff --git a/msg/RoverAckermannGuidanceStatus.msg b/msg/RoverAckermannGuidanceStatus.msg index 69dec269420f..a06d1290bf50 100644 --- a/msg/RoverAckermannGuidanceStatus.msg +++ b/msg/RoverAckermannGuidanceStatus.msg @@ -4,6 +4,5 @@ float32 desired_speed # [m/s] Rover desired ground speed float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller float32 heading_error # [deg] Heading error of the pure pursuit controller float32 pid_throttle_integral # [-1, 1] Integral of the PID for the normalized throttle to control the rover speed during missions -float32 crosstrack_error # [m] Shortest distance from the vehicle to the path # TOPICS rover_ackermann_guidance_status diff --git a/src/modules/rover_ackermann/CMakeLists.txt b/src/modules/rover_ackermann/CMakeLists.txt index 805e20b73f7b..f02a91c0b6dc 100644 --- a/src/modules/rover_ackermann/CMakeLists.txt +++ b/src/modules/rover_ackermann/CMakeLists.txt @@ -43,6 +43,7 @@ px4_add_module( RoverAckermannGuidance px4_work_queue SlewRate + pure_pursuit MODULE_CONFIG module.yaml ) diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index 19cdf5cf1aa5..bd77e31eea75 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -209,21 +209,24 @@ void RoverAckermannGuidance::updateWaypoints() _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); // Global waypoint coordinates - if (position_setpoint_triplet.current.valid) { + 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); } else { _curr_wp = Vector2d(0, 0); } - if (position_setpoint_triplet.previous.valid) { + 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); } else { _prev_wp = _curr_pos; } - if (position_setpoint_triplet.next.valid) { + 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); } else { @@ -280,45 +283,16 @@ float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_local, const Vector2f &curr_pos_local, const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, const float &wheel_base, const float &desired_speed, const float &vehicle_yaw) { - // Calculate crosstrack error - const Vector2f prev_wp_to_curr_wp_local = curr_wp_local - prev_wp_local; - - if (prev_wp_to_curr_wp_local.norm() < FLT_EPSILON) { // Avoid division by 0 (this case should not happen) - return 0.f; - } - - const Vector2f prev_wp_to_curr_pos_local = curr_pos_local - prev_wp_local; - const Vector2f distance_on_line_segment = ((prev_wp_to_curr_pos_local * prev_wp_to_curr_wp_local) / - prev_wp_to_curr_wp_local.norm()) * prev_wp_to_curr_wp_local.normalized(); - const Vector2f crosstrack_error = (prev_wp_local + distance_on_line_segment) - curr_pos_local; - - // Calculate desired heading towards lookahead point - float desired_heading{0.f}; - float lookahead_distance = math::constrain(lookahead_gain * desired_speed, - lookahead_min, lookahead_max); - - if (crosstrack_error.longerThan(lookahead_distance)) { - if (crosstrack_error.norm() < lookahead_max) { - lookahead_distance = crosstrack_error.norm(); // Scale lookahead radius - desired_heading = calcDesiredHeading(curr_wp_local, prev_wp_local, curr_pos_local, lookahead_distance); - - } else { // Excessively large crosstrack error - desired_heading = calcDesiredHeading(curr_wp_local, curr_pos_local, curr_pos_local, lookahead_distance); - } - - } else { // Crosstrack error smaller than lookahead - desired_heading = calcDesiredHeading(curr_wp_local, prev_wp_local, curr_pos_local, lookahead_distance); - } - // Calculate desired steering to reach lookahead point + const float lookahead_distance = math::constrain(lookahead_gain * desired_speed, + lookahead_min, lookahead_max); + const float desired_heading = _pure_pursuit.calcDesiredHeading(curr_wp_local, prev_wp_local, curr_pos_local, + lookahead_distance); const float heading_error = matrix::wrap_pi(desired_heading - vehicle_yaw); - // For logging _rover_ackermann_guidance_status.lookahead_distance = lookahead_distance; _rover_ackermann_guidance_status.heading_error = (heading_error * 180.f) / (M_PI_F); - _rover_ackermann_guidance_status.crosstrack_error = crosstrack_error.norm(); - // Calculate desired steering if (math::abs_t(heading_error) <= M_PI_2_F) { return atanf(2 * wheel_base * sinf(heading_error) / lookahead_distance); @@ -330,47 +304,5 @@ float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_local, return atanf(2 * wheel_base * (-1.0f + sinf(heading_error + M_PI_2_F)) / lookahead_distance); } -} -float RoverAckermannGuidance::calcDesiredHeading(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, - const Vector2f &curr_pos_local, - const float &lookahead_distance) -{ - // Setup variables - const float line_segment_slope = (curr_wp_local(1) - prev_wp_local(1)) / (curr_wp_local(0) - prev_wp_local(0)); - const float line_segment_rover_offset = prev_wp_local(1) - curr_pos_local(1) + line_segment_slope * (curr_pos_local( - 0) - prev_wp_local(0)); - const float a = -line_segment_slope; - const float c = -line_segment_rover_offset; - const float r = lookahead_distance; - const float x0 = -a * c / (a * a + 1.0f); - const float y0 = -c / (a * a + 1.0f); - - // Calculate intersection points - if (c * c > r * r * (a * a + 1.0f) + FLT_EPSILON) { // No intersection points exist - return 0.f; - - } else if (abs(c * c - r * r * (a * a + 1.0f)) < FLT_EPSILON) { // One intersection point exists - return atan2f(y0, x0); - - } else { // Two intersetion points exist - const float d = r * r - c * c / (a * a + 1.0f); - const float mult = sqrt(d / (a * a + 1.0f)); - const float ax = x0 + mult; - const float bx = x0 - mult; - const float ay = y0 - a * mult; - const float by = y0 + a * mult; - const Vector2f point1(ax, ay); - const Vector2f point2(bx, by); - const Vector2f distance1 = (curr_wp_local - curr_pos_local) - point1; - const Vector2f distance2 = (curr_wp_local - curr_pos_local) - point2; - - // Return intersection point closer to current waypoint - if (distance1.norm_squared() < distance2.norm_squared()) { - return atan2f(ay, ax); - - } else { - return atan2f(by, bx); - } - } } diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index a618f830e593..2674f67ca4eb 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -35,6 +35,7 @@ // PX4 includes #include +#include // uORB includes #include @@ -121,17 +122,6 @@ class RoverAckermannGuidance : public ModuleParams const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, const float &wheel_base, const float &desired_speed, const float &vehicle_yaw); - /** - * @brief Return desired heading to the intersection point between a circle with a radius of - * lookahead_distance around the vehicle and a line segment from the previous to the current waypoint. - * @param curr_wp_local Current waypoint in local frame. - * @param prev_wp_local Previous waypoint in local frame. - * @param curr_pos_local Current position of the vehicle in local frame. - * @param lookahead_distance Radius of circle around vehicle. - */ - float calcDesiredHeading(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, const Vector2f &curr_pos_local, - const float &lookahead_distance); - protected: /** * @brief Update the parameters of the module. @@ -154,6 +144,7 @@ class RoverAckermannGuidance : public ModuleParams MapProjection _global_local_proj_ref{}; // Transform global to local coordinates. + PurePursuit _pure_pursuit; // Pure pursuit library // Rover variables Vector2d _curr_pos{}; From aa0dda744388271d7477bd3099c5ea2ba6da5599 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Thu, 18 Jul 2024 13:50:22 +0200 Subject: [PATCH 519/652] ackermann: fix naming conventions --- .../rover_ackermann/RoverAckermann.cpp | 2 +- .../RoverAckermannGuidance.cpp | 48 +++++++++---------- .../RoverAckermannGuidance.hpp | 32 ++++++------- 3 files changed, 39 insertions(+), 43 deletions(-) diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index e65eb11442e8..b5468880587c 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -112,7 +112,7 @@ void RoverAckermann::Run() case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: - _motor_setpoint = _ackermann_guidance.purePursuit(_nav_state); + _motor_setpoint = _ackermann_guidance.computeGuidance(_nav_state); break; default: // Unimplemented nav states will stop the rover diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index bd77e31eea75..3cc6dfc3c2b9 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -56,7 +56,7 @@ void RoverAckermannGuidance::updateParams() 1); // Output limit } -RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit(const int nav_state) +RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(const int nav_state) { // Initializations float desired_speed{0.f}; @@ -76,12 +76,12 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit(const vehicle_local_position_s local_position{}; _local_position_sub.copy(&local_position); - if (!_global_local_proj_ref.isInitialized() - || (_global_local_proj_ref.getProjectionReferenceTimestamp() != local_position.ref_timestamp)) { - _global_local_proj_ref.initReference(local_position.ref_lat, local_position.ref_lon, local_position.ref_timestamp); + 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_local = Vector2f(local_position.x, local_position.y); + _curr_pos_ned = Vector2f(local_position.x, local_position.y); const Vector3f rover_velocity = {local_position.vx, local_position.vy, local_position.vz}; actual_speed = rover_velocity.norm(); } @@ -162,7 +162,7 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit(const } // Calculate desired steering - desired_steering = calcDesiredSteering(_curr_wp_local, _prev_wp_local, _curr_pos_local, _param_ra_lookahd_gain.get(), + desired_steering = calcDesiredSteering(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, _param_ra_lookahd_gain.get(), _param_ra_lookahd_min.get(), _param_ra_lookahd_max.get(), _param_ra_wheel_base.get(), desired_speed, vehicle_yaw); desired_steering = math::constrain(desired_steering, -_param_ra_max_steer_angle.get(), _param_ra_max_steer_angle.get()); @@ -233,16 +233,16 @@ void RoverAckermannGuidance::updateWaypoints() _next_wp = _home_position; // Enables corner slow down with RTL } - // Local waypoint coordinates - _curr_wp_local = _global_local_proj_ref.project(_curr_wp(0), _curr_wp(1)); - _prev_wp_local = _global_local_proj_ref.project(_prev_wp(0), _prev_wp(1)); - _next_wp_local = _global_local_proj_ref.project(_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)); // Update acceptance radius _prev_acceptance_radius = _acceptance_radius; if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) { - _acceptance_radius = updateAcceptanceRadius(_curr_wp_local, _prev_wp_local, _next_wp_local, _param_nav_acc_rad.get(), + _acceptance_radius = updateAcceptanceRadius(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, _param_nav_acc_rad.get(), _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_steer_angle.get()); } else { @@ -250,19 +250,19 @@ void RoverAckermannGuidance::updateWaypoints() } } -float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, - const Vector2f &next_wp_local, const float &default_acceptance_radius, const float &acceptance_radius_gain, +float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, + const Vector2f &next_wp_ned, const float &default_acceptance_radius, const float &acceptance_radius_gain, const float &acceptance_radius_max, const float &wheel_base, const float &max_steer_angle) { // Setup variables - const Vector2f curr_to_prev_wp_local = prev_wp_local - curr_wp_local; - const Vector2f curr_to_next_wp_local = next_wp_local - curr_wp_local; + const Vector2f curr_to_prev_wp_ned = prev_wp_ned - curr_wp_ned; + const Vector2f curr_to_next_wp_ned = next_wp_ned - curr_wp_ned; float acceptance_radius = default_acceptance_radius; // Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment - if (curr_to_next_wp_local.norm() > FLT_EPSILON && curr_to_prev_wp_local.norm() > FLT_EPSILON) { - const float theta = acosf((curr_to_prev_wp_local * curr_to_next_wp_local) / (curr_to_prev_wp_local.norm() * - curr_to_next_wp_local.norm())) / 2.f; + if (curr_to_next_wp_ned.norm() > FLT_EPSILON && curr_to_prev_wp_ned.norm() > FLT_EPSILON) { + const float theta = acosf((curr_to_prev_wp_ned * curr_to_next_wp_ned) / (curr_to_prev_wp_ned.norm() * + curr_to_next_wp_ned.norm())) / 2.f; const float min_turning_radius = wheel_base / sinf(max_steer_angle); const float acceptance_radius_temp = min_turning_radius / tanf(theta); const float acceptance_radius_temp_scaled = acceptance_radius_gain * @@ -279,14 +279,14 @@ float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_loc return acceptance_radius; } -float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, - const Vector2f &curr_pos_local, const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, +float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, + const Vector2f &curr_pos_ned, const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, const float &wheel_base, const float &desired_speed, const float &vehicle_yaw) { // Calculate desired steering to reach lookahead point const float lookahead_distance = math::constrain(lookahead_gain * desired_speed, lookahead_min, lookahead_max); - const float desired_heading = _pure_pursuit.calcDesiredHeading(curr_wp_local, prev_wp_local, curr_pos_local, + const float desired_heading = _pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, lookahead_distance); const float heading_error = matrix::wrap_pi(desired_heading - vehicle_yaw); // For logging @@ -296,12 +296,8 @@ float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_local, if (math::abs_t(heading_error) <= M_PI_2_F) { return atanf(2 * wheel_base * sinf(heading_error) / lookahead_distance); - } else if (heading_error > FLT_EPSILON) { - return atanf(2 * wheel_base * (1.0f + sinf(heading_error - M_PI_2_F)) / - lookahead_distance); - } else { - return atanf(2 * wheel_base * (-1.0f + sinf(heading_error + M_PI_2_F)) / + return atanf(2 * wheel_base * (sign(heading_error) * 1.0f + sinf(heading_error - sign(heading_error) * M_PI_2_F)) / lookahead_distance); } diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index 2674f67ca4eb..090f37b15e97 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -82,10 +82,10 @@ class RoverAckermannGuidance : public ModuleParams * @brief Compute guidance for ackermann rover and return motor_setpoint for throttle and steering. * @param nav_state Vehicle navigation state */ - motor_setpoint purePursuit(const int nav_state); + motor_setpoint computeGuidance(const int nav_state); /** - * @brief Update global/local waypoint coordinates and acceptance radius + * @brief Update global/NED waypoint coordinates and acceptance radius */ void updateWaypoints(); @@ -93,24 +93,24 @@ class RoverAckermannGuidance : public ModuleParams * @brief Returns and publishes the acceptance radius for current waypoint based on the angle between a line segment * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of * the vehicle. - * @param curr_wp_local Current waypoint in local frame. - * @param prev_wp_local Previous waypoint in local frame. - * @param next_wp_local Next waypoint in local frame. + * @param curr_wp_ned Current waypoint in NED frame. + * @param prev_wp_ned Previous waypoint in NED frame. + * @param next_wp_ned Next waypoint in NED frame. * @param default_acceptance_radius Default acceptance radius for waypoints. * @param acceptance_radius_gain Scaling of the geometric optimal acceptance radius for the rover to cut corners. * @param acceptance_radius_max Maximum value for the acceptance radius. * @param wheel_base Rover wheelbase. * @param max_steer_angle Rover maximum steer angle. */ - float updateAcceptanceRadius(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, - const Vector2f &next_wp_local, const float &default_acceptance_radius, const float &acceptance_radius_gain, + float updateAcceptanceRadius(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, + const Vector2f &next_wp_ned, const float &default_acceptance_radius, const float &acceptance_radius_gain, const float &acceptance_radius_max, const float &wheel_base, const float &max_steer_angle); /** * @brief Calculate and return desired steering input - * @param curr_wp_local Current waypoint in local frame. - * @param prev_wp_local Previous waypoint in local frame. - * @param curr_pos_local Current position of the vehicle in local frame. + * @param curr_wp_ned Current waypoint in NED frame. + * @param prev_wp_ned Previous waypoint in NED frame. + * @param curr_pos_ned Current position of the vehicle in NED frame. * @param lookahead_gain Tuning parameter for the lookahead distance pure pursuit controller. * @param lookahead_min Minimum lookahead distance. * @param lookahead_max Maximum lookahead distance. @@ -118,7 +118,7 @@ class RoverAckermannGuidance : public ModuleParams * @param desired_speed Desired speed for the rover. * @param vehicle_yaw Current yaw of the rover. */ - float calcDesiredSteering(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local, const Vector2f &curr_pos_local, + float calcDesiredSteering(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, const float &wheel_base, const float &desired_speed, const float &vehicle_yaw); @@ -143,12 +143,12 @@ class RoverAckermannGuidance : public ModuleParams rover_ackermann_guidance_status_s _rover_ackermann_guidance_status{}; - MapProjection _global_local_proj_ref{}; // Transform global to local coordinates. + MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates. PurePursuit _pure_pursuit; // Pure pursuit library // Rover variables Vector2d _curr_pos{}; - Vector2f _curr_pos_local{}; + Vector2f _curr_pos_ned{}; PID_t _pid_throttle; hrt_abstime _timestamp{0}; @@ -157,9 +157,9 @@ class RoverAckermannGuidance : public ModuleParams Vector2d _next_wp{}; Vector2d _prev_wp{}; Vector2d _home_position{}; - Vector2f _curr_wp_local{}; - Vector2f _prev_wp_local{}; - Vector2f _next_wp_local{}; + Vector2f _curr_wp_ned{}; + Vector2f _prev_wp_ned{}; + Vector2f _next_wp_ned{}; float _acceptance_radius{0.5f}; float _prev_acceptance_radius{0.5f}; From 561dceea7bd4a0434745a85cb0b936bacc80d517 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 17 Jul 2024 12:38:32 -0400 Subject: [PATCH 520/652] drivers/rc: new standalone dsm_rc driver - extracted from monolithic drivers/rc_input which will eventually be dropped once all drivers migrated and boards updated --- src/drivers/rc/dsm_rc/CMakeLists.txt | 44 +++ src/drivers/rc/dsm_rc/DsmRc.cpp | 417 +++++++++++++++++++++++++++ src/drivers/rc/dsm_rc/DsmRc.hpp | 102 +++++++ src/drivers/rc/dsm_rc/Kconfig | 5 + src/drivers/rc/dsm_rc/module.yaml | 11 + 5 files changed, 579 insertions(+) create mode 100644 src/drivers/rc/dsm_rc/CMakeLists.txt create mode 100644 src/drivers/rc/dsm_rc/DsmRc.cpp create mode 100644 src/drivers/rc/dsm_rc/DsmRc.hpp create mode 100644 src/drivers/rc/dsm_rc/Kconfig create mode 100644 src/drivers/rc/dsm_rc/module.yaml diff --git a/src/drivers/rc/dsm_rc/CMakeLists.txt b/src/drivers/rc/dsm_rc/CMakeLists.txt new file mode 100644 index 000000000000..addfa9afb59a --- /dev/null +++ b/src/drivers/rc/dsm_rc/CMakeLists.txt @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2015-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_module( + MODULE drivers__rc__dsm_rc + MAIN dsm_rc + COMPILE_FLAGS + SRCS + DsmRc.cpp + DsmRc.hpp + MODULE_CONFIG + module.yaml + DEPENDS + rc + ) diff --git a/src/drivers/rc/dsm_rc/DsmRc.cpp b/src/drivers/rc/dsm_rc/DsmRc.cpp new file mode 100644 index 000000000000..f35bc4487ff0 --- /dev/null +++ b/src/drivers/rc/dsm_rc/DsmRc.cpp @@ -0,0 +1,417 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 "DsmRc.hpp" + +#include + +#include + +using namespace time_literals; + +DsmRc::DsmRc(const char *device) : + ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(device)), + _cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")), + _publish_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": publish interval")) +{ + if (device) { + strncpy(_device, device, sizeof(_device) - 1); + _device[sizeof(_device) - 1] = '\0'; + } +} + +DsmRc::~DsmRc() +{ +#if defined(SPEKTRUM_POWER_PASSIVE) + // Disable power controls for Spektrum receiver + SPEKTRUM_POWER_PASSIVE(); +#endif // SPEKTRUM_POWER_PASSIVE + + perf_free(_cycle_perf); + perf_free(_publish_interval_perf); +} + +int DsmRc::task_spawn(int argc, char *argv[]) +{ + bool error_flag = false; + + int myoptind = 1; + int ch; + const char *myoptarg = nullptr; + const char *device_name = nullptr; + bool silent = false; + + while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'd': + device_name = myoptarg; + silent = false; + break; + + case '?': + error_flag = true; + break; + + default: + PX4_WARN("unrecognized flag"); + error_flag = true; + break; + } + } + + if (error_flag) { + return -1; + } + + if (device_name && (access(device_name, R_OK | W_OK) == 0)) { + DsmRc *instance = new DsmRc(device_name); + + if (instance == nullptr) { + PX4_ERR("alloc failed"); + return PX4_ERROR; + } + + _object.store(instance); + _task_id = task_id_is_work_queue; + + instance->ScheduleOnInterval(_current_update_interval); + + return PX4_OK; + + } else if (silent) { + return PX4_OK; + + } else { + if (device_name) { + PX4_ERR("invalid device (-d) %s", device_name); + + } else { + PX4_ERR("valid device required"); + } + } + + return PX4_ERROR; +} + +void DsmRc::Run() +{ + if (should_exit()) { + + close(_rcs_fd); + + dsm_deinit(); + + exit_and_cleanup(); + return; + } + + perf_begin(_cycle_perf); + + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status; + + if (_vehicle_status_sub.copy(&vehicle_status)) { + _armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED); + } + } + + const hrt_abstime cycle_timestamp = hrt_absolute_time(); + + + /* vehicle command */ + vehicle_command_s vcmd; + + if (_vehicle_cmd_sub.update(&vcmd)) { + // Check for a pairing command + if (vcmd.command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR) { + + uint8_t cmd_ret = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED; +#if defined(SPEKTRUM_POWER) + + if (!_rc_scan_locked && !_armed) { + if ((int)vcmd.param1 == 0) { + // DSM binding command + int dsm_bind_mode = (int)vcmd.param2; + + int dsm_bind_pulses = 0; + + if (dsm_bind_mode == 0) { + dsm_bind_pulses = DSM2_BIND_PULSES; + + } else if (dsm_bind_mode == 1) { + dsm_bind_pulses = DSMX_BIND_PULSES; + + } else { + dsm_bind_pulses = DSMX8_BIND_PULSES; + } + + bind_spektrum(dsm_bind_pulses); + + cmd_ret = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; + } + + } else { + cmd_ret = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; + } + +#endif // SPEKTRUM_POWER + + // publish acknowledgement + vehicle_command_ack_s command_ack{}; + command_ack.command = vcmd.command; + command_ack.result = cmd_ret; + command_ack.target_system = vcmd.source_system; + command_ack.target_component = vcmd.source_component; + command_ack.timestamp = hrt_absolute_time(); + uORB::Publication vehicle_command_ack_pub{ORB_ID(vehicle_command_ack)}; + vehicle_command_ack_pub.publish(command_ack); + } + } + + bool rc_updated = false; + + constexpr hrt_abstime rc_scan_max = 3_s; + + // read all available data from the serial RC input UART + uint8_t rcs_buf[DSM_BUFFER_SIZE] {}; + int newBytes = ::read(_rcs_fd, &rcs_buf[0], DSM_BUFFER_SIZE); + + if (newBytes > 0) { + _bytes_rx += newBytes; + } + + const bool rc_scan_locked = _rc_scan_locked; + + if (_rc_scan_begin == 0) { + _rc_scan_begin = cycle_timestamp; + + // Configure serial port + if (_rcs_fd < 0) { + _rcs_fd = open(_device, O_RDWR | O_NONBLOCK); + } + + dsm_config(_rcs_fd); + + // flush serial buffer and any existing buffered data + tcflush(_rcs_fd, TCIOFLUSH); + + } else if (_rc_scan_locked + || cycle_timestamp - _rc_scan_begin < rc_scan_max) { + + if (newBytes > 0) { + uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {}; + uint16_t raw_rc_count = 0; + + int8_t dsm_rssi = 0; + bool dsm_11_bit = false; + unsigned frame_drops = 0; + + if (dsm_parse(cycle_timestamp, &rcs_buf[0], newBytes, &raw_rc_values[0], &raw_rc_count, &dsm_11_bit, &frame_drops, + &dsm_rssi, input_rc_s::RC_INPUT_MAX_CHANNELS) + ) { + // we have a new DSM frame. Publish it. + input_rc_s input_rc{}; + input_rc.timestamp_last_signal = cycle_timestamp; + input_rc.channel_count = math::constrain(raw_rc_count, (uint16_t)0, (uint16_t)input_rc_s::RC_INPUT_MAX_CHANNELS); + input_rc.rssi = dsm_rssi; + input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_DSM; + + unsigned valid_chans = 0; + + for (unsigned i = 0; i < input_rc.channel_count; i++) { + input_rc.values[i] = raw_rc_values[i]; + + if (raw_rc_values[i] != UINT16_MAX) { + valid_chans++; + } + } + + input_rc.channel_count = valid_chans; + + if (valid_chans == 0) { + input_rc.rssi = 0; + } + + input_rc.rc_lost = (valid_chans == 0); + input_rc.rc_lost_frame_count = frame_drops; + + input_rc.link_quality = -1; + input_rc.rssi_dbm = NAN; + + input_rc.timestamp = hrt_absolute_time(); + _input_rc_pub.publish(input_rc); + perf_count(_publish_interval_perf); + + _timestamp_last_signal = cycle_timestamp; + rc_updated = true; + + if (valid_chans > 0) { + _rc_scan_locked = true; + } + } + } + + } else { + _rc_scan_begin = 0; + _rc_scan_locked = false; + + close(_rcs_fd); + _rcs_fd = -1; + } + + if (!rc_updated && !_armed && (hrt_elapsed_time(&_timestamp_last_signal) > 1_s)) { + _rc_scan_locked = false; + } + + if (!rc_scan_locked && _rc_scan_locked) { + PX4_INFO("RC input locked"); + } + + perf_end(_cycle_perf); +} + +#if defined(SPEKTRUM_POWER) +bool DsmRc::bind_spektrum(int arg) const +{ + int ret = PX4_ERROR; + + /* specify 11ms DSMX. RX will automatically fall back to 22ms or DSM2 if necessary */ + + /* only allow DSM2, DSM-X and DSM-X with more than 7 channels */ + PX4_INFO("DSM_BIND_START: DSM%s RX", (arg == 0) ? "2" : ((arg == 1) ? "-X" : "-X8")); + + if (arg == DSM2_BIND_PULSES || + arg == DSMX_BIND_PULSES || + arg == DSMX8_BIND_PULSES) { + + dsm_bind(DSM_CMD_BIND_POWER_DOWN, 0); + + dsm_bind(DSM_CMD_BIND_SET_RX_OUT, 0); + usleep(500000); + + dsm_bind(DSM_CMD_BIND_POWER_UP, 0); + usleep(72000); + + irqstate_t flags = px4_enter_critical_section(); + dsm_bind(DSM_CMD_BIND_SEND_PULSES, arg); + px4_leave_critical_section(flags); + + usleep(50000); + + dsm_bind(DSM_CMD_BIND_REINIT_UART, 0); + + ret = OK; + + } else { + PX4_ERR("DSM bind failed"); + ret = -EINVAL; + } + + return (ret == PX4_OK); +} +#endif /* SPEKTRUM_POWER */ + +int DsmRc::custom_command(int argc, char *argv[]) +{ +#if defined(SPEKTRUM_POWER) + const char *verb = argv[0]; + + if (!strcmp(verb, "bind")) { + uORB::Publication vehicle_command_pub{ORB_ID(vehicle_command)}; + vehicle_command_s vcmd{}; + vcmd.command = vehicle_command_s::VEHICLE_CMD_START_RX_PAIR; + vcmd.timestamp = hrt_absolute_time(); + vehicle_command_pub.publish(vcmd); + return 0; + } + +#endif // SPEKTRUM_POWER + + if (!is_running()) { + int ret = DsmRc::task_spawn(argc, argv); + + if (ret) { + return ret; + } + } + + return print_usage("unknown command"); +} + +int DsmRc::print_status() +{ + PX4_INFO("Max update rate: %u Hz", 1000000 / _current_update_interval); + + if (_device[0] != '\0') { + PX4_INFO("UART device: %s", _device); + PX4_INFO("UART RX bytes: %" PRIu32, _bytes_rx); + } + + PX4_INFO("RC state: %s", _rc_scan_locked ? "found" : "searching for signal"); + + perf_print_counter(_cycle_perf); + perf_print_counter(_publish_interval_perf); + + return 0; +} + +int DsmRc::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +This module does Spektrum DSM RC input parsing. + +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("dsm_rc", "driver"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); + +#if defined(SPEKTRUM_POWER) + PRINT_MODULE_USAGE_COMMAND_DESCR("bind", "Send a DSM bind command (module must be running)"); +#endif /* SPEKTRUM_POWER */ + + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int dsm_rc_main(int argc, char *argv[]) +{ + return DsmRc::main(argc, argv); +} diff --git a/src/drivers/rc/dsm_rc/DsmRc.hpp b/src/drivers/rc/dsm_rc/DsmRc.hpp new file mode 100644 index 000000000000..5ce935ec5de1 --- /dev/null +++ b/src/drivers/rc/dsm_rc/DsmRc.hpp @@ -0,0 +1,102 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +class DsmRc : public ModuleBase, public px4::ScheduledWorkItem +{ +public: + + DsmRc(const char *device); + virtual ~DsmRc(); + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + /** @see ModuleBase::print_status() */ + int print_status() override; + +private: + + void Run() override; + +#if defined(SPEKTRUM_POWER) + bool bind_spektrum(int arg = DSMX8_BIND_PULSES) const; +#endif // SPEKTRUM_POWER + + hrt_abstime _rc_scan_begin{0}; + hrt_abstime _timestamp_last_signal{0}; + + bool _rc_scan_locked{false}; + + static constexpr unsigned _current_update_interval{4000}; // 250 Hz + + uORB::Subscription _vehicle_cmd_sub{ORB_ID(vehicle_command)}; + uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; + + uORB::PublicationMulti _input_rc_pub{ORB_ID(input_rc)}; + + bool _armed{false}; + + int _rcs_fd{-1}; + char _device[20] {}; ///< device / serial port path + + perf_counter_t _cycle_perf; + perf_counter_t _publish_interval_perf; + uint32_t _bytes_rx{0}; +}; diff --git a/src/drivers/rc/dsm_rc/Kconfig b/src/drivers/rc/dsm_rc/Kconfig new file mode 100644 index 000000000000..19095081606c --- /dev/null +++ b/src/drivers/rc/dsm_rc/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RC_DSM_RC + bool "dsm_rc" + default n + ---help--- + Enable support for dsm_rc diff --git a/src/drivers/rc/dsm_rc/module.yaml b/src/drivers/rc/dsm_rc/module.yaml new file mode 100644 index 000000000000..4117b4eb76de --- /dev/null +++ b/src/drivers/rc/dsm_rc/module.yaml @@ -0,0 +1,11 @@ +module_name: DSM RC Input Driver +serial_config: + - command: "dsm_rc start -d ${SERIAL_DEV}" + port_config_param: + name: RC_DSM_PRT_CFG + group: Serial + #default: RC + #depends_on_port: RC + description_extended: | + DSM RC (Spektrum) driver. + From 7a6c4f0bfacb7f9c6b98d23173d29e165282c932 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 17 Jul 2024 12:53:49 -0400 Subject: [PATCH 521/652] drivers/rc: new standalone sbus_rc driver - extracted from monolithic drivers/rc_input which will eventually be dropped once all drivers migrated and boards updated --- src/drivers/rc/sbus_rc/CMakeLists.txt | 44 ++++ src/drivers/rc/sbus_rc/Kconfig | 5 + src/drivers/rc/sbus_rc/SbusRc.cpp | 315 ++++++++++++++++++++++++++ src/drivers/rc/sbus_rc/SbusRc.hpp | 102 +++++++++ src/drivers/rc/sbus_rc/module.yaml | 11 + 5 files changed, 477 insertions(+) create mode 100644 src/drivers/rc/sbus_rc/CMakeLists.txt create mode 100644 src/drivers/rc/sbus_rc/Kconfig create mode 100644 src/drivers/rc/sbus_rc/SbusRc.cpp create mode 100644 src/drivers/rc/sbus_rc/SbusRc.hpp create mode 100644 src/drivers/rc/sbus_rc/module.yaml diff --git a/src/drivers/rc/sbus_rc/CMakeLists.txt b/src/drivers/rc/sbus_rc/CMakeLists.txt new file mode 100644 index 000000000000..fd5e56263330 --- /dev/null +++ b/src/drivers/rc/sbus_rc/CMakeLists.txt @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2015-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_module( + MODULE drivers__rc__sbus_rc + MAIN sbus_rc + COMPILE_FLAGS + SRCS + SbusRc.cpp + SbusRc.hpp + MODULE_CONFIG + module.yaml + DEPENDS + rc + ) diff --git a/src/drivers/rc/sbus_rc/Kconfig b/src/drivers/rc/sbus_rc/Kconfig new file mode 100644 index 000000000000..d79e5745b59c --- /dev/null +++ b/src/drivers/rc/sbus_rc/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RC_SBUS_RC + bool "sbus_rc" + default n + ---help--- + Enable support for sbus_rc diff --git a/src/drivers/rc/sbus_rc/SbusRc.cpp b/src/drivers/rc/sbus_rc/SbusRc.cpp new file mode 100644 index 000000000000..12d57da141e1 --- /dev/null +++ b/src/drivers/rc/sbus_rc/SbusRc.cpp @@ -0,0 +1,315 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 "SbusRc.hpp" + +#include + +SbusRc::SbusRc(const char *device) : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(device)), + _cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")), + _publish_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": publish interval")) +{ + if (device) { + strncpy(_device, device, sizeof(_device) - 1); + _device[sizeof(_device) - 1] = '\0'; + } +} + +SbusRc::~SbusRc() +{ + perf_free(_cycle_perf); + perf_free(_publish_interval_perf); +} + +int SbusRc::task_spawn(int argc, char *argv[]) +{ + bool error_flag = false; + + int myoptind = 1; + int ch; + const char *myoptarg = nullptr; + const char *device_name = nullptr; + bool silent = false; + + while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'd': + device_name = myoptarg; + silent = false; + break; + + case '?': + error_flag = true; + break; + + default: + PX4_WARN("unrecognized flag"); + error_flag = true; + break; + } + } + + if (error_flag) { + return -1; + } + + if (device_name && (access(device_name, R_OK | W_OK) == 0)) { + SbusRc *instance = new SbusRc(device_name); + + if (instance == nullptr) { + PX4_ERR("alloc failed"); + return PX4_ERROR; + } + + _object.store(instance); + _task_id = task_id_is_work_queue; + + instance->ScheduleOnInterval(_current_update_interval); + + return PX4_OK; + + } else if (silent) { + return PX4_OK; + + } else { + if (device_name) { + PX4_ERR("invalid device (-d) %s", device_name); + + } else { + PX4_ERR("valid device required"); + } + } + + return PX4_ERROR; +} + +void SbusRc::Run() +{ + if (should_exit()) { + + close(_rcs_fd); + + exit_and_cleanup(); + return; + } + + perf_begin(_cycle_perf); + + // Check if parameters have changed + if (_parameter_update_sub.updated()) { + // clear update + parameter_update_s param_update; + _parameter_update_sub.copy(¶m_update); + + updateParams(); + } + + const hrt_abstime cycle_timestamp = hrt_absolute_time(); + + bool rc_updated = false; + + constexpr hrt_abstime rc_scan_max = 3_s; + + // read all available data from the serial RC input UART + uint8_t rcs_buf[SBUS_BUFFER_SIZE] {}; + int newBytes = ::read(_rcs_fd, &rcs_buf[0], SBUS_BUFFER_SIZE); + + if (newBytes > 0) { + _bytes_rx += newBytes; + } + + const bool rc_scan_locked = _rc_scan_locked; + + if (_rc_scan_begin == 0) { + _rc_scan_begin = cycle_timestamp; + + // Configure serial port + if (_rcs_fd < 0) { + _rcs_fd = open(_device, O_RDWR | O_NONBLOCK); + } + + sbus_config(_rcs_fd, board_rc_singlewire(_device)); + + // First check if the board provides a board-specific inversion method (e.g. via GPIO), + // and if not use an IOCTL + if (!board_rc_invert_input(_device, true)) { +#if defined(TIOCSINVERT) + ioctl(_rcs_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX); +#endif // TIOCSINVERT + } + + // flush serial buffer and any existing buffered data + tcflush(_rcs_fd, TCIOFLUSH); + + } else if (_rc_scan_locked + || cycle_timestamp - _rc_scan_begin < rc_scan_max) { + + if (newBytes > 0) { + uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {}; + uint16_t raw_rc_count = 0; + bool sbus_failsafe = false; + bool sbus_frame_drop = false; + unsigned sbus_frame_drops = 0; + + if (sbus_parse(cycle_timestamp, &rcs_buf[0], newBytes, &raw_rc_values[0], &raw_rc_count, + &sbus_failsafe, &sbus_frame_drop, &sbus_frame_drops, input_rc_s::RC_INPUT_MAX_CHANNELS) + ) { + // we have a new SBUS frame. Publish it. + input_rc_s input_rc{}; + input_rc.timestamp_last_signal = cycle_timestamp; + input_rc.channel_count = math::constrain(raw_rc_count, (uint16_t)0, (uint16_t)input_rc_s::RC_INPUT_MAX_CHANNELS); + input_rc.rssi = -1; + input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_SBUS; + + unsigned valid_chans = 0; + + for (unsigned i = 0; i < input_rc.channel_count; i++) { + input_rc.values[i] = raw_rc_values[i]; + + if (raw_rc_values[i] != UINT16_MAX) { + valid_chans++; + } + } + + input_rc.channel_count = valid_chans; + + if ((_param_rc_rssi_pwm_chan.get() > 0) && (_param_rc_rssi_pwm_chan.get() < input_rc.channel_count)) { + const int32_t rssi_pwm_chan = _param_rc_rssi_pwm_chan.get(); + const int32_t rssi_pwm_min = _param_rc_rssi_pwm_min.get(); + const int32_t rssi_pwm_max = _param_rc_rssi_pwm_max.get(); + + // get RSSI from input channel + int rc_rssi = ((input_rc.values[rssi_pwm_chan - 1] - rssi_pwm_min) * 100) / (rssi_pwm_max - rssi_pwm_min); + input_rc.rssi = math::constrain(rc_rssi, 0, 100); + } + + if (valid_chans == 0) { + input_rc.rssi = 0; + } + + input_rc.rc_failsafe = sbus_failsafe; + input_rc.rc_lost = (valid_chans == 0); + input_rc.rc_lost_frame_count = sbus_frame_drops; + + input_rc.link_quality = -1; + input_rc.rssi_dbm = NAN; + + input_rc.timestamp = hrt_absolute_time(); + _input_rc_pub.publish(input_rc); + perf_count(_publish_interval_perf); + + _timestamp_last_signal = cycle_timestamp; + rc_updated = true; + + if (valid_chans > 0) { + _rc_scan_locked = true; + } + } + } + + } else { + _rc_scan_begin = 0; + _rc_scan_locked = false; + + close(_rcs_fd); + _rcs_fd = -1; + } + + if (!rc_updated && (hrt_elapsed_time(&_timestamp_last_signal) > 1_s)) { + _rc_scan_locked = false; + } + + if (!rc_scan_locked && _rc_scan_locked) { + PX4_INFO("RC input locked"); + } + + perf_end(_cycle_perf); +} + +int SbusRc::custom_command(int argc, char *argv[]) +{ + if (!is_running()) { + int ret = SbusRc::task_spawn(argc, argv); + + if (ret) { + return ret; + } + } + + return print_usage("unknown command"); +} + +int SbusRc::print_status() +{ + PX4_INFO("Max update rate: %u Hz", 1000000 / _current_update_interval); + + if (_device[0] != '\0') { + PX4_INFO("UART device: %s", _device); + PX4_INFO("UART RX bytes: %" PRIu32, _bytes_rx); + } + + PX4_INFO("RC state: %s", _rc_scan_locked ? "found" : "searching for signal"); + + perf_print_counter(_cycle_perf); + perf_print_counter(_publish_interval_perf); + + return 0; +} + +int SbusRc::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +This module does SBUS RC input parsing. + +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("sbus_rc", "driver"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int sbus_rc_main(int argc, char *argv[]) +{ + return SbusRc::main(argc, argv); +} diff --git a/src/drivers/rc/sbus_rc/SbusRc.hpp b/src/drivers/rc/sbus_rc/SbusRc.hpp new file mode 100644 index 000000000000..c02d7e3f50a2 --- /dev/null +++ b/src/drivers/rc/sbus_rc/SbusRc.hpp @@ -0,0 +1,102 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace time_literals; + +class SbusRc : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + + SbusRc(const char *device); + virtual ~SbusRc(); + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + /** @see ModuleBase::print_status() */ + int print_status() override; + +private: + + void Run() override; + + hrt_abstime _rc_scan_begin{0}; + hrt_abstime _timestamp_last_signal{0}; + + bool _rc_scan_locked{false}; + + static constexpr unsigned _current_update_interval{4000}; // 250 Hz + + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + + uORB::PublicationMulti _input_rc_pub{ORB_ID(input_rc)}; + + int _rcs_fd{-1}; + char _device[20] {}; ///< device / serial port path + + perf_counter_t _cycle_perf; + perf_counter_t _publish_interval_perf; + uint32_t _bytes_rx{0}; + + DEFINE_PARAMETERS( + (ParamInt) _param_rc_rssi_pwm_chan, + (ParamInt) _param_rc_rssi_pwm_min, + (ParamInt) _param_rc_rssi_pwm_max + ) +}; diff --git a/src/drivers/rc/sbus_rc/module.yaml b/src/drivers/rc/sbus_rc/module.yaml new file mode 100644 index 000000000000..ed19fb7e4710 --- /dev/null +++ b/src/drivers/rc/sbus_rc/module.yaml @@ -0,0 +1,11 @@ +module_name: SBUS RC Input Driver +serial_config: + - command: "sbus_rc start -d ${SERIAL_DEV}" + port_config_param: + name: RC_SBUS_PRT_CFG + group: Serial + #default: RC + #depends_on_port: RC + description_extended: | + SBUS RC driver. + From 3a3f04c0f43c9f777b8257a0a5b37ce5e3c0ad48 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 17 Jul 2024 13:14:06 -0400 Subject: [PATCH 522/652] drivers/rc: new standalone ghst_rc driver - extracted from monolithic drivers/rc_input which will eventually be dropped once all drivers migrated and boards updated --- src/drivers/rc/ghst_rc/CMakeLists.txt | 45 ++++ src/drivers/rc/ghst_rc/GhstRc.cpp | 304 ++++++++++++++++++++++ src/drivers/rc/ghst_rc/GhstRc.hpp | 104 ++++++++ src/drivers/rc/ghst_rc/Kconfig | 5 + src/drivers/rc/ghst_rc/ghst_telemetry.cpp | 139 ++++++++++ src/drivers/rc/ghst_rc/ghst_telemetry.hpp | 91 +++++++ src/drivers/rc/ghst_rc/module.yaml | 22 ++ 7 files changed, 710 insertions(+) create mode 100644 src/drivers/rc/ghst_rc/CMakeLists.txt create mode 100644 src/drivers/rc/ghst_rc/GhstRc.cpp create mode 100644 src/drivers/rc/ghst_rc/GhstRc.hpp create mode 100644 src/drivers/rc/ghst_rc/Kconfig create mode 100644 src/drivers/rc/ghst_rc/ghst_telemetry.cpp create mode 100644 src/drivers/rc/ghst_rc/ghst_telemetry.hpp create mode 100644 src/drivers/rc/ghst_rc/module.yaml diff --git a/src/drivers/rc/ghst_rc/CMakeLists.txt b/src/drivers/rc/ghst_rc/CMakeLists.txt new file mode 100644 index 000000000000..2a0342584fd6 --- /dev/null +++ b/src/drivers/rc/ghst_rc/CMakeLists.txt @@ -0,0 +1,45 @@ +############################################################################ +# +# Copyright (c) 2015-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_module( + MODULE drivers__rc__ghst_rc + MAIN ghst_rc + COMPILE_FLAGS + SRCS + GhstRc.cpp + GhstRc.hpp + ghst_telemetry.cpp + MODULE_CONFIG + module.yaml + DEPENDS + rc + ) diff --git a/src/drivers/rc/ghst_rc/GhstRc.cpp b/src/drivers/rc/ghst_rc/GhstRc.cpp new file mode 100644 index 000000000000..1960c84ce6d4 --- /dev/null +++ b/src/drivers/rc/ghst_rc/GhstRc.cpp @@ -0,0 +1,304 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 "GhstRc.hpp" + +#include + +GhstRc::GhstRc(const char *device) : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(device)), + _cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")), + _publish_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": publish interval")) +{ + if (device) { + strncpy(_device, device, sizeof(_device) - 1); + _device[sizeof(_device) - 1] = '\0'; + } +} + +GhstRc::~GhstRc() +{ + delete _ghst_telemetry; + + perf_free(_cycle_perf); + perf_free(_publish_interval_perf); +} + +int GhstRc::task_spawn(int argc, char *argv[]) +{ + bool error_flag = false; + + int myoptind = 1; + int ch; + const char *myoptarg = nullptr; + const char *device_name = nullptr; + bool silent = false; + + while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'd': + device_name = myoptarg; + silent = false; + break; + + case '?': + error_flag = true; + break; + + default: + PX4_WARN("unrecognized flag"); + error_flag = true; + break; + } + } + + if (error_flag) { + return -1; + } + + if (device_name && (access(device_name, R_OK | W_OK) == 0)) { + GhstRc *instance = new GhstRc(device_name); + + if (instance == nullptr) { + PX4_ERR("alloc failed"); + return PX4_ERROR; + } + + _object.store(instance); + _task_id = task_id_is_work_queue; + + instance->ScheduleOnInterval(_current_update_interval); + + return PX4_OK; + + } else if (silent) { + return PX4_OK; + + } else { + if (device_name) { + PX4_ERR("invalid device (-d) %s", device_name); + + } else { + PX4_ERR("valid device required"); + } + } + + return PX4_ERROR; +} + +void GhstRc::Run() +{ + if (should_exit()) { + + close(_rcs_fd); + + exit_and_cleanup(); + return; + } + + perf_begin(_cycle_perf); + + // Check if parameters have changed + if (_parameter_update_sub.updated()) { + // clear update + parameter_update_s param_update; + _parameter_update_sub.copy(¶m_update); + + updateParams(); + } + + const hrt_abstime cycle_timestamp = hrt_absolute_time(); + + bool rc_updated = false; + + constexpr hrt_abstime rc_scan_max = 3_s; + + // read all available data from the serial RC input UART + static constexpr size_t RC_MAX_BUFFER_SIZE{64}; + uint8_t rcs_buf[RC_MAX_BUFFER_SIZE] {}; + int newBytes = ::read(_rcs_fd, &rcs_buf[0], RC_MAX_BUFFER_SIZE); + + if (newBytes > 0) { + _bytes_rx += newBytes; + } + + const bool rc_scan_locked = _rc_scan_locked; + + if (_rc_scan_begin == 0) { + _rc_scan_begin = cycle_timestamp; + + // Configure serial port + if (_rcs_fd < 0) { + _rcs_fd = open(_device, O_RDWR | O_NONBLOCK); + } + + ghst_config(_rcs_fd); + + // flush serial buffer and any existing buffered data + tcflush(_rcs_fd, TCIOFLUSH); + + } else if (_rc_scan_locked + || cycle_timestamp - _rc_scan_begin < rc_scan_max) { + + if (newBytes > 0) { + uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {}; + uint16_t raw_rc_count = 0; + int8_t ghst_rssi = -1; + + if (ghst_parse(cycle_timestamp, &rcs_buf[0], newBytes, &raw_rc_values[0], &ghst_rssi, + &raw_rc_count, input_rc_s::RC_INPUT_MAX_CHANNELS) + ) { + // we have a new GHST frame. Publish it. + input_rc_s input_rc{}; + input_rc.timestamp_last_signal = cycle_timestamp; + input_rc.channel_count = math::constrain(raw_rc_count, (uint16_t)0, (uint16_t)input_rc_s::RC_INPUT_MAX_CHANNELS); + input_rc.rssi = ghst_rssi; + input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_GHST; + + unsigned valid_chans = 0; + + for (unsigned i = 0; i < input_rc.channel_count; i++) { + input_rc.values[i] = raw_rc_values[i]; + + if (raw_rc_values[i] != UINT16_MAX) { + valid_chans++; + } + } + + input_rc.channel_count = valid_chans; + + if (valid_chans == 0) { + input_rc.rssi = 0; + } + + input_rc.rc_lost = (valid_chans == 0); + + input_rc.link_quality = -1; + input_rc.rssi_dbm = NAN; + + input_rc.timestamp = hrt_absolute_time(); + _input_rc_pub.publish(input_rc); + perf_count(_publish_interval_perf); + + _timestamp_last_signal = cycle_timestamp; + rc_updated = true; + + if (valid_chans > 0) { + _rc_scan_locked = true; + } + + if (!_rc_scan_locked && !_ghst_telemetry && _param_rc_ghst_tel_en.get()) { + _ghst_telemetry = new GHSTTelemetry(_rcs_fd); + } + + if (_ghst_telemetry) { + _ghst_telemetry->update(cycle_timestamp); + } + } + } + + } else { + _rc_scan_begin = 0; + _rc_scan_locked = false; + + close(_rcs_fd); + _rcs_fd = -1; + } + + if (!rc_updated && (hrt_elapsed_time(&_timestamp_last_signal) > 1_s)) { + _rc_scan_locked = false; + } + + if (!rc_scan_locked && _rc_scan_locked) { + PX4_INFO("RC input locked"); + } + + perf_end(_cycle_perf); +} + +int GhstRc::custom_command(int argc, char *argv[]) +{ + if (!is_running()) { + int ret = GhstRc::task_spawn(argc, argv); + + if (ret) { + return ret; + } + } + + return print_usage("unknown command"); +} + +int GhstRc::print_status() +{ + PX4_INFO("Max update rate: %u Hz", 1000000 / _current_update_interval); + + if (_device[0] != '\0') { + PX4_INFO("UART device: %s", _device); + PX4_INFO("UART RX bytes: %" PRIu32, _bytes_rx); + } + + PX4_INFO("RC state: %s", _rc_scan_locked ? "found" : "searching for signal"); + + perf_print_counter(_cycle_perf); + perf_print_counter(_publish_interval_perf); + + return 0; +} + +int GhstRc::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +This module does Ghost (GHST) RC input parsing. + +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("ghst_rc", "driver"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int ghst_rc_main(int argc, char *argv[]) +{ + return GhstRc::main(argc, argv); +} diff --git a/src/drivers/rc/ghst_rc/GhstRc.hpp b/src/drivers/rc/ghst_rc/GhstRc.hpp new file mode 100644 index 000000000000..0090b216dc21 --- /dev/null +++ b/src/drivers/rc/ghst_rc/GhstRc.hpp @@ -0,0 +1,104 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ghst_telemetry.hpp" + +using namespace time_literals; + +class GhstRc : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + + GhstRc(const char *device); + virtual ~GhstRc(); + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + /** @see ModuleBase::print_status() */ + int print_status() override; + +private: + + void Run() override; + + hrt_abstime _rc_scan_begin{0}; + hrt_abstime _timestamp_last_signal{0}; + + bool _rc_scan_locked{false}; + + static constexpr unsigned _current_update_interval{4000}; // 250 Hz + + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + + uORB::PublicationMulti _input_rc_pub{ORB_ID(input_rc)}; + + int _rcs_fd{-1}; + char _device[20] {}; ///< device / serial port path + + GHSTTelemetry *_ghst_telemetry{nullptr}; + + perf_counter_t _cycle_perf; + perf_counter_t _publish_interval_perf; + uint32_t _bytes_rx{0}; + + DEFINE_PARAMETERS( + (ParamBool) _param_rc_ghst_tel_en + ) +}; diff --git a/src/drivers/rc/ghst_rc/Kconfig b/src/drivers/rc/ghst_rc/Kconfig new file mode 100644 index 000000000000..fbff9b26d4d3 --- /dev/null +++ b/src/drivers/rc/ghst_rc/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RC_GHST_RC + bool "ghst_rc" + default n + ---help--- + Enable support for ghst_rc diff --git a/src/drivers/rc/ghst_rc/ghst_telemetry.cpp b/src/drivers/rc/ghst_rc/ghst_telemetry.cpp new file mode 100644 index 000000000000..47c1c21fa583 --- /dev/null +++ b/src/drivers/rc/ghst_rc/ghst_telemetry.cpp @@ -0,0 +1,139 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file ghst_telemetry.cpp + * + * IRC Ghost (Immersion RC Ghost) telemetry. + * + * @author Igor Misic + * @author Juraj Ciberlin + */ + +#include "ghst_telemetry.hpp" +#include + +using time_literals::operator ""_s; + +GHSTTelemetry::GHSTTelemetry(int uart_fd) : + _uart_fd(uart_fd) +{ +} + +bool GHSTTelemetry::update(const hrt_abstime &now) +{ + bool success = false; + + if ((now - _last_update) > (1_s / (UPDATE_RATE_HZ * NUM_DATA_TYPES))) { + + switch (_next_type) { + case 0U: + success = send_battery_status(); + break; + + case 1U: + success = send_gps1_status(); + break; + + case 2U: + success = send_gps2_status(); + break; + + default: + success = false; + break; + } + + _last_update = now; + _next_type = (_next_type + 1U) % NUM_DATA_TYPES; + } + + return success; +} + +bool GHSTTelemetry::send_battery_status() +{ + bool success = false; + float voltage_in_10mV; + float current_in_10mA; + float fuel_in_10mAh; + battery_status_s battery_status; + + if (_battery_status_sub.update(&battery_status)) { + voltage_in_10mV = battery_status.voltage_v * FACTOR_VOLTS_TO_10MV; + current_in_10mA = battery_status.current_a * FACTOR_AMPS_TO_10MA; + fuel_in_10mAh = battery_status.discharged_mah * FACTOR_MAH_TO_10MAH; + success = ghst_send_telemetry_battery_status(_uart_fd, + static_cast(voltage_in_10mV), + static_cast(current_in_10mA), + static_cast(fuel_in_10mAh)); + } + + return success; +} + +bool GHSTTelemetry::send_gps1_status() +{ + sensor_gps_s vehicle_gps_position; + + if (!_vehicle_gps_position_sub.update(&vehicle_gps_position)) { + return false; + } + + int32_t latitude = static_cast(round(vehicle_gps_position.latitude_deg * 1e7)); // 1e-7 degrees + int32_t longitude = static_cast(round(vehicle_gps_position.longitude_deg * 1e7)); // 1e-7 degrees + uint16_t altitude = static_cast(round(vehicle_gps_position.altitude_msl_m)); // meters + + return ghst_send_telemetry_gps1_status(_uart_fd, latitude, longitude, altitude); +} + +bool GHSTTelemetry::send_gps2_status() +{ + sensor_gps_s vehicle_gps_position; + + if (!_vehicle_gps_position_sub.update(&vehicle_gps_position)) { + return false; + } + + uint16_t ground_speed = (uint16_t)(vehicle_gps_position.vel_d_m_s / 3.6f * 10.f); + uint16_t ground_course = (uint16_t)(math::degrees(vehicle_gps_position.cog_rad) * 100.f); + uint8_t num_sats = vehicle_gps_position.satellites_used; + + // TBD: Can these be computed in a RC telemetry driver? + uint16_t home_dist = 0; + uint16_t home_dir = 0; + uint8_t flags = 0; + + return ghst_send_telemetry_gps2_status(_uart_fd, ground_speed, ground_course, num_sats, home_dist, home_dir, flags); +} + diff --git a/src/drivers/rc/ghst_rc/ghst_telemetry.hpp b/src/drivers/rc/ghst_rc/ghst_telemetry.hpp new file mode 100644 index 000000000000..faa61f69b28e --- /dev/null +++ b/src/drivers/rc/ghst_rc/ghst_telemetry.hpp @@ -0,0 +1,91 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file ghst_telemetry.cpp + * + * IRC Ghost (Immersion RC Ghost) telemetry. + * + * @author Igor Misic + * @author Juraj Ciberlin + */ + +#pragma once + +#include +#include +#include +#include + +/** + * High-level class that handles sending of GHST telemetry data + */ +class GHSTTelemetry +{ +public: + /** + * @param uart_fd file descriptor for the UART to use. It is expected to be configured + * already. + */ + explicit GHSTTelemetry(int uart_fd); + + ~GHSTTelemetry() = default; + + /** + * Send telemetry data. Call this regularly (i.e. at 100Hz), it will automatically + * limit the sending rate. + * @return true if new data sent + */ + bool update(const hrt_abstime &now); + +private: + bool send_battery_status(); + bool send_gps1_status(); + bool send_gps2_status(); + + uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; + uORB::Subscription _battery_status_sub{ORB_ID(battery_status)}; + + int _uart_fd; + hrt_abstime _last_update {0U}; + uint32_t _next_type {0U}; + + static constexpr uint32_t NUM_DATA_TYPES {3U}; // number of different telemetry data types + static constexpr uint32_t UPDATE_RATE_HZ {10U}; // update rate [Hz] + + // Factors that should be applied to get correct values + static constexpr float FACTOR_VOLTS_TO_10MV {100.0F}; + static constexpr float FACTOR_AMPS_TO_10MA {100.0F}; + static constexpr float FACTOR_MAH_TO_10MAH {0.1F}; + +}; diff --git a/src/drivers/rc/ghst_rc/module.yaml b/src/drivers/rc/ghst_rc/module.yaml new file mode 100644 index 000000000000..2e15a42d97a3 --- /dev/null +++ b/src/drivers/rc/ghst_rc/module.yaml @@ -0,0 +1,22 @@ +module_name: GHST RC Input Driver +serial_config: + - command: "ghst_rc start -d ${SERIAL_DEV}" + port_config_param: + name: RC_GHST_PRT_CFG + group: Serial + #default: RC + #depends_on_port: RC + description_extended: | + Ghost (GHST) RC driver. + +parameters: + - group: RC + definitions: + RC_GHST_TEL_EN: + description: + short: Ghost RC telemetry enable + long: | + Ghost telemetry enable + + type: boolean + default: [0] From 85de0ff227d75af95b8f73187b29ae930660d446 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 17 Jul 2024 13:48:30 -0400 Subject: [PATCH 523/652] boards: move ARK fmu-v6x/pi6x to dedicated RC drivers --- boards/ark/fmu-v6x/default.px4board | 3 ++- boards/ark/pi6x/default.px4board | 2 +- src/drivers/rc/Kconfig | 3 +++ src/drivers/rc/sbus_rc/module.yaml | 2 +- 4 files changed, 7 insertions(+), 3 deletions(-) diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index b75d468cfc03..92bf7cb23895 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_BATT_SMBUS=y @@ -31,7 +32,7 @@ CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y -CONFIG_DRIVERS_RC_INPUT=y +CONFIG_COMMON_RC=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_UAVCAN=y diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 8646ea006e29..84c6fd79f2b2 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -21,7 +21,7 @@ CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_PWM_OUT=y -CONFIG_DRIVERS_RC_INPUT=y +CONFIG_COMMON_RC=y CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_UAVCAN=y CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 diff --git a/src/drivers/rc/Kconfig b/src/drivers/rc/Kconfig index f4b771e2ba19..7a53a650f432 100644 --- a/src/drivers/rc/Kconfig +++ b/src/drivers/rc/Kconfig @@ -3,6 +3,9 @@ menu "RC" bool "Common RC" default n select DRIVERS_RC_CRSF_RC + select DRIVERS_RC_DSM_RC + select DRIVERS_RC_GHST_RC + select DRIVERS_RC_SBUS_RC ---help--- Enable default set of magnetometer drivers rsource "*/Kconfig" diff --git a/src/drivers/rc/sbus_rc/module.yaml b/src/drivers/rc/sbus_rc/module.yaml index ed19fb7e4710..778f419063e4 100644 --- a/src/drivers/rc/sbus_rc/module.yaml +++ b/src/drivers/rc/sbus_rc/module.yaml @@ -4,7 +4,7 @@ serial_config: port_config_param: name: RC_SBUS_PRT_CFG group: Serial - #default: RC + default: RC #depends_on_port: RC description_extended: | SBUS RC driver. From b46b2cdf546d7548ef00c61499c6a9f9e67a9798 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Fri, 19 Jul 2024 13:43:29 -0600 Subject: [PATCH 524/652] airframes: droneblocks dexi 5 default to CRSF on RC input with telemetry --- ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 index d7f985d1d03e..d599af5b3868 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 @@ -68,6 +68,9 @@ param set-default MPC_THR_MIN 0.025 param set-default MPC_VEL_MANUAL 5.0 param set-default MPC_XY_VEL_MAX 8.0 +param set-default RC_CRSF_PRT_CFG 300 +param set-default RC_CRSF_TEL_EN 1 + param set-default RTL_RETURN_ALT 15 param set-default SENS_FLOW_MINHGT 0.0 From 9ff6c4bf288a97662eab84fd5955faed0d5a26fc Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 19 Jul 2024 18:25:43 -0400 Subject: [PATCH 525/652] remove newlines --- src/drivers/rc/dsm_rc/module.yaml | 1 - src/drivers/rc/ghst_rc/ghst_telemetry.cpp | 1 - src/drivers/rc/sbus_rc/module.yaml | 1 - 3 files changed, 3 deletions(-) diff --git a/src/drivers/rc/dsm_rc/module.yaml b/src/drivers/rc/dsm_rc/module.yaml index 4117b4eb76de..12f36bc77a8e 100644 --- a/src/drivers/rc/dsm_rc/module.yaml +++ b/src/drivers/rc/dsm_rc/module.yaml @@ -8,4 +8,3 @@ serial_config: #depends_on_port: RC description_extended: | DSM RC (Spektrum) driver. - diff --git a/src/drivers/rc/ghst_rc/ghst_telemetry.cpp b/src/drivers/rc/ghst_rc/ghst_telemetry.cpp index 47c1c21fa583..9a910063931a 100644 --- a/src/drivers/rc/ghst_rc/ghst_telemetry.cpp +++ b/src/drivers/rc/ghst_rc/ghst_telemetry.cpp @@ -136,4 +136,3 @@ bool GHSTTelemetry::send_gps2_status() return ghst_send_telemetry_gps2_status(_uart_fd, ground_speed, ground_course, num_sats, home_dist, home_dir, flags); } - diff --git a/src/drivers/rc/sbus_rc/module.yaml b/src/drivers/rc/sbus_rc/module.yaml index 778f419063e4..bc8a0ee14078 100644 --- a/src/drivers/rc/sbus_rc/module.yaml +++ b/src/drivers/rc/sbus_rc/module.yaml @@ -8,4 +8,3 @@ serial_config: #depends_on_port: RC description_extended: | SBUS RC driver. - From 36d89df0a722e2fca3f23e4d0ddd9da9fb5b7ecc Mon Sep 17 00:00:00 2001 From: Stockton Slack Date: Mon, 8 Jul 2024 12:32:22 -0600 Subject: [PATCH 526/652] Fix load monitoring inconsistency bug --- src/modules/load_mon/LoadMon.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/load_mon/LoadMon.cpp b/src/modules/load_mon/LoadMon.cpp index aa400391dc52..937d02c03e12 100644 --- a/src/modules/load_mon/LoadMon.cpp +++ b/src/modules/load_mon/LoadMon.cpp @@ -202,7 +202,7 @@ void LoadMon::cpuload() } } - fseek(_proc_fd, 0, SEEK_END); + fseek(_proc_fd, 0, SEEK_SET); if (parsedCount == 5) { int32_t kb_main_cached = kb_page_cache + kb_slab_reclaimable; From 39abd87949f1df59a14b00ebe5cd13328852cb09 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Wed, 24 Jul 2024 11:24:07 +0200 Subject: [PATCH 527/652] set best sensor to -1 after last sensor fails (#23425) --- src/modules/sensors/data_validator/DataValidatorGroup.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/modules/sensors/data_validator/DataValidatorGroup.cpp b/src/modules/sensors/data_validator/DataValidatorGroup.cpp index a7ded78d26cb..eabf61788ca4 100644 --- a/src/modules/sensors/data_validator/DataValidatorGroup.cpp +++ b/src/modules/sensors/data_validator/DataValidatorGroup.cpp @@ -230,6 +230,10 @@ float *DataValidatorGroup::get_best(uint64_t timestamp, int *index) if (_first_failover_time == 0) { _first_failover_time = timestamp; } + + if (max_confidence < FLT_EPSILON) { + max_index = -1; + } } } From 79e0e00d8c1c581a60630fbd244336beed9f2e41 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 24 Jul 2024 15:09:17 +0200 Subject: [PATCH 528/652] ekf2: block process noise increment without constraining the variance The wind variance can be reset to a value larger than the wind init variance (e.g.: when the reset occurs when flying close to the N or E axis). Constraining the variance after a covariance initialization would artificially increase the correlation and could destabilize the filter. --- src/modules/ekf2/EKF/covariance.cpp | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 28decbc0d1d1..520b7855443c 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -201,14 +201,15 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_WIND) // wind vel: add process noise - if (!_external_wind_init) { - float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) - * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); - float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt; - - for (unsigned index = 0; index < State::wind_vel.dof; index++) { - const unsigned i = State::wind_vel.idx + index; - P(i, i) = fminf(P(i, i) + wind_vel_process_noise, sq(_params.initial_wind_uncertainty)); + float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) + * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); + float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt; + + for (unsigned index = 0; index < State::wind_vel.dof; index++) { + const unsigned i = State::wind_vel.idx + index; + + if (P(i, i) < sq(_params.initial_wind_uncertainty)) { + P(i, i) += wind_vel_process_noise; } } From 46e43ec7252632ed151ffecd4f3c37f854698cc6 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 26 Jul 2023 18:55:38 +0200 Subject: [PATCH 529/652] Decouple filepaths from rcS/MTD --- Kconfig | 12 +++++ ROMFS/CMakeLists.txt | 5 ++ ROMFS/cannode/init.d/rcS | 17 ++----- ROMFS/px4fmu_common/init.d/rcS | 10 +--- Tools/filepaths/generate_config.py | 61 +++++++++++++++++++++++++ Tools/filepaths/rc.filepaths.jinja | 6 +++ boards/nxp/mr-canhubk3/default.px4board | 1 + boards/nxp/ucans32k146/default.px4board | 1 + boards/px4/sitl/default.px4board | 1 + boards/px4/sitl/zenoh.px4board | 1 - src/modules/logger/logger.h | 4 +- src/modules/zenoh/zenoh_config.cpp | 6 +-- src/modules/zenoh/zenoh_config.hpp | 8 ++-- 13 files changed, 101 insertions(+), 32 deletions(-) create mode 100755 Tools/filepaths/generate_config.py create mode 100644 Tools/filepaths/rc.filepaths.jinja diff --git a/Kconfig b/Kconfig index 6427534f91f8..5f4fb16435b0 100644 --- a/Kconfig +++ b/Kconfig @@ -185,6 +185,18 @@ menu "Serial ports" string "EXT2 tty port" endmenu +menu "File paths" + + config BOARD_ROOT_PATH + string "PX4 Root file path" + depends on MODULES_LOGGER + default "/fs/microsd" + + config BOARD_PARAM_FILE + string "Parameter file" + default "/fs/mtd_params" +endmenu + menu "drivers" source "src/drivers/Kconfig" endmenu diff --git a/ROMFS/CMakeLists.txt b/ROMFS/CMakeLists.txt index 532b659b05e0..a520a4d377d1 100644 --- a/ROMFS/CMakeLists.txt +++ b/ROMFS/CMakeLists.txt @@ -120,6 +120,7 @@ add_custom_command( ${romfs_gen_root_dir}/init.d/rc.serial ${romfs_gen_root_dir}/init.d/rc.autostart ${romfs_gen_root_dir}/init.d/rc.autostart.post + ${romfs_gen_root_dir}/init.d/rc.filepaths ${romfs_copy_stamp} COMMAND ${CMAKE_COMMAND} -E remove_directory ${romfs_gen_root_dir}/* COMMAND ${CMAKE_COMMAND} -E tar xf ${romfs_tar_file} @@ -131,6 +132,9 @@ add_custom_command( --rc-dir ${romfs_gen_root_dir}/init.d --serial-ports ${board_serial_ports} ${added_arguments} --config-files ${module_config_files} #--verbose + COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/filepaths/generate_config.py + --rc-dir ${romfs_gen_root_dir}/init.d + --params-file ${CONFIG_BOARD_PARAM_FILE} COMMAND ${CMAKE_COMMAND} -E touch ${romfs_copy_stamp} WORKING_DIRECTORY ${romfs_gen_root_dir} DEPENDS ${romfs_tar_file} @@ -320,6 +324,7 @@ add_custom_target(romfs_gen_files_target DEPENDS ${romfs_copy_stamp} ${romfs_gen_root_dir}/init.d/rc.serial + ${romfs_gen_root_dir}/init.d/rc.filepaths romfs_extras.stamp ) diff --git a/ROMFS/cannode/init.d/rcS b/ROMFS/cannode/init.d/rcS index 0d9da3a10afc..96edd27ead1b 100644 --- a/ROMFS/cannode/init.d/rcS +++ b/ROMFS/cannode/init.d/rcS @@ -21,25 +21,14 @@ set R / # ver all -if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params -then - set PARAM_FILE /fs/mtd_params -fi - -if mft query -q -k MTD -s MTD_PARAMETERS -v /dev/eeeprom0 -then - set PARAM_FILE /dev/eeeprom0 -fi - -if mft query -q -k MTD -s MTD_PARAMETERS -v /mnt/qspi/params -then - set PARAM_FILE /mnt/qspi/params -fi +# Load param file location from kconfig +. ${R}etc/init.d/rc.filepaths # # Load parameters. # param select $PARAM_FILE + if ! param load then param reset_all diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 0849dbd6cd6a..39eed1bcab4d 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -120,14 +120,8 @@ then . $FRC else - # - # Set the parameter file the board supports params on - # MTD device. - # - if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params - then - set PARAM_FILE /fs/mtd_params - fi + # Load param file location from kconfig + . ${R}etc/init.d/rc.filepaths # Check if /fs/mtd_params is a valid BSON file if ! bsondump docsize /fs/mtd_caldata diff --git a/Tools/filepaths/generate_config.py b/Tools/filepaths/generate_config.py new file mode 100755 index 000000000000..d4aa8b6d2625 --- /dev/null +++ b/Tools/filepaths/generate_config.py @@ -0,0 +1,61 @@ +#!/usr/bin/env python3 +""" Script to generate Serial rc.filepaths for the ROMFS startup script """ + +import argparse +import os +import sys + +try: + from jinja2 import Environment, FileSystemLoader +except ImportError as e: + print("Failed to import jinja2: " + str(e)) + print("") + print("You may need to install it using:") + print(" pip3 install --user jinja2") + print("") + sys.exit(1) + +try: + import yaml +except ImportError as e: + print("Failed to import yaml: " + str(e)) + print("") + print("You may need to install it using:") + print(" pip3 install --user pyyaml") + print("") + sys.exit(1) + +parser = argparse.ArgumentParser(description='Generate PX4 ROMFS filepaths') + +parser.add_argument('--config-files', type=str, nargs='*', default=[], + help='YAML module config file(s)') +parser.add_argument('--constrained-flash', action='store_true', + help='Reduce verbosity in ROMFS scripts to reduce flash size') +parser.add_argument('--rc-dir', type=str, action='store', + help='ROMFS output directory', default=None) +parser.add_argument('--params-file', type=str, action='store', + help='Parameter output file', default=None) +parser.add_argument('-v', '--verbose', dest='verbose', action='store_true', + help='Verbose Output') + +args = parser.parse_args() + +verbose = args.verbose +constrained_flash = args.constrained_flash +rc_filepaths_output_dir = args.rc_dir +rc_filepaths_template = 'rc.filepaths.jinja' + + +jinja_env = Environment(loader=FileSystemLoader( + os.path.dirname(os.path.realpath(__file__)))) + +# generate the ROMFS script using a jinja template +if rc_filepaths_output_dir is not None: + rc_filepath_output_file = os.path.join(rc_filepaths_output_dir, "rc.filepaths") + + if verbose: print("Generating {:}".format(rc_filepath_output_file)) + template = jinja_env.get_template(rc_filepaths_template) + with open(rc_filepath_output_file, 'w') as fid: + fid.write(template.render(constrained_flash=constrained_flash, params_file=args.params_file)) +else: + raise Exception("--rc-dir needs to be specified") diff --git a/Tools/filepaths/rc.filepaths.jinja b/Tools/filepaths/rc.filepaths.jinja new file mode 100644 index 000000000000..30a2c2cce643 --- /dev/null +++ b/Tools/filepaths/rc.filepaths.jinja @@ -0,0 +1,6 @@ +{# jinja template to generate the serial autostart script. #} + +# serial autostart script generated with generate_serial_config.py + + +set PARAM_FILE {{ params_file }} diff --git a/boards/nxp/mr-canhubk3/default.px4board b/boards/nxp/mr-canhubk3/default.px4board index 277c62de7889..4f551cbec644 100644 --- a/boards/nxp/mr-canhubk3/default.px4board +++ b/boards/nxp/mr-canhubk3/default.px4board @@ -2,6 +2,7 @@ CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" CONFIG_BOARD_ARCHITECTURE="cortex-m7" CONFIG_BOARD_ROMFSROOT="cannode" CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_PARAM_FILE="/mnt/qspi/params" CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y diff --git a/boards/nxp/ucans32k146/default.px4board b/boards/nxp/ucans32k146/default.px4board index f9530438758b..45430b9c51b9 100644 --- a/boards/nxp/ucans32k146/default.px4board +++ b/boards/nxp/ucans32k146/default.px4board @@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m4" CONFIG_BOARD_ROMFSROOT="cannode" CONFIG_BOARD_CONSTRAINED_MEMORY=y CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" +CONFIG_BOARD_PARAM_FILE="/dev/eeeprom0" CONFIG_DRIVERS_BOOTLOADERS=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_GPS=y diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index cfbaf4ddc998..d46a7cc7e70f 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -1,6 +1,7 @@ CONFIG_PLATFORM_POSIX=y CONFIG_BOARD_TESTING=y CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_ROOT_PATH="./" CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_OSD_MSP_OSD=y diff --git a/boards/px4/sitl/zenoh.px4board b/boards/px4/sitl/zenoh.px4board index 58a29ad52fd8..20ff39d1b00e 100644 --- a/boards/px4/sitl/zenoh.px4board +++ b/boards/px4/sitl/zenoh.px4board @@ -1,3 +1,2 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=n CONFIG_MODULES_ZENOH=y -CONFIG_ZENOH_CONFIG_PATH="./zenoh" diff --git a/src/modules/logger/logger.h b/src/modules/logger/logger.h index 9b468010997f..44499c71b503 100644 --- a/src/modules/logger/logger.h +++ b/src/modules/logger/logger.h @@ -158,8 +158,8 @@ class Logger : public ModuleBase, public ModuleParams static constexpr int MAX_MISSION_TOPICS_NUM = 5; /**< Maximum number of mission topics */ static constexpr unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */ static constexpr const char *LOG_ROOT[(int)LogType::Count] = { - PX4_STORAGEDIR "/log", - PX4_STORAGEDIR "/mission_log" + CONFIG_BOARD_ROOT_PATH "/log", + CONFIG_BOARD_ROOT_PATH "/mission_log" }; struct LogFileName { diff --git a/src/modules/zenoh/zenoh_config.cpp b/src/modules/zenoh/zenoh_config.cpp index 8069956585cb..83f81fb31bbe 100644 --- a/src/modules/zenoh/zenoh_config.cpp +++ b/src/modules/zenoh/zenoh_config.cpp @@ -58,7 +58,7 @@ const char *default_sub_config = ""; //TODO maybe use YAML Zenoh_Config::Zenoh_Config() { bool correct_config = true; - DIR *dir = opendir(ZENOH_SD_ROOT_PATH); + DIR *dir = opendir(ZENOH_ROOT_PATH); fp_mapping = NULL; if (dir) { @@ -342,14 +342,14 @@ void Zenoh_Config::generate_clean_config() printf("Generate clean\n"); FILE *fp; - DIR *dir = opendir(ZENOH_SD_ROOT_PATH); + DIR *dir = opendir(ZENOH_ROOT_PATH); if (dir) { printf("Zenoh directory exists\n"); } else { /* Create zenoh dir. */ - if (mkdir(ZENOH_SD_ROOT_PATH, 0700) < 0) { + if (mkdir(ZENOH_ROOT_PATH, 0700) < 0) { printf("Failed to create Zenoh directory\n"); return; } diff --git a/src/modules/zenoh/zenoh_config.hpp b/src/modules/zenoh/zenoh_config.hpp index 72ae22d391d1..68a1f7121fb4 100644 --- a/src/modules/zenoh/zenoh_config.hpp +++ b/src/modules/zenoh/zenoh_config.hpp @@ -49,10 +49,10 @@ #include #define ZENOH_MAX_PATH_LENGTH (128 + 40) -#define ZENOH_SD_ROOT_PATH CONFIG_ZENOH_CONFIG_PATH -#define ZENOH_PUB_CONFIG_PATH ZENOH_SD_ROOT_PATH"/pub.csv" -#define ZENOH_SUB_CONFIG_PATH ZENOH_SD_ROOT_PATH"/sub.csv" -#define ZENOH_NET_CONFIG_PATH ZENOH_SD_ROOT_PATH"/net.txt" +#define ZENOH_ROOT_PATH CONFIG_BOARD_ROOT_PATH"/zenoh" +#define ZENOH_PUB_CONFIG_PATH ZENOH_ROOT_PATH"/pub.csv" +#define ZENOH_SUB_CONFIG_PATH ZENOH_ROOT_PATH"/sub.csv" +#define ZENOH_NET_CONFIG_PATH ZENOH_ROOT_PATH"/net.txt" #define NET_MODE_SIZE sizeof("client") #define NET_LOCATOR_SIZE 64 From a99cc0a20b1b29696d16b6a3157f03ee863fd999 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 10 Apr 2024 14:47:05 +0200 Subject: [PATCH 530/652] Remove unused kconfig symbol --- src/modules/zenoh/Kconfig | 6 ------ 1 file changed, 6 deletions(-) diff --git a/src/modules/zenoh/Kconfig b/src/modules/zenoh/Kconfig index 904c03e2891d..c3c042df1317 100644 --- a/src/modules/zenoh/Kconfig +++ b/src/modules/zenoh/Kconfig @@ -6,12 +6,6 @@ menuconfig MODULES_ZENOH Enable support for Zenoh if MODULES_ZENOH - config ZENOH_CONFIG_PATH - string "Config path" - default "/fs/microsd/zenoh" - help - Path to store network, publishers and subscribers configuration - config ZENOH_DEBUG int "Zenoh debug level" default 0 From 3fa9cda505c388b1d04fad0eb255673c5ed44109 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 11 Apr 2024 03:29:52 -0700 Subject: [PATCH 531/652] platforms/common:Use CONFIG_BOARD_ROOT_PATH instead of string constant --- platforms/common/include/px4_platform_common/board_common.h | 2 +- platforms/common/include/px4_platform_common/defines.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/platforms/common/include/px4_platform_common/board_common.h b/platforms/common/include/px4_platform_common/board_common.h index 970c47ec9e08..4dff12c1b24f 100644 --- a/platforms/common/include/px4_platform_common/board_common.h +++ b/platforms/common/include/px4_platform_common/board_common.h @@ -239,7 +239,7 @@ # else /* Use PX4IO FW search paths defaults based on version */ # if BOARD_USES_PX4IO_VERSION == 2 -# define PX4IO_FW_SEARCH_PATHS {"/etc/extras/px4_io-v2_default.bin","/fs/microsd/px4_io-v2_default.bin", "/fs/microsd/px4io2.bin", nullptr } +# define PX4IO_FW_SEARCH_PATHS {"/etc/extras/px4_io-v2_default.bin",CONFIG_BOARD_ROOT_PATH "/px4_io-v2_default.bin", CONFIG_BOARD_ROOT_PATH "/px4io2.bin", nullptr } # endif # endif #endif diff --git a/platforms/common/include/px4_platform_common/defines.h b/platforms/common/include/px4_platform_common/defines.h index 38d7b4201f4c..3b420f95f10f 100644 --- a/platforms/common/include/px4_platform_common/defines.h +++ b/platforms/common/include/px4_platform_common/defines.h @@ -64,7 +64,7 @@ static inline constexpr bool PX4_ISFINITE(double x) { return __builtin_isfinite( ****************************************************************************/ #define PX4_ROOTFSDIR "" -#define PX4_STORAGEDIR PX4_ROOTFSDIR "/fs/microsd" +#define PX4_STORAGEDIR PX4_ROOTFSDIR CONFIG_BOARD_ROOT_PATH #define _PX4_IOC(x,y) _IOC(x,y) // mode for open with O_CREAT From d0d9aaa6e96fa385e3f11e27a5ebfaa2c0021229 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 11 Apr 2024 03:30:21 -0700 Subject: [PATCH 532/652] drivers:Use CONFIG_BOARD_ROOT_PATH instead of string constant --- src/drivers/tap_esc/tap_esc_uploader.h | 2 +- src/drivers/uavcan/uavcan_module.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/tap_esc/tap_esc_uploader.h b/src/drivers/tap_esc/tap_esc_uploader.h index 1f1a0964bf36..abfd5ee65224 100644 --- a/src/drivers/tap_esc/tap_esc_uploader.h +++ b/src/drivers/tap_esc/tap_esc_uploader.h @@ -44,7 +44,7 @@ #include #include -#define TAP_ESC_FW_SEARCH_PATHS {"/etc/extras/tap_esc.bin", "/fs/microsd/tap_esc.bin", nullptr } +#define TAP_ESC_FW_SEARCH_PATHS {"/etc/extras/tap_esc.bin", CONFIG_BOARD_ROOT_PATH "/tap_esc.bin", nullptr } #define PROTO_SUPPORT_BL_REV 5 /**< supported bootloader protocol revision */ #define SYNC_RETRY_TIMES 5 /**< (uint8) esc sync failed allow retry times*/ #define UPLOADER_RETRY_TIMES 2 /**< esc uploader failed allow retry times*/ diff --git a/src/drivers/uavcan/uavcan_module.hpp b/src/drivers/uavcan/uavcan_module.hpp index 08d6bd5e987a..bd055cda9be7 100644 --- a/src/drivers/uavcan/uavcan_module.hpp +++ b/src/drivers/uavcan/uavcan_module.hpp @@ -49,7 +49,7 @@ // firmware paths #define UAVCAN_MAX_PATH_LENGTH (128 + 40) -#define UAVCAN_SD_ROOT_PATH "/fs/microsd/" +#define UAVCAN_SD_ROOT_PATH CONFIG_BOARD_ROOT_PATH "/" #define UAVCAN_FIRMWARE_PATH UAVCAN_SD_ROOT_PATH"ufw" #define UAVCAN_ROMFS_FW_PATH "/etc/uavcan/fw" #define UAVCAN_ROMFS_FW_PREFIX "_" From ea92c7ffccb0ca20ff7582b9f57fb6abe35e454a Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 11 Apr 2024 03:30:57 -0700 Subject: [PATCH 533/652] lib:Use CONFIG_BOARD_ROOT_PATH instead of string constant --- src/lib/rc/rc_tests/RCTest.cpp | 2 +- src/lib/systemlib/hardfault_log.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/rc/rc_tests/RCTest.cpp b/src/lib/rc/rc_tests/RCTest.cpp index a0f985cfe441..1997c19e85a3 100644 --- a/src/lib/rc/rc_tests/RCTest.cpp +++ b/src/lib/rc/rc_tests/RCTest.cpp @@ -19,7 +19,7 @@ #if defined(CONFIG_ARCH_BOARD_PX4_SITL) #define TEST_DATA_PATH "./test_data/" #else -#define TEST_DATA_PATH "/fs/microsd" +#define TEST_DATA_PATH CONFIG_BOARD_ROOT_PATH #endif extern "C" __EXPORT int rc_tests_main(int argc, char *argv[]); diff --git a/src/lib/systemlib/hardfault_log.h b/src/lib/systemlib/hardfault_log.h index 48340e295db9..678a0398f3ed 100644 --- a/src/lib/systemlib/hardfault_log.h +++ b/src/lib/systemlib/hardfault_log.h @@ -213,7 +213,7 @@ typedef struct ssarc_s dump_s; * Specifier to the xxxx_NUM definei.e %Y is YYYY so add 2 and %s is -2 * Also xxxxTIME_FMT need to match in size. See CCASERT in hardfault_log.c */ -#define LOG_PATH_BASE "/fs/microsd/" +#define LOG_PATH_BASE CONFIG_BOARD_ROOT_PATH "/" #define LOG_PATH_BASE_LEN ((arraySize(LOG_PATH_BASE))-1) #define LOG_NAME_FMT "fault_%s.log" From 54b20f1ff35e019babf2c3f7799ad604a89e33ba Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 11 Apr 2024 03:31:31 -0700 Subject: [PATCH 534/652] mavlink:Use CONFIG_BOARD_ROOT_PATH instead of string constant --- src/modules/mavlink/mavlink_ftp.cpp | 2 +- src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index a376392c00fd..058e9d95f1b3 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -1160,7 +1160,7 @@ bool MavlinkFTP::_validatePathIsWritable(const char *path) // Don't allow writes to system paths as they are in RAM // Ideally we'd canonicalize the path (with 'realpath'), but it might not exist, so realpath() would fail. // The next simpler thing is to check there's no reference to a parent dir. - if (strncmp(path, "/fs/microsd/", 12) != 0 || strstr(path, "/../") != nullptr) { + if (strncmp(path, CONFIG_BOARD_ROOT_PATH "/", 12) != 0 || strstr(path, "/../") != nullptr) { PX4_ERR("Disallowing write to %s", path); return false; } diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp index 288023a6508d..2accd21c5411 100644 --- a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp +++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp @@ -43,7 +43,7 @@ #include "../mavlink_ftp.h" #ifdef __PX4_NUTTX -#define PX4_MAVLINK_TEST_DATA_DIR "/fs/microsd/ftp_unit_test_data" +#define PX4_MAVLINK_TEST_DATA_DIR CONFIG_BOARD_ROOT_PATH "/ftp_unit_test_data" #else #define PX4_MAVLINK_TEST_DATA_DIR "ftp_unit_test_data" #endif From ab82c24e3e26ee6345f98404222940511612dd65 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 11 Apr 2024 03:32:01 -0700 Subject: [PATCH 535/652] systemcmds:Use CONFIG_BOARD_ROOT_PATH instead of string constant --- src/systemcmds/hardfault_log/hardfault_log.c | 2 +- src/systemcmds/netman/netman.cpp | 2 +- src/systemcmds/tests/test_mount.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/systemcmds/hardfault_log/hardfault_log.c b/src/systemcmds/hardfault_log/hardfault_log.c index f8ff269ec6b8..bad376b25edc 100644 --- a/src/systemcmds/hardfault_log/hardfault_log.c +++ b/src/systemcmds/hardfault_log/hardfault_log.c @@ -1289,7 +1289,7 @@ static void print_usage(void) "Hardfault type: 0=divide by 0, 1=Assertion, 2=jump to 0x0, 3=write to 0x0 (default=0)", true); PRINT_MODULE_USAGE_COMMAND_DESCR("commit", - "Write uncommitted hardfault to /fs/microsd/fault_%i.txt (and rearm, but don't reset)"); + "Write uncommitted hardfault to " CONFIG_BOARD_ROOT_PATH "/fault_%i.txt (and rearm, but don't reset)"); PRINT_MODULE_USAGE_COMMAND_DESCR("count", "Read the reboot counter, counts the number of reboots of an uncommitted hardfault (returned as the exit code of the program)"); PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reset the reboot counter"); diff --git a/src/systemcmds/netman/netman.cpp b/src/systemcmds/netman/netman.cpp index b9e653bdfeb1..a7014c62de28 100644 --- a/src/systemcmds/netman/netman.cpp +++ b/src/systemcmds/netman/netman.cpp @@ -51,7 +51,7 @@ #include #include -constexpr char DEFAULT_NETMAN_CONFIG[] = "/fs/microsd/net.cfg"; +constexpr char DEFAULT_NETMAN_CONFIG[] = CONFIG_BOARD_ROOT_PATH "/net.cfg"; #if defined(CONFIG_NETINIT_DHCPC) # define DEFAULT_PROTO IPv4PROTO_FALLBACK # define DEFAULT_IP CONFIG_NETMAN_FALLBACK_IPADDR diff --git a/src/systemcmds/tests/test_mount.cpp b/src/systemcmds/tests/test_mount.cpp index d7675714de8b..2d7bb895a436 100644 --- a/src/systemcmds/tests/test_mount.cpp +++ b/src/systemcmds/tests/test_mount.cpp @@ -62,7 +62,7 @@ int test_mount(int argc, char *argv[]) const unsigned iterations = 2000; const unsigned alignments = 10; - const char *cmd_filename = "/fs/microsd/mount_test_cmds.txt"; + const char *cmd_filename = CONFIG_BOARD_ROOT_PATH "/mount_test_cmds.txt"; /* check if microSD card is mounted */ From b38305dd21fd1f3584e1de4dbbffecff34415b9a Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 11 Apr 2024 03:36:59 -0700 Subject: [PATCH 536/652] CONFIG_BOARD_ROOT_PATH is not dependant on Logger only --- Kconfig | 1 - 1 file changed, 1 deletion(-) diff --git a/Kconfig b/Kconfig index 5f4fb16435b0..f9f2e5e8ec44 100644 --- a/Kconfig +++ b/Kconfig @@ -189,7 +189,6 @@ menu "File paths" config BOARD_ROOT_PATH string "PX4 Root file path" - depends on MODULES_LOGGER default "/fs/microsd" config BOARD_PARAM_FILE From af36c0b6ecc7b35519e2b1455c6ebe19173a37e4 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 12 Apr 2024 09:44:25 +0200 Subject: [PATCH 537/652] mr_canhubk3: generate mtd_net when file is missing --- boards/nxp/mr-canhubk3/init/rc.board_defaults | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/boards/nxp/mr-canhubk3/init/rc.board_defaults b/boards/nxp/mr-canhubk3/init/rc.board_defaults index 7ef22a054cb6..27aef9019a59 100644 --- a/boards/nxp/mr-canhubk3/init/rc.board_defaults +++ b/boards/nxp/mr-canhubk3/init/rc.board_defaults @@ -28,6 +28,12 @@ then safety_button start fi +if [ -f "/mnt/qspi/mtd_net" ] +then +else + netman update -i eth0 +fi + if param greater -s UAVCAN_ENABLE 0 then ifup can0 From 4ca3e1b6e68206174f002657d8d415d225e17af4 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 12 Apr 2024 09:47:44 +0200 Subject: [PATCH 538/652] mr_canhubk3: add netman in default.px4board --- boards/nxp/mr-canhubk3/default.px4board | 1 + boards/nxp/mr-canhubk3/fmu.px4board | 1 - boards/nxp/mr-canhubk3/sysview.px4board | 1 - boards/nxp/mr-canhubk3/zenoh.px4board | 1 - 4 files changed, 1 insertion(+), 3 deletions(-) diff --git a/boards/nxp/mr-canhubk3/default.px4board b/boards/nxp/mr-canhubk3/default.px4board index 4f551cbec644..63294e276f8a 100644 --- a/boards/nxp/mr-canhubk3/default.px4board +++ b/boards/nxp/mr-canhubk3/default.px4board @@ -17,6 +17,7 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_MFT=y CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=y diff --git a/boards/nxp/mr-canhubk3/fmu.px4board b/boards/nxp/mr-canhubk3/fmu.px4board index d6b17b1094e0..48a7883fe259 100644 --- a/boards/nxp/mr-canhubk3/fmu.px4board +++ b/boards/nxp/mr-canhubk3/fmu.px4board @@ -59,7 +59,6 @@ CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y CONFIG_SYSTEMCMDS_DMESG=y CONFIG_SYSTEMCMDS_DUMPFILE=y CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y -CONFIG_SYSTEMCMDS_NETMAN=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REFLECT=y diff --git a/boards/nxp/mr-canhubk3/sysview.px4board b/boards/nxp/mr-canhubk3/sysview.px4board index d190234fcbdb..2089b09931c5 100644 --- a/boards/nxp/mr-canhubk3/sysview.px4board +++ b/boards/nxp/mr-canhubk3/sysview.px4board @@ -45,7 +45,6 @@ CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y CONFIG_SYSTEMCMDS_DMESG=y CONFIG_SYSTEMCMDS_DUMPFILE=y CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y -CONFIG_SYSTEMCMDS_NETMAN=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REFLECT=y diff --git a/boards/nxp/mr-canhubk3/zenoh.px4board b/boards/nxp/mr-canhubk3/zenoh.px4board index 28de5ea5cc76..fe2297a5547f 100644 --- a/boards/nxp/mr-canhubk3/zenoh.px4board +++ b/boards/nxp/mr-canhubk3/zenoh.px4board @@ -50,7 +50,6 @@ CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y CONFIG_SYSTEMCMDS_DMESG=y CONFIG_SYSTEMCMDS_DUMPFILE=y CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y -CONFIG_SYSTEMCMDS_NETMAN=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REFLECT=y From ebcfb5348ce1cdd18ebc562812b03ccdad6f488c Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 22 Jul 2024 13:35:49 +0200 Subject: [PATCH 539/652] Navigator: increase stack by 40 bytes Signed-off-by: Silvan Fuhrer --- src/modules/navigator/navigator_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index d5ea7ac22d28..434be34e7739 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1069,7 +1069,7 @@ int Navigator::task_spawn(int argc, char *argv[]) _task_id = px4_task_spawn_cmd("navigator", SCHED_DEFAULT, SCHED_PRIORITY_NAVIGATION, - PX4_STACK_ADJUSTED(2160), + PX4_STACK_ADJUSTED(2200), (px4_main_t)&run_trampoline, (char *const *)argv); From fd72578e982098ec35d005512216224acfb3a968 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 24 Jul 2024 12:32:23 -0400 Subject: [PATCH 540/652] ekf2: avoid constraining parameters every iteration --- src/modules/ekf2/EKF/covariance.cpp | 15 +++++++-------- src/modules/ekf2/EKF/ekf.cpp | 17 +++++++++++++++++ 2 files changed, 24 insertions(+), 8 deletions(-) diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 520b7855443c..787d1636e2ab 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -115,11 +115,11 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) const float dt = 0.5f * (imu_delayed.delta_vel_dt + imu_delayed.delta_ang_dt); // gyro noise variance - float gyro_noise = math::constrain(_params.gyro_noise, 0.f, 1.f); + float gyro_noise = _params.gyro_noise; const float gyro_var = sq(gyro_noise); // accel noise variance - float accel_noise = math::constrain(_params.accel_noise, 0.f, 1.f); + float accel_noise = _params.accel_noise; Vector3f accel_var; for (unsigned i = 0; i < 3; i++) { @@ -143,7 +143,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) // gyro bias: add process noise { - const float gyro_bias_sig = dt * math::constrain(_params.gyro_bias_p_noise, 0.f, 1.f); + const float gyro_bias_sig = dt * _params.gyro_bias_p_noise; const float gyro_bias_process_noise = sq(gyro_bias_sig); for (unsigned index = 0; index < State::gyro_bias.dof; index++) { @@ -157,7 +157,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) // accel bias: add process noise { - const float accel_bias_sig = dt * math::constrain(_params.accel_bias_p_noise, 0.f, 1.f); + const float accel_bias_sig = dt * _params.accel_bias_p_noise; const float accel_bias_process_noise = sq(accel_bias_sig); for (unsigned index = 0; index < State::accel_bias.dof; index++) { @@ -172,7 +172,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_MAGNETOMETER) // mag_I: add process noise - float mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.f, 1.f); + float mag_I_sig = dt * _params.mage_p_noise; float mag_I_process_noise = sq(mag_I_sig); for (unsigned index = 0; index < State::mag_I.dof; index++) { @@ -184,7 +184,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) } // mag_B: add process noise - float mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.f, 1.f); + float mag_B_sig = dt * _params.magb_p_noise; float mag_B_process_noise = sq(mag_B_sig); for (unsigned index = 0; index < State::mag_B.dof; index++) { @@ -201,8 +201,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_WIND) // wind vel: add process noise - float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) - * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); + float wind_vel_nsd_scaled = _params.wind_vel_nsd * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf)); float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt; for (unsigned index = 0; index < State::wind_vel.dof; index++) { diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 5efb2b84ff4b..ac75a367d662 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -132,6 +132,8 @@ void Ekf::reset() } _zero_velocity_update.reset(); + + updateParameters(); } bool Ekf::update() @@ -339,6 +341,21 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl void Ekf::updateParameters() { + _params.gyro_noise = math::constrain(_params.gyro_noise, 0.f, 1.f); + _params.accel_noise = math::constrain(_params.accel_noise, 0.f, 1.f); + + _params.gyro_bias_p_noise = math::constrain(_params.gyro_bias_p_noise, 0.f, 1.f); + _params.accel_bias_p_noise = math::constrain(_params.accel_bias_p_noise, 0.f, 1.f); + +#if defined(CONFIG_EKF2_MAGNETOMETER) + _params.mage_p_noise = math::constrain(_params.mage_p_noise, 0.f, 1.f); + _params.magb_p_noise = math::constrain(_params.magb_p_noise, 0.f, 1.f); +#endif // CONFIG_EKF2_MAGNETOMETER + +#if defined(CONFIG_EKF2_WIND) + _params.wind_vel_nsd = math::constrain(_params.wind_vel_nsd, 0.f, 1.f); +#endif // CONFIG_EKF2_WIND + #if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME) _aux_global_position.updateParameters(); #endif // CONFIG_EKF2_AUX_GLOBAL_POSITION From b76c1c97b3e4de622c308408afc00ec654751b28 Mon Sep 17 00:00:00 2001 From: oravla5 Date: Mon, 22 Jul 2024 11:03:48 +0200 Subject: [PATCH 541/652] ekf2: Optical flow enabled by default --- src/modules/ekf2/module.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 9c37daac7726..e29c1b46ccc0 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -670,7 +670,7 @@ parameters: short: Optical flow aiding long: Enable optical flow fusion. type: boolean - default: 0 + default: 1 EKF2_OF_N_MIN: description: short: Optical flow minimum noise From 85b6b0a4061e448c05fc912e4949a24ce513dbd9 Mon Sep 17 00:00:00 2001 From: sbtjagu <145494402+sbtjagu@users.noreply.github.com> Date: Thu, 25 Jul 2024 17:13:30 +0200 Subject: [PATCH 542/652] ackermann: added delay comand support (#23445) --- .../RoverAckermannGuidance.cpp | 75 ++++++++++--------- .../RoverAckermannGuidance.hpp | 1 + 2 files changed, 42 insertions(+), 34 deletions(-) diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index 3cc6dfc3c2b9..2862bcf18199 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -125,47 +125,54 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c _curr_wp(0), _curr_wp(1)); - if (_param_ra_miss_vel_min.get() > 0.f && _param_ra_miss_vel_min.get() < _param_ra_miss_vel_def.get() - && _param_ra_miss_vel_gain.get() > FLT_EPSILON) { // Cornering slow down effect - if (distance_to_prev_wp <= _prev_acceptance_radius && _prev_acceptance_radius > FLT_EPSILON) { - const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acceptance_radius; - desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); - - } else if (distance_to_curr_wp <= _acceptance_radius && _acceptance_radius > FLT_EPSILON) { - const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; - desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); - - } else { // Straight line speed - if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_jerk.get() > FLT_EPSILON - && _acceptance_radius > FLT_EPSILON) { - float max_velocity{0.f}; - - if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { - max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), - _param_ra_max_accel.get(), distance_to_curr_wp, 0.f); + if (distance_to_curr_wp > _acceptance_radius) { + if (_param_ra_miss_vel_min.get() > 0.f && _param_ra_miss_vel_min.get() < _param_ra_miss_vel_def.get() + && _param_ra_miss_vel_gain.get() > FLT_EPSILON) { // Cornering slow down effect + if (distance_to_prev_wp <= _prev_acceptance_radius && _prev_acceptance_radius > FLT_EPSILON) { + const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acceptance_radius; + desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); + + } else if (distance_to_curr_wp <= _acceptance_radius && _acceptance_radius > FLT_EPSILON) { + const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; + desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); + + } else { // Straight line speed + if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_jerk.get() > FLT_EPSILON + && _acceptance_radius > FLT_EPSILON) { + float max_velocity{0.f}; + + if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { + max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), + _param_ra_max_accel.get(), distance_to_curr_wp, 0.f); + + } else { + const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; + max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), + _param_ra_max_accel.get(), distance_to_curr_wp - _acceptance_radius, cornering_speed); + } + + desired_speed = math::constrain(max_velocity, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); } else { - const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; - max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), - _param_ra_max_accel.get(), distance_to_curr_wp - _acceptance_radius, cornering_speed); + desired_speed = _param_ra_miss_vel_def.get(); } - - desired_speed = math::constrain(max_velocity, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); - - } else { - desired_speed = _param_ra_miss_vel_def.get(); } + + } else { + desired_speed = _param_ra_miss_vel_def.get(); } - } else { - desired_speed = _param_ra_miss_vel_def.get(); - } + // Calculate desired steering + desired_steering = calcDesiredSteering(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, _param_ra_lookahd_gain.get(), + _param_ra_lookahd_min.get(), _param_ra_lookahd_max.get(), _param_ra_wheel_base.get(), desired_speed, vehicle_yaw); + desired_steering = math::constrain(desired_steering, -_param_ra_max_steer_angle.get(), + _param_ra_max_steer_angle.get()); + _prev_desired_steering = desired_steering; - // Calculate desired steering - desired_steering = calcDesiredSteering(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, _param_ra_lookahd_gain.get(), - _param_ra_lookahd_min.get(), _param_ra_lookahd_max.get(), _param_ra_wheel_base.get(), desired_speed, vehicle_yaw); - desired_steering = math::constrain(desired_steering, -_param_ra_max_steer_angle.get(), - _param_ra_max_steer_angle.get()); + } else { // Catch delay command + desired_steering = _prev_desired_steering; // Avoid steering on the spot + desired_speed = 0.f; + } } // Throttle PID diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index 090f37b15e97..0a73abceb553 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -151,6 +151,7 @@ class RoverAckermannGuidance : public ModuleParams Vector2f _curr_pos_ned{}; PID_t _pid_throttle; hrt_abstime _timestamp{0}; + float _prev_desired_steering{0.f}; // Waypoint variables Vector2d _curr_wp{}; From a07c986dbc893dd3e87be95a3a13841ae1279952 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Fri, 26 Jul 2024 07:46:11 +1000 Subject: [PATCH 543/652] Params generated as markdown table (#23443) --- src/lib/parameters/px4params/markdownout.py | 86 +++++++-------------- 1 file changed, 26 insertions(+), 60 deletions(-) diff --git a/src/lib/parameters/px4params/markdownout.py b/src/lib/parameters/px4params/markdownout.py index f83c504f8059..34e6f9e38666 100644 --- a/src/lib/parameters/px4params/markdownout.py +++ b/src/lib/parameters/px4params/markdownout.py @@ -17,38 +17,21 @@ def __init__(self, groups): - - """ ) for group in groups: - result += '## %s\n\n' % group.GetName() - result += ( -""" - - - - - -""" - ) + result += f'## {group.GetName()}\n\n' + for param in group.GetParams(): - code = param.GetName() - name = param.GetFieldValue("short_desc") or '' - name = html.escape(name) + name = param.GetName() + short_desc = param.GetFieldValue("short_desc") or '' + if short_desc: + if not short_desc.strip().endswith('.'): + short_desc += "." + #short_desc = html.escape(short_desc) long_desc = param.GetFieldValue("long_desc") or '' - long_desc = html.escape(long_desc) + #long_desc = html.escape(long_desc) min_val = param.GetFieldValue("min") or '' max_val = param.GetFieldValue("max") or '' increment = param.GetFieldValue("increment") or '' @@ -62,60 +45,43 @@ def __init__(self, groups): #field_codes = param.GetFieldCodes() ## Disabled as not needed for display. #boolean = param.GetFieldValue("boolean") # or '' # Disabled - does not appear useful. - # Format values for display. - # Display min/max/increment value based on what values are defined. - max_min_combined = '' - if min_val or max_val: - if not min_val: - min_val='?' - if not max_val: - max_val='?' - max_min_combined+=f"[{min_val}, {max_val}] " - if increment: - max_min_combined+='(%s)' % increment - - if long_desc != '': - long_desc = f"

      Comment: {long_desc}

      " - - if name == code: - name = "" - code=f"{code}" - - if reboot_required: - reboot_required='

      Reboot required: %s

      \n' % reboot_required - enum_codes=param.GetEnumCodes() or '' # Gets numerical values for parameter. enum_output='' # Format codes and their descriptions for display. if enum_codes: - enum_output+='Values:
        ' + enum_output+='**Values:**\n\n' enum_codes=sorted(enum_codes,key=float) for item in enum_codes: - enum_output+=f"\n
      • {item}: {html.escape(param.GetEnumValue(item))}
      • " - enum_output+='\n
      ' - + enum_output+=f"- `{item}`: {param.GetEnumValue(item)}\n" + enum_output+='\n\n' bitmask_list=param.GetBitmaskList() #Gets bitmask values for parameter bitmask_output='' #Format bitmask values if bitmask_list: - bitmask_output+='Bitmask:
        ' + bitmask_output+='**Bitmask:**\n\n' for bit in bitmask_list: bit_text = param.GetBitmaskBit(bit) - bit_text = html.escape(bit_text) - bitmask_output+=f"
      • {bit}: {bit_text}
      • \n" - bitmask_output+='
      \n' + bitmask_output+=f"- `{bit}`: {bit_text}\n" + bitmask_output+='\n\n' if is_boolean and def_val=='1': def_val='Enabled (1)' if is_boolean and def_val=='0': def_val='Disabled (0)' - result += f"\n \n \n \n \n \n\n" - - #Close the table. - result += '
      NameDescription[Min, Max] (Incr.)DefaultUnits
      {code} ({type}){name} {long_desc} {enum_output} {bitmask_output} {reboot_required}{max_min_combined}{def_val}{unit}
      \n\n' + result += f'### {name} (`{type}`)' + ' {#' + name + '}\n\n' + if short_desc: + result += f'{short_desc}\n\n' + if long_desc: + result += f'{long_desc}\n\n' + if enum_codes: + result += enum_output + if bitmask_list: + result += bitmask_output + # Format the ranges as a table. + result += f"Reboot | minValue | maxValue | increment | default | unit\n--- | --- | --- | --- | --- | ---\n{reboot_required} | {min_val} | {max_val} | {increment} | {def_val} | {unit} \n\n" self.output = result From 0b1eba948a31c9f83fd48a32ddd94226df394adf Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 25 Jul 2024 15:02:57 +0200 Subject: [PATCH 544/652] ekf2-flow: add param to force using internal gyro In some cases the vibration environment of the optical flow sensor is worse than near the autopilot. --- .../optical_flow/optical_flow_control.cpp | 23 +++++++++++++++---- src/modules/ekf2/EKF/common.h | 6 +++++ src/modules/ekf2/EKF2.cpp | 1 + src/modules/ekf2/EKF2.hpp | 2 ++ src/modules/ekf2/module.yaml | 10 ++++++++ 5 files changed, 37 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 3c4c031f316c..3299577a2875 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 @@ -56,12 +56,25 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) _ref_body_rate = -(imu_delayed.delta_ang / imu_delayed.delta_ang_dt - getGyroBias()); // ensure valid flow sample gyro rate before proceeding - if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(0)) || !PX4_ISFINITE(_flow_sample_delayed.gyro_rate(1))) { - _flow_sample_delayed.gyro_rate = _ref_body_rate; + switch (static_cast(_params.flow_gyro_src)) { + default: + + /* FALLTHROUGH */ + case FlowGyroSource::Auto: + if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(0)) || !PX4_ISFINITE(_flow_sample_delayed.gyro_rate(1))) { + _flow_sample_delayed.gyro_rate = _ref_body_rate; + } - } else if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(2))) { - // Some flow modules only provide X ind Y angular rates. If this is the case, complete the vector with our own Z gyro - _flow_sample_delayed.gyro_rate(2) = _ref_body_rate(2); + if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(2))) { + // Some flow modules only provide X ind Y angular rates. If this is the case, complete the vector with our own Z gyro + _flow_sample_delayed.gyro_rate(2) = _ref_body_rate(2); + } + + break; + + case FlowGyroSource::Internal: + _flow_sample_delayed.gyro_rate = _ref_body_rate; + break; } const flowSample &flow_sample = _flow_sample_delayed; diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 6294310bbfc2..af03d2a8db84 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -167,6 +167,11 @@ enum class MagCheckMask : uint8_t { FORCE_WMM = (1 << 2) }; +enum class FlowGyroSource : uint8_t { + Auto = 0, + Internal = 1 +}; + struct imuSample { uint64_t time_us{}; ///< timestamp of the measurement (uSec) Vector3f delta_ang{}; ///< delta angle in body frame (integrated gyro measurements) (rad) @@ -442,6 +447,7 @@ struct parameters { #if defined(CONFIG_EKF2_OPTICAL_FLOW) int32_t flow_ctrl {0}; + int32_t flow_gyro_src {static_cast(FlowGyroSource::Auto)}; float flow_delay_ms{5.0f}; ///< optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval // optical flow fusion diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index ac98b9584f0b..bceb4d3dcc23 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -181,6 +181,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_OPTICAL_FLOW) _param_ekf2_of_ctrl(_params->flow_ctrl), + _param_ekf2_of_gyr_src(_params->flow_gyro_src), _param_ekf2_of_delay(_params->flow_delay_ms), _param_ekf2_of_n_min(_params->flow_noise), _param_ekf2_of_n_max(_params->flow_noise_qual_min), diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 326b0833a4e4..ef7280e88c18 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -656,6 +656,8 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem // optical flow fusion (ParamExtInt) _param_ekf2_of_ctrl, ///< optical flow fusion selection + (ParamExtInt) + _param_ekf2_of_gyr_src, (ParamExtFloat) _param_ekf2_of_delay, ///< optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval (ParamExtFloat) diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index e29c1b46ccc0..8ed6e700dbad 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -671,6 +671,16 @@ parameters: long: Enable optical flow fusion. type: boolean default: 1 + EKF2_OF_GYR_SRC: + description: + short: Optical flow angular rate compensation source + long: 'Auto: use gyro from optical flow message if available, internal gyro otherwise. + Internal: always use internal gyro' + type: enum + values: + 0: Auto + 1: Internal + default: 0 EKF2_OF_N_MIN: description: short: Optical flow minimum noise From ee8030de564668050aefab000ac1d129cd00faa1 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Jul 2024 17:11:13 +0200 Subject: [PATCH 545/652] Commander: do not switch out of Terminte after disarm Signed-off-by: Silvan Fuhrer --- src/modules/commander/UserModeIntention.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/UserModeIntention.cpp b/src/modules/commander/UserModeIntention.cpp index 9bb3d08407f9..ac56b9f78225 100644 --- a/src/modules/commander/UserModeIntention.cpp +++ b/src/modules/commander/UserModeIntention.cpp @@ -73,7 +73,10 @@ bool UserModeIntention::change(uint8_t user_intended_nav_state, ModeChangeSource _had_mode_change = true; _user_intented_nav_state = user_intended_nav_state; - if (!_health_and_arming_checks.modePreventsArming(user_intended_nav_state)) { + // Special case termination state: even though this mode prevents arming, + // still don't switch out of it after disarm and thus store it in _nav_state_after_disarming. + if (!_health_and_arming_checks.modePreventsArming(user_intended_nav_state) + || user_intended_nav_state == vehicle_status_s::NAVIGATION_STATE_TERMINATION) { _nav_state_after_disarming = user_intended_nav_state; } From 97561d7802eddb899f1c4f0a3a3ae9aa4c26bb73 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Jul 2024 17:11:59 +0200 Subject: [PATCH 546/652] Commander: never allow to switch out of Terminate state with user intend Signed-off-by: Silvan Fuhrer --- src/modules/commander/UserModeIntention.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/commander/UserModeIntention.cpp b/src/modules/commander/UserModeIntention.cpp index ac56b9f78225..02b4a7f3f7e1 100644 --- a/src/modules/commander/UserModeIntention.cpp +++ b/src/modules/commander/UserModeIntention.cpp @@ -69,6 +69,9 @@ bool UserModeIntention::change(uint8_t user_intended_nav_state, ModeChangeSource } } + // never allow to change out of termination state + allow_change &= _vehicle_status.nav_state != vehicle_status_s::NAVIGATION_STATE_TERMINATION; + if (allow_change) { _had_mode_change = true; _user_intented_nav_state = user_intended_nav_state; From 5808dac4bc1d2135d581a6a7b6aaef80a180081f Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Wed, 24 Jul 2024 14:09:12 +0200 Subject: [PATCH 547/652] reset position-mode line following after position reset --- src/modules/ekf2/EKF/ekf.cpp | 1 + .../FixedwingPositionControl.cpp | 25 +++++++++++++------ .../FixedwingPositionControl.hpp | 10 +++----- 3 files changed, 23 insertions(+), 13 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index ac75a367d662..9f6a0ab40b66 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -330,6 +330,7 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl && fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1) ) { ECL_INFO("fused external observation as position measurement"); + _state_reset_status.reset_count.posNE++; _time_last_hor_pos_fuse = _time_delayed_us; _last_known_pos.xy() = _state.pos.xy(); return true; diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index a1286db40252..c80a9edb4106 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -2134,6 +2134,10 @@ FixedwingPositionControl::control_manual_position(const float control_interval, throttle_max = 0.0f; } + if (_local_pos.xy_reset_counter != _xy_reset_counter) { + _time_last_xy_reset = _local_pos.timestamp; + } + /* heading control */ // TODO: either make it course hold (easier) or a real heading hold (minus all the complexity here) if (fabsf(_manual_control_setpoint.roll) < HDG_HOLD_MAN_INPUT_THRESH && @@ -2164,6 +2168,13 @@ FixedwingPositionControl::control_manual_position(const float control_interval, _hdg_hold_position.lon = _current_longitude; } + // if there's a reset-by-fusion, the ekf needs some time to converge, + // therefore we go into track holiding for 2 seconds + if (_local_pos.timestamp - _time_last_xy_reset < 2e6) { + _hdg_hold_position.lat = _current_latitude; + _hdg_hold_position.lon = _current_longitude; + } + Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; Vector2f curr_wp_local = _global_local_proj_ref.project(_hdg_hold_position.lat, _hdg_hold_position.lon); @@ -2310,28 +2321,24 @@ FixedwingPositionControl::Run() // handle estimator reset events. we only adjust setpoins for manual modes if (_control_mode.flag_control_manual_enabled) { - if (_control_mode.flag_control_altitude_enabled && _local_pos.vz_reset_counter != _alt_reset_counter) { + if (_control_mode.flag_control_altitude_enabled && _local_pos.vz_reset_counter != _vz_reset_counter) { // make TECS accept step in altitude and demanded altitude _tecs.handle_alt_step(_current_altitude, -_local_pos.vz); } // adjust navigation waypoints in position control mode if (_control_mode.flag_control_altitude_enabled && _control_mode.flag_control_velocity_enabled - && _local_pos.vxy_reset_counter != _pos_reset_counter) { + && _local_pos.vxy_reset_counter != _vxy_reset_counter) { // reset heading hold flag, which will re-initialise position control _hdg_hold_enabled = false; } } - // update the reset counters in any case - _alt_reset_counter = _local_pos.vz_reset_counter; - _pos_reset_counter = _local_pos.vxy_reset_counter; - // Convert Local setpoints to global setpoints if (!_global_local_proj_ref.isInitialized() || (_global_local_proj_ref.getProjectionReferenceTimestamp() != _local_pos.ref_timestamp) - || (_local_pos.vxy_reset_counter != _pos_reset_counter)) { + || (_local_pos.vxy_reset_counter != _vxy_reset_counter)) { double reference_latitude = 0.; double reference_longitude = 0.; @@ -2616,6 +2623,10 @@ FixedwingPositionControl::Run() _spoilers_setpoint_pub.publish(spoilers_setpoint); } + _vz_reset_counter = _local_pos.vz_reset_counter; + _vxy_reset_counter = _local_pos.vxy_reset_counter; + _xy_reset_counter = _local_pos.xy_reset_counter; + perf_end(_loop_perf); } } diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index 3f2398f340c4..9a34f43524d3 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -406,12 +406,10 @@ class FixedwingPositionControl final : public ModuleBase Date: Thu, 25 Jul 2024 16:34:13 +0200 Subject: [PATCH 548/652] bugfix: wrong reset_counter used --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 9 ++++----- src/modules/fw_pos_control/FixedwingPositionControl.hpp | 3 +-- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index c80a9edb4106..6cc6bd01a99c 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -2321,14 +2321,14 @@ FixedwingPositionControl::Run() // handle estimator reset events. we only adjust setpoins for manual modes if (_control_mode.flag_control_manual_enabled) { - if (_control_mode.flag_control_altitude_enabled && _local_pos.vz_reset_counter != _vz_reset_counter) { + if (_control_mode.flag_control_altitude_enabled && _local_pos.z_reset_counter != _z_reset_counter) { // make TECS accept step in altitude and demanded altitude _tecs.handle_alt_step(_current_altitude, -_local_pos.vz); } // adjust navigation waypoints in position control mode if (_control_mode.flag_control_altitude_enabled && _control_mode.flag_control_velocity_enabled - && _local_pos.vxy_reset_counter != _vxy_reset_counter) { + && _local_pos.xy_reset_counter != _xy_reset_counter) { // reset heading hold flag, which will re-initialise position control _hdg_hold_enabled = false; @@ -2338,7 +2338,7 @@ FixedwingPositionControl::Run() // Convert Local setpoints to global setpoints if (!_global_local_proj_ref.isInitialized() || (_global_local_proj_ref.getProjectionReferenceTimestamp() != _local_pos.ref_timestamp) - || (_local_pos.vxy_reset_counter != _vxy_reset_counter)) { + || (_local_pos.xy_reset_counter != _xy_reset_counter)) { double reference_latitude = 0.; double reference_longitude = 0.; @@ -2623,8 +2623,7 @@ FixedwingPositionControl::Run() _spoilers_setpoint_pub.publish(spoilers_setpoint); } - _vz_reset_counter = _local_pos.vz_reset_counter; - _vxy_reset_counter = _local_pos.vxy_reset_counter; + _z_reset_counter = _local_pos.z_reset_counter; _xy_reset_counter = _local_pos.xy_reset_counter; perf_end(_loop_perf); diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index 9a34f43524d3..77eb88eb6511 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -406,9 +406,8 @@ class FixedwingPositionControl final : public ModuleBase Date: Fri, 26 Jul 2024 16:26:17 +0200 Subject: [PATCH 549/652] fw_position_control: use time literals --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 6cc6bd01a99c..f636b0e013fd 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -2170,7 +2170,7 @@ FixedwingPositionControl::control_manual_position(const float control_interval, // if there's a reset-by-fusion, the ekf needs some time to converge, // therefore we go into track holiding for 2 seconds - if (_local_pos.timestamp - _time_last_xy_reset < 2e6) { + if (_local_pos.timestamp - _time_last_xy_reset < 2_s) { _hdg_hold_position.lat = _current_latitude; _hdg_hold_position.lon = _current_longitude; } From 9257744da36945725910439f6a99bc4cad4d8296 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 29 Jul 2024 11:14:59 +0200 Subject: [PATCH 550/652] TECS: reduce default of FW_T_SPD_STD to reduce airspeed measurement delay (#23441) Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/fw_path_navigation_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control/fw_path_navigation_params.c b/src/modules/fw_pos_control/fw_path_navigation_params.c index a5d9c851f3bd..ac2ab276af41 100644 --- a/src/modules/fw_pos_control/fw_path_navigation_params.c +++ b/src/modules/fw_pos_control/fw_path_navigation_params.c @@ -514,7 +514,7 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); * @increment 0.1 * @group FW TECS */ -PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.2f); +PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.07f); /** * Airspeed rate measurement standard deviation From 7b3d168af1ae9c02a29a3eec99338dbd2072acd4 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 29 Jul 2024 14:18:00 +0200 Subject: [PATCH 551/652] baro tuning: make hpf argument optional This filter is often not needed. Setting the default value to -1 makes it optional. --- .../baro_static_pressure_compensation_tuning.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py b/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py index 2629700228c3..f30c7cf4a7f1 100644 --- a/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py +++ b/src/modules/ekf2/EKF/python/tuning_tools/baro_static_pressure_compensation/baro_static_pressure_compensation_tuning.py @@ -226,7 +226,7 @@ def run(logfile, w_hpf): # Provide parameter file path and name parser.add_argument('logfile', help='Full ulog file path, name and extension', type=str) - parser.add_argument('--hpf', help='Cuttoff frequency of high-pass filter on baro error (Hz)', type=float) + parser.add_argument('--hpf', help='Cuttoff frequency of high-pass filter on baro error (Hz)', type=float, default=-1) args = parser.parse_args() logfile = os.path.abspath(args.logfile) # Convert to absolute path From b93dd0e8d45340e510e74b5be84a618b15a95787 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Tue, 30 Jul 2024 14:16:05 +0200 Subject: [PATCH 552/652] purePursuit: migrate parameters to library (#23438) --- .../airframes/4012_gz_rover_ackermann | 8 +-- src/lib/pure_pursuit/CMakeLists.txt | 3 +- src/lib/pure_pursuit/PurePursuit.cpp | 34 ++++++++++--- src/lib/pure_pursuit/PurePursuit.hpp | 49 +++++++++++++++--- src/lib/pure_pursuit/PurePursuitTest.cpp | 51 +++++++++++-------- src/lib/pure_pursuit/module.yaml | 37 ++++++++++++++ .../RoverAckermannGuidance.cpp | 40 +++++++-------- .../RoverAckermannGuidance.hpp | 19 +++---- src/modules/rover_ackermann/module.yaml | 37 -------------- 9 files changed, 168 insertions(+), 110 deletions(-) create mode 100644 src/lib/pure_pursuit/module.yaml diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann b/ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann index 91c44baff3e9..6f81b7036aa0 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann @@ -15,9 +15,6 @@ param set-default SIM_GZ_EN 1 # Gazebo bridge param set-default NAV_ACC_RAD 0.5 param set-default RA_ACC_RAD_GAIN 2 param set-default RA_ACC_RAD_MAX 3 -param set-default RA_LOOKAHD_GAIN 1 -param set-default RA_LOOKAHD_MAX 10 -param set-default RA_LOOKAHD_MIN 1 param set-default RA_MAX_ACCEL 1.5 param set-default RA_MAX_JERK 15 param set-default RA_MAX_SPEED 3 @@ -30,6 +27,11 @@ param set-default RA_SPEED_I 0.01 param set-default RA_SPEED_P 2 param set-default RA_WHEEL_BASE 0.321 +# Pure Pursuit parameters +param set-default PP_LOOKAHD_GAIN 1 +param set-default PP_LOOKAHD_MAX 10 +param set-default PP_LOOKAHD_MIN 1 + # Simulated sensors param set-default SENS_EN_GPSSIM 1 param set-default SENS_EN_BAROSIM 0 diff --git a/src/lib/pure_pursuit/CMakeLists.txt b/src/lib/pure_pursuit/CMakeLists.txt index 1547d3dcdb69..19154fb5a53f 100644 --- a/src/lib/pure_pursuit/CMakeLists.txt +++ b/src/lib/pure_pursuit/CMakeLists.txt @@ -36,4 +36,5 @@ px4_add_library(pure_pursuit PurePursuit.hpp ) -px4_add_unit_gtest(SRC PurePursuitTest.cpp LINKLIBS pure_pursuit) +px4_add_functional_gtest(SRC PurePursuitTest.cpp LINKLIBS pure_pursuit) +set_property(GLOBAL APPEND PROPERTY PX4_MODULE_CONFIG_FILES ${CMAKE_CURRENT_SOURCE_DIR}/module.yaml) diff --git a/src/lib/pure_pursuit/PurePursuit.cpp b/src/lib/pure_pursuit/PurePursuit.cpp index 5313efb393db..324a504959ba 100644 --- a/src/lib/pure_pursuit/PurePursuit.cpp +++ b/src/lib/pure_pursuit/PurePursuit.cpp @@ -34,21 +34,43 @@ #include "PurePursuit.hpp" #include + +PurePursuit::PurePursuit(ModuleParams *parent) : ModuleParams(parent) +{ + _param_handles.lookahead_gain = param_find("PP_LOOKAHD_GAIN"); + _param_handles.lookahead_max = param_find("PP_LOOKAHD_MAX"); + _param_handles.lookahead_min = param_find("PP_LOOKAHD_MIN"); + updateParams(); +} + +void PurePursuit::updateParams() +{ + param_get(_param_handles.lookahead_gain, &_params.lookahead_gain); + param_get(_param_handles.lookahead_max, &_params.lookahead_max); + param_get(_param_handles.lookahead_min, &_params.lookahead_min); + + ModuleParams::updateParams(); + +} + float PurePursuit::calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, - const float lookahead_distance) + const float vehicle_speed) { // Check input validity - if (!curr_wp_ned.isAllFinite() || !curr_pos_ned.isAllFinite() || lookahead_distance < FLT_EPSILON - || !PX4_ISFINITE(lookahead_distance) || !prev_wp_ned.isAllFinite()) { + if (!curr_wp_ned.isAllFinite() || !curr_pos_ned.isAllFinite() || vehicle_speed < -FLT_EPSILON + || !PX4_ISFINITE(vehicle_speed) || !prev_wp_ned.isAllFinite()) { return NAN; } + _lookahead_distance = math::constrain(_params.lookahead_gain * vehicle_speed, + _params.lookahead_min, _params.lookahead_max); + // Pure pursuit const Vector2f curr_pos_to_curr_wp = curr_wp_ned - curr_pos_ned; const Vector2f prev_wp_to_curr_wp = curr_wp_ned - prev_wp_ned; - if (curr_pos_to_curr_wp.norm() < lookahead_distance + if (curr_pos_to_curr_wp.norm() < _lookahead_distance || prev_wp_to_curr_wp.norm() < FLT_EPSILON) { // Target current waypoint if closer to it than lookahead or waypoints overlap return atan2f(curr_pos_to_curr_wp(1), curr_pos_to_curr_wp(0)); @@ -61,11 +83,11 @@ float PurePursuit::calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2 const Vector2f curr_pos_to_path = distance_on_line_segment - prev_wp_to_curr_pos; // Shortest vector from the current position to the path - if (curr_pos_to_path.norm() > lookahead_distance) { // Target closest point on path if there is no intersection point + if (curr_pos_to_path.norm() > _lookahead_distance) { // Target closest point on path if there is no intersection point return atan2f(curr_pos_to_path(1), curr_pos_to_path(0)); } - const float line_extension = sqrt(powf(lookahead_distance, 2.f) - powf(curr_pos_to_path.norm(), + const float line_extension = sqrt(powf(_lookahead_distance, 2.f) - powf(curr_pos_to_path.norm(), 2.f)); // Length of the vector from the endpoint of distance_on_line_segment to the intersection point const Vector2f prev_wp_to_intersection_point = distance_on_line_segment + line_extension * prev_wp_to_curr_wp_u; diff --git a/src/lib/pure_pursuit/PurePursuit.hpp b/src/lib/pure_pursuit/PurePursuit.hpp index 6e6203296194..66b9b8ce7cfe 100644 --- a/src/lib/pure_pursuit/PurePursuit.hpp +++ b/src/lib/pure_pursuit/PurePursuit.hpp @@ -31,7 +31,10 @@ * ****************************************************************************/ +#pragma once + #include +#include using namespace matrix; @@ -50,6 +53,10 @@ using namespace matrix; * Pure pursuit is a path following algorithm that uses the intersection between the path and * a circle (the radius of which is referred to as lookahead distance) around the vehicle as * the target point for the vehicle. + * The lookahead distance is defined as v * k. + * v: Vehicle ground speed [m/s] + * k: Tuning parameter + * The lookahead distance is further constrained between an upper and lower threshhold. * C * / * __/__ @@ -68,24 +75,52 @@ using namespace matrix; * ⌄ * (+- 3.14159 rad) * - * Input: Current/prev waypoint and the vehicle position in NED frame as well as the lookahead distance. - * Output: Calculates the intersection points and returns the heading towards the point that is closer to the current waypoint. + * Input: Current/prev waypoint and the vehicle position in NED frame as well as the vehicle speed. + * Output: Calculates the intersection points as described above and returns the heading towards the point that is closer to the current waypoint. */ -class PurePursuit +class PurePursuit : public ModuleParams { public: + PurePursuit(ModuleParams *parent); + ~PurePursuit() = default; + /** * @brief Return heading towards the intersection point between a circle with a radius of - * lookahead_distance around the vehicle and an extended line segment from the previous to the current waypoint. + * vehicle_speed * PP_LOOKAHD_GAIN around the vehicle and an extended line segment from the previous to the current waypoint. * Exceptions: - * Will return heading towards the current waypoint if it is closer to the vehicle than the lookahead. + * Will return heading towards the current waypoint if it is closer to the vehicle than the lookahead or if the waypoints overlap. * Will return heading towards the closest point on the path if there are no intersection points (crosstrack error bigger than lookahead). * Will return NAN if input is invalid. * @param curr_wp_ned North/East coordinates of current waypoint in NED frame [m]. * @param prev_wp_ned North/East coordinates of previous waypoint in NED frame [m]. * @param curr_pos_ned North/East coordinates of current position of the vehicle in NED frame [m]. - * @param lookahead_distance Radius of circle around vehicle [m]. + * @param vehicle_speed Vehicle speed [m/s]. + * @param RA_LOOKAHD_GAIN Tuning parameter [-] + * @param RA_LOOKAHD_MAX Maximum lookahead distance [m] + * @param RA_LOOKAHD_MIN Minimum lookahead distance [m] */ float calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, - const float lookahead_distance); + float vehicle_speed); + + float getLookaheadDistance() {return _lookahead_distance;}; + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + + struct { + param_t lookahead_gain; + param_t lookahead_max; + param_t lookahead_min; + } _param_handles{}; + + struct { + float lookahead_gain{1.f}; + float lookahead_max{10.f}; + float lookahead_min{1.f}; + } _params{}; +private: + float _lookahead_distance{0.f}; }; diff --git a/src/lib/pure_pursuit/PurePursuitTest.cpp b/src/lib/pure_pursuit/PurePursuitTest.cpp index 6d1ad1caae67..c5b6897fbdaf 100644 --- a/src/lib/pure_pursuit/PurePursuitTest.cpp +++ b/src/lib/pure_pursuit/PurePursuitTest.cpp @@ -59,6 +59,15 @@ * | * ⌄ * (+- 3.14159 rad) + * + * NOTE: + * The tuning parameters for the pure pursuit algorithm are set to the following for all tests: + * PP_LOOKAHD_GAIN = 1.f + * PP_LOOKAHD_MAX = 10.f + * PP_LOOKAHD_MIN = 1.f + * This way passing the vehicle_speed in calcDesiredHeading function is equivalent to passing + * the lookahead distance. + * ******************************************************************/ #include @@ -66,9 +75,14 @@ using namespace matrix; -TEST(PurePursuitTest, InvalidLookaheadDistance) +class PurePursuitTest : public ::testing::Test +{ +public: + PurePursuit pure_pursuit{nullptr}; +}; + +TEST_F(PurePursuitTest, InvalidSpeed) { - PurePursuit pure_pursuit; // V C // / // / @@ -77,20 +91,16 @@ TEST(PurePursuitTest, InvalidLookaheadDistance) const Vector2f curr_wp_ned(10.f, 10.f); const Vector2f prev_wp_ned(0.f, 0.f); const Vector2f curr_pos_ned(10.f, 0.f); - // Zero lookahead - const float desired_heading1 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, 0.f); - // Negative lookahead - const float desired_heading2 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, -1.f); - // NaN lookahead - const float desired_heading3 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, NAN); + // Negative speed + const float desired_heading1 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, -1.f); + // NaN speed + const float desired_heading2 = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, NAN); EXPECT_FALSE(PX4_ISFINITE(desired_heading1)); EXPECT_FALSE(PX4_ISFINITE(desired_heading2)); - EXPECT_FALSE(PX4_ISFINITE(desired_heading3)); } -TEST(PurePursuitTest, InvalidWaypoints) +TEST_F(PurePursuitTest, InvalidWaypoints) { - PurePursuit pure_pursuit; // V C // / // / @@ -115,9 +125,8 @@ TEST(PurePursuitTest, InvalidWaypoints) EXPECT_FALSE(PX4_ISFINITE(desired_heading3)); } -TEST(PurePursuitTest, OutOfLookahead) +TEST_F(PurePursuitTest, OutOfLookahead) { - PurePursuit pure_pursuit; const float lookahead_distance{5.f}; // V C // / @@ -133,13 +142,12 @@ TEST(PurePursuitTest, OutOfLookahead) const float desired_heading2 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 20.f), Vector2f(0.f, 0.f), Vector2f(10.f, 10.f), lookahead_distance); - EXPECT_NEAR(desired_heading1, M_PI_2_F + M_PI_4_F, FLT_EPSILON); // Fallback: Bearing to current waypoint - EXPECT_NEAR(desired_heading2, M_PI_F, FLT_EPSILON); // Fallback: Bearing to current waypoint + EXPECT_NEAR(desired_heading1, M_PI_2_F + M_PI_4_F, FLT_EPSILON); // Fallback: Bearing to closest point on path + EXPECT_NEAR(desired_heading2, M_PI_F, FLT_EPSILON); // Fallback: Bearing to closest point on path } -TEST(PurePursuitTest, WaypointOverlap) +TEST_F(PurePursuitTest, WaypointOverlap) { - PurePursuit pure_pursuit; const float lookahead_distance{5.f}; // C/P // @@ -157,13 +165,12 @@ TEST(PurePursuitTest, WaypointOverlap) const float desired_heading2 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 0.f), Vector2f(0.f, 0.f), Vector2f(10.f, 10.f), lookahead_distance); - EXPECT_NEAR(desired_heading1, M_PI_4_F, FLT_EPSILON); // Fallback: Bearing to current waypoint - EXPECT_NEAR(desired_heading2, -(M_PI_4_F + M_PI_2_F), FLT_EPSILON); // Fallback: Bearing to current waypoint + EXPECT_NEAR(desired_heading1, M_PI_4_F, FLT_EPSILON); // Fallback: Bearing to closest point on path + EXPECT_NEAR(desired_heading2, -(M_PI_4_F + M_PI_2_F), FLT_EPSILON); // Fallback: Bearing to closest point on path } -TEST(PurePursuitTest, CurrAndPrevSameNorthCoordinate) +TEST_F(PurePursuitTest, CurrAndPrevSameNorthCoordinate) { - PurePursuit pure_pursuit; const float lookahead_distance{5.f}; // P -- V -- C const float desired_heading1 = pure_pursuit.calcDesiredHeading(Vector2f(0.f, 20.f), Vector2f(0.f, 0.f), Vector2f(0.f, @@ -190,5 +197,5 @@ TEST(PurePursuitTest, CurrAndPrevSameNorthCoordinate) EXPECT_NEAR(desired_heading1, M_PI_2_F, FLT_EPSILON); EXPECT_NEAR(desired_heading2, M_PI_2_F + M_PI_4_F, FLT_EPSILON); EXPECT_NEAR(desired_heading3, -(M_PI_2_F + M_PI_4_F), FLT_EPSILON); - EXPECT_NEAR(desired_heading4, M_PI_F, FLT_EPSILON); // Fallback: Bearing to current waypoint + EXPECT_NEAR(desired_heading4, M_PI_F, FLT_EPSILON); // Fallback: Bearing to closest point on path } diff --git a/src/lib/pure_pursuit/module.yaml b/src/lib/pure_pursuit/module.yaml new file mode 100644 index 000000000000..5e7cc109d464 --- /dev/null +++ b/src/lib/pure_pursuit/module.yaml @@ -0,0 +1,37 @@ +module_name: Pure Pursuit + +parameters: + - group: Pure Pursuit + definitions: + PP_LOOKAHD_GAIN: + description: + short: Tuning parameter for the pure pursuit controller + long: Lower value -> More aggressive controller (beware overshoot/oscillations) + type: float + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + PP_LOOKAHD_MIN: + description: + short: Minimum lookahead distance for the pure pursuit controller + type: float + unit: m + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + PP_LOOKAHD_MAX: + description: + short: Maximum lookahead distance for the pure pursuit controller + type: float + unit: m + min: 0.1 + max: 100 + increment: 0.01 + decimal: 2 + default: 10 diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index 2862bcf18199..db0495b67a3e 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -60,7 +60,6 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c { // Initializations float desired_speed{0.f}; - float desired_steering{0.f}; float vehicle_yaw{0.f}; float actual_speed{0.f}; bool mission_finished{false}; @@ -116,8 +115,10 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c } // Guidance logic - if (!mission_finished) { - // Calculate desired speed + if (mission_finished) { + _desired_steering = 0.f; + + } else { const float distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), _prev_wp(0), _prev_wp(1)); @@ -125,7 +126,11 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c _curr_wp(0), _curr_wp(1)); - if (distance_to_curr_wp > _acceptance_radius) { + if (distance_to_curr_wp < _acceptance_radius) { // Catch delay command + desired_speed = 0.f; + + } else { + // Calculate desired speed if (_param_ra_miss_vel_min.get() > 0.f && _param_ra_miss_vel_min.get() < _param_ra_miss_vel_def.get() && _param_ra_miss_vel_gain.get() > FLT_EPSILON) { // Cornering slow down effect if (distance_to_prev_wp <= _prev_acceptance_radius && _prev_acceptance_radius > FLT_EPSILON) { @@ -163,15 +168,10 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c } // Calculate desired steering - desired_steering = calcDesiredSteering(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, _param_ra_lookahd_gain.get(), - _param_ra_lookahd_min.get(), _param_ra_lookahd_max.get(), _param_ra_wheel_base.get(), desired_speed, vehicle_yaw); - desired_steering = math::constrain(desired_steering, -_param_ra_max_steer_angle.get(), - _param_ra_max_steer_angle.get()); - _prev_desired_steering = desired_steering; - - } else { // Catch delay command - desired_steering = _prev_desired_steering; // Avoid steering on the spot - desired_speed = 0.f; + _desired_steering = calcDesiredSteering(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, _param_ra_wheel_base.get(), + desired_speed, vehicle_yaw); + _desired_steering = math::constrain(_desired_steering, -_param_ra_max_steer_angle.get(), + _param_ra_max_steer_angle.get()); } } @@ -203,7 +203,7 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c // Return motor setpoints motor_setpoint motor_setpoint_temp; - motor_setpoint_temp.steering = math::interpolate(desired_steering, -_param_ra_max_steer_angle.get(), + motor_setpoint_temp.steering = math::interpolate(_desired_steering, -_param_ra_max_steer_angle.get(), _param_ra_max_steer_angle.get(), -1.f, 1.f); motor_setpoint_temp.throttle = math::constrain(throttle, 0.f, 1.f); @@ -258,8 +258,8 @@ void RoverAckermannGuidance::updateWaypoints() } float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, - const Vector2f &next_wp_ned, const float &default_acceptance_radius, const float &acceptance_radius_gain, - const float &acceptance_radius_max, const float &wheel_base, const float &max_steer_angle) + const Vector2f &next_wp_ned, const float default_acceptance_radius, const float acceptance_radius_gain, + const float acceptance_radius_max, const float wheel_base, const float max_steer_angle) { // Setup variables const Vector2f curr_to_prev_wp_ned = prev_wp_ned - curr_wp_ned; @@ -287,14 +287,12 @@ float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_ned } float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, - const Vector2f &curr_pos_ned, const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, - const float &wheel_base, const float &desired_speed, const float &vehicle_yaw) + const Vector2f &curr_pos_ned, const float wheel_base, const float desired_speed, const float vehicle_yaw) { // Calculate desired steering to reach lookahead point - const float lookahead_distance = math::constrain(lookahead_gain * desired_speed, - lookahead_min, lookahead_max); const float desired_heading = _pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, - lookahead_distance); + desired_speed); + const float lookahead_distance = _pure_pursuit.getLookaheadDistance(); const float heading_error = matrix::wrap_pi(desired_heading - vehicle_yaw); // For logging _rover_ackermann_guidance_status.lookahead_distance = lookahead_distance; diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index 0a73abceb553..592083556f13 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -82,7 +82,7 @@ class RoverAckermannGuidance : public ModuleParams * @brief Compute guidance for ackermann rover and return motor_setpoint for throttle and steering. * @param nav_state Vehicle navigation state */ - motor_setpoint computeGuidance(const int nav_state); + motor_setpoint computeGuidance(int nav_state); /** * @brief Update global/NED waypoint coordinates and acceptance radius @@ -103,24 +103,20 @@ class RoverAckermannGuidance : public ModuleParams * @param max_steer_angle Rover maximum steer angle. */ float updateAcceptanceRadius(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, - const Vector2f &next_wp_ned, const float &default_acceptance_radius, const float &acceptance_radius_gain, - const float &acceptance_radius_max, const float &wheel_base, const float &max_steer_angle); + const Vector2f &next_wp_ned, float default_acceptance_radius, float acceptance_radius_gain, + float acceptance_radius_max, float wheel_base, float max_steer_angle); /** * @brief Calculate and return desired steering input * @param curr_wp_ned Current waypoint in NED frame. * @param prev_wp_ned Previous waypoint in NED frame. * @param curr_pos_ned Current position of the vehicle in NED frame. - * @param lookahead_gain Tuning parameter for the lookahead distance pure pursuit controller. - * @param lookahead_min Minimum lookahead distance. - * @param lookahead_max Maximum lookahead distance. * @param wheel_base Rover wheelbase. * @param desired_speed Desired speed for the rover. * @param vehicle_yaw Current yaw of the rover. */ float calcDesiredSteering(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, - const float &lookahead_gain, const float &lookahead_min, const float &lookahead_max, const float &wheel_base, - const float &desired_speed, const float &vehicle_yaw); + float wheel_base, float desired_speed, float vehicle_yaw); protected: /** @@ -144,14 +140,14 @@ class RoverAckermannGuidance : public ModuleParams MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates. - PurePursuit _pure_pursuit; // Pure pursuit library + PurePursuit _pure_pursuit{this}; // Pure pursuit library // Rover variables Vector2d _curr_pos{}; Vector2f _curr_pos_ned{}; PID_t _pid_throttle; hrt_abstime _timestamp{0}; - float _prev_desired_steering{0.f}; + float _desired_steering{0.f}; // Waypoint variables Vector2d _curr_wp{}; @@ -168,9 +164,6 @@ class RoverAckermannGuidance : public ModuleParams DEFINE_PARAMETERS( (ParamFloat) _param_ra_wheel_base, (ParamFloat) _param_ra_max_steer_angle, - (ParamFloat) _param_ra_lookahd_gain, - (ParamFloat) _param_ra_lookahd_max, - (ParamFloat) _param_ra_lookahd_min, (ParamFloat) _param_ra_acc_rad_max, (ParamFloat) _param_ra_acc_rad_gain, (ParamFloat) _param_ra_miss_vel_def, diff --git a/src/modules/rover_ackermann/module.yaml b/src/modules/rover_ackermann/module.yaml index d8cb88831676..6571d0eeebeb 100644 --- a/src/modules/rover_ackermann/module.yaml +++ b/src/modules/rover_ackermann/module.yaml @@ -27,43 +27,6 @@ parameters: decimal: 2 default: 0.5236 - RA_LOOKAHD_GAIN: - description: - short: Tuning parameter for the pure pursuit controller - long: Lower value -> More aggressive controller (beware overshoot/oscillations) - type: float - min: 0.1 - max: 100 - increment: 0.01 - decimal: 2 - default: 1 - - RA_LOOKAHD_MAX: - description: - short: Maximum lookahead distance for the pure pursuit controller - long: | - This is the maximum crosstrack error before the controller starts - targeting the current waypoint rather then the path between the previous - and next waypoint. - type: float - unit: m - min: 0.1 - max: 100 - increment: 0.01 - decimal: 2 - default: 10 - - RA_LOOKAHD_MIN: - description: - short: Minimum lookahead distance for the pure pursuit controller - type: float - unit: m - min: 0.1 - max: 100 - increment: 0.01 - decimal: 2 - default: 1 - RA_ACC_RAD_MAX: description: short: Maximum acceptance radius for the waypoints From edcda80cb9181bd8b90c8d00f5861287d0d64b9d Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 30 Jul 2024 14:27:27 +0200 Subject: [PATCH 553/652] Commander: adhere to parameter naming convention (#23466) --- src/modules/commander/Commander.cpp | 14 +++++++------- src/modules/commander/Commander.hpp | 6 +++--- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index c4e3d331e45d..2f326deb01ce 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -670,9 +670,9 @@ transition_result_t Commander::disarm(arm_disarm_reason_t calling_reason, bool f } // update flight uuid - const int32_t flight_uuid = _param_flight_uuid.get() + 1; - _param_flight_uuid.set(flight_uuid); - _param_flight_uuid.commit_no_notification(); + const int32_t flight_uuid = _param_com_flight_uuid.get() + 1; + _param_com_flight_uuid.set(flight_uuid); + _param_com_flight_uuid.commit_no_notification(); _status_changed = true; @@ -1991,7 +1991,7 @@ void Commander::checkForMissionUpdate() if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF || _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF) { // Transition mode to loiter or auto-mission after takeoff is completed. - if ((_param_takeoff_finished_action.get() == 1) && auto_mission_available) { + if ((_param_com_takeoff_act.get() == 1) && auto_mission_available) { _user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION); } else { @@ -2236,7 +2236,7 @@ void Commander::handleAutoDisarm() if (isArmed()) { // Check for auto-disarm on landing or pre-flight - if (_param_com_disarm_land.get() > 0 || _param_com_disarm_preflight.get() > 0) { + if (_param_com_disarm_land.get() > 0 || _param_com_disarm_prflt.get() > 0) { const bool landed_amid_mission = (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) && !_mission_result_sub.get().finished; @@ -2247,8 +2247,8 @@ void Commander::handleAutoDisarm() _auto_disarm_landed.set_hysteresis_time_from(false, _param_com_disarm_land.get() * 1_s); _auto_disarm_landed.set_state_and_update(_vehicle_land_detected.landed, hrt_absolute_time()); - } else if (_param_com_disarm_preflight.get() > 0 && !_have_taken_off_since_arming) { - _auto_disarm_landed.set_hysteresis_time_from(false, _param_com_disarm_preflight.get() * 1_s); + } else if (_param_com_disarm_prflt.get() > 0 && !_have_taken_off_since_arming) { + _auto_disarm_landed.set_hysteresis_time_from(false, _param_com_disarm_prflt.get() * 1_s); _auto_disarm_landed.set_state_and_update(true, hrt_absolute_time()); } diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 9431381d8cc4..7453cb2a1b7e 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -332,7 +332,7 @@ class Commander : public ModuleBase, public ModuleParams DEFINE_PARAMETERS( (ParamFloat) _param_com_disarm_land, - (ParamFloat) _param_com_disarm_preflight, + (ParamFloat) _param_com_disarm_prflt, (ParamBool) _param_com_disarm_man, (ParamInt) _param_com_dl_loss_t, (ParamInt) _param_com_hldl_loss_t, @@ -347,8 +347,8 @@ class Commander : public ModuleBase, public ModuleParams (ParamFloat) _param_com_obc_loss_t, (ParamInt) _param_com_prearm_mode, (ParamInt) _param_com_rc_override, - (ParamInt) _param_flight_uuid, - (ParamInt) _param_takeoff_finished_action, + (ParamInt) _param_com_flight_uuid, + (ParamInt) _param_com_takeoff_act, (ParamFloat) _param_com_cpu_max ) }; From 7d79bdfa05b53d4399213be2a4226ff29f4044a5 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 20 Mar 2024 18:41:28 +0100 Subject: [PATCH 554/652] batteryCheck: apply supply circuit breaker also to battery checks This was the case in older versions of PX4. --- .../commander/HealthAndArmingChecks/checks/batteryCheck.cpp | 5 +++++ .../commander/HealthAndArmingChecks/checks/batteryCheck.hpp | 3 ++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index f13977199e7a..70d97c7f2c8c 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -32,6 +32,7 @@ ****************************************************************************/ #include "batteryCheck.hpp" +#include #include @@ -89,6 +90,10 @@ static constexpr const char *battery_mode_str(battery_mode_t battery_mode) void BatteryChecks::checkAndReport(const Context &context, Report &reporter) { + if (circuit_breaker_enabled_by_val(_param_cbrk_supply_chk.get(), CBRK_SUPPLY_CHK_KEY)) { + return; + } + int battery_required_count = 0; bool battery_has_fault = false; // There are possibly multiple batteries, and we can't know which ones serve which purpose. So the safest diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.hpp index 81f1058d3571..64cf1ed5e6ce 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.hpp @@ -57,6 +57,7 @@ class BatteryChecks : public HealthAndArmingCheckBase bool _battery_connected_at_arming[battery_status_s::MAX_INSTANCES] {}; DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, - (ParamFloat) _param_arm_battery_level_min + (ParamFloat) _param_arm_battery_level_min, + (ParamInt) _param_cbrk_supply_chk ) }; From 0d00543292f3cd5b0d37f6f0449f87a4ea55d280 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 17 Jul 2024 15:46:53 +0200 Subject: [PATCH 555/652] batteryCheck: explicitly report missing battery with ID --- .../checks/batteryCheck.cpp | 25 +++++++++++++------ 1 file changed, 18 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index 70d97c7f2c8c..c5e8015413e1 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -94,7 +94,6 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) return; } - int battery_required_count = 0; bool battery_has_fault = false; // There are possibly multiple batteries, and we can't know which ones serve which purpose. So the safest // option is to check if ANY of them have a warning, and specifically find which one has the most @@ -106,6 +105,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) hrt_abstime oldest_update = hrt_absolute_time(); float worst_battery_time_s{NAN}; int num_connected_batteries{0}; + bool is_required_battery_missing{false}; for (auto &battery_sub : _battery_status_subs) { int index = battery_sub.get_instance(); @@ -115,8 +115,18 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) continue; } - if (battery.is_required) { - battery_required_count++; + if (battery.is_required && !battery.connected) { + is_required_battery_missing = true; + /* EVENT + * @description + * Make sure all required batteries are connected. + */ + reporter.healthFailure(NavModes::All, health_component_t::battery, events::ID("check_battery_missing"), + events::Log::Error, "Battery {1} missing", index + 1); + + if (reporter.mavlink_log_pub()) { + mavlink_log_critical(reporter.mavlink_log_pub(), "Battery %i missing\t", index + 1); + } } if (!_last_armed && context.isArmed()) { @@ -259,16 +269,17 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) reporter.failsafeFlags().battery_unhealthy = // All connected batteries are regularly being published hrt_elapsed_time(&oldest_update) > 5_s - // There is at least one connected battery (in any slot) - || num_connected_batteries < battery_required_count + // There is a required battery that's missing + || is_required_battery_missing // No currently-connected batteries have any fault || battery_has_fault || reporter.failsafeFlags().battery_warning == battery_status_s::BATTERY_WARNING_FAILED; - if (reporter.failsafeFlags().battery_unhealthy && !battery_has_fault) { // faults are reported above already + if (reporter.failsafeFlags().battery_unhealthy + && !is_required_battery_missing && !battery_has_fault) { // missing batteries and faults are reported above already /* EVENT * @description - * Make sure all batteries are connected and operational. + * Make sure all batteries are operational. */ reporter.healthFailure(NavModes::All, health_component_t::battery, events::ID("check_battery_unhealthy"), events::Log::Error, "Battery unhealthy"); From e06629bfe5b8bd21d97d8b42dd6c60eb261b2558 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 17 Jul 2024 16:55:36 +0200 Subject: [PATCH 556/652] failsafe: unhealthy battery during spoolup leads to disarm battery failures can occur upon arming when the load gets sgnificant. In that case the safest thing to do is prevent a takeoff before anything worse happens. --- src/modules/commander/failsafe/failsafe.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index 9a9b1e7cad2c..fef6e2136bf3 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -475,7 +475,6 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state, CHECK_FAILSAFE(status_flags, geofence_breached, fromGfActParam(_param_gf_action.get()).cannotBeDeferred()); // Battery flight time remaining failsafe - CHECK_FAILSAFE(status_flags, battery_low_remaining_time, ActionOptions(fromRemainingFlightTimeLowActParam(_param_com_fltt_low_act.get()))); @@ -512,18 +511,19 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state, } - // Failure detector + // Handle fails during spoolup just after arming if ((_armed_time != 0) && (time_us < _armed_time + static_cast(_param_com_spoolup_time.get() * 1_s)) ) { CHECK_FAILSAFE(status_flags, fd_esc_arming_failure, ActionOptions(Action::Disarm).cannotBeDeferred()); + CHECK_FAILSAFE(status_flags, battery_unhealthy, ActionOptions(Action::Disarm).cannotBeDeferred()); } + // Handle fails during the early takeoff phase if ((_armed_time != 0) && (time_us < _armed_time + static_cast((_param_com_lkdown_tko.get() + _param_com_spoolup_time.get()) * 1_s)) ) { - // This handles the case where something fails during the early takeoff phase CHECK_FAILSAFE(status_flags, fd_critical_failure, ActionOptions(Action::Disarm).cannotBeDeferred()); } else if (!circuit_breaker_enabled_by_val(_param_cbrk_flightterm.get(), CBRK_FLIGHTTERM_KEY)) { From 2e66bbdfb8bf0eccdb1155156934c5e18e559f03 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 19 Jul 2024 15:27:16 +0200 Subject: [PATCH 557/652] battery_status: add failed to arm fault instead of duplicate over temperature --- msg/BatteryStatus.msg | 2 +- src/lib/events/enums.json | 6 +++--- .../commander/HealthAndArmingChecks/checks/batteryCheck.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index 00d2efef4c5d..c726051ff911 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -50,7 +50,7 @@ uint8 BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible uint8 BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware uint8 BATTERY_FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system uint8 BATTERY_FAULT_HARDWARE_FAILURE = 9 # hardware problem -uint8 BATTERY_WARNING_OVER_TEMPERATURE = 10 # Over-temperature +uint8 BATTERY_FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element! uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index 8e86170951bf..7076bea8a394 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -631,7 +631,7 @@ "description": "Battery reported over-current" }, "4": { - "name": "fault_temperature", + "name": "over_temperature", "description": "Battery has reached a critical temperature which can result in a critical failure" }, "5": { @@ -655,8 +655,8 @@ "description": "Battery reported an hardware problem" }, "10": { - "name": "over_temperature", - "description": "Battery is over-heating" + "name": "failed_to_arm", + "description": "Battery failed to arm" } } }, diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index c5e8015413e1..f244f10066cb 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -53,7 +53,7 @@ static constexpr const char *battery_fault_reason_str(battery_fault_reason_t bat case battery_fault_reason_t::over_current: return "over current"; - case battery_fault_reason_t::fault_temperature: return "critical temperature"; + case battery_fault_reason_t::over_temperature: return "over temperature"; case battery_fault_reason_t::under_temperature: return "under temperature"; @@ -65,7 +65,7 @@ static constexpr const char *battery_fault_reason_str(battery_fault_reason_t bat case battery_fault_reason_t::hardware_fault: return "hardware fault"; - case battery_fault_reason_t::over_temperature: return "near temperature limit"; + case battery_fault_reason_t::failed_to_arm: return "failed to arm"; } From 72ed160aa91b80c130cbe49208c10d2e749d8d80 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 19 Jul 2024 15:24:20 +0200 Subject: [PATCH 558/652] batteryCheck: fix comment typo hyster{i,e}sis --- .../commander/HealthAndArmingChecks/checks/batteryCheck.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index f244f10066cb..ef3d8c7010c9 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -301,7 +301,7 @@ void BatteryChecks::rtlEstimateCheck(const Context &context, Report &reporter, f rtl_time_estimate_s rtl_time_estimate; // Compare estimate of RTL time to estimate of remaining flight time - // add hysterisis: if already in the condition, only get out of it if the remaining flight time is significantly higher again + // add hysteresis: if already in the condition, only get out of it if the remaining flight time is significantly higher again const float hysteresis_factor = reporter.failsafeFlags().battery_low_remaining_time ? 1.1f : 1.0f; reporter.failsafeFlags().battery_low_remaining_time = _rtl_time_estimate_sub.copy(&rtl_time_estimate) From a18c18e163761f99c15069428461ebb460163676 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 19 Jul 2024 15:29:08 +0200 Subject: [PATCH 559/652] battery_status: remove custom_faults --- msg/BatteryStatus.msg | 1 - .../commander/HealthAndArmingChecks/checks/batteryCheck.cpp | 5 ++--- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index c726051ff911..6c5ce43b5997 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -54,7 +54,6 @@ uint8 BATTERY_FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element! uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. -uint32 custom_faults # Bitmask indicating smart battery internal manufacturer faults, those are not user actionable. uint8 warning # Current battery warning uint8 mode # Battery mode. Note, the normal operation mode diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index ef3d8c7010c9..c51932f2ec42 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -190,11 +190,10 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) /* EVENT * @description * The battery reported a failure which might be dangerous to fly with. - * Manufacturer error code: {4} */ - reporter.healthFailure + reporter.healthFailure (NavModes::All, health_component_t::battery, events::ID("check_battery_fault"), {events::Log::Emergency, events::LogInternal::Warning}, - "Battery {1}: {2}. {3}", index + 1, static_cast(fault_index), action, battery.custom_faults); + "Battery {1}: {2}. {3}", index + 1, static_cast(fault_index), action); if (reporter.mavlink_log_pub()) { mavlink_log_emergency(reporter.mavlink_log_pub(), "Battery %d: %s. %s \t", index + 1, From ba579245fbaa5aa75bfe91850ee9ff1f367f8e45 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 19 Jul 2024 15:32:01 +0200 Subject: [PATCH 560/652] battery_status: remove unused smart battery mode --- msg/BatteryStatus.msg | 7 --- src/lib/events/enums.json | 18 ------- .../checks/batteryCheck.cpp | 50 ++++--------------- .../mavlink/streams/BATTERY_STATUS.hpp | 15 +----- 4 files changed, 10 insertions(+), 80 deletions(-) diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index 6c5ce43b5997..b5155308f229 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -55,13 +55,6 @@ uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element! uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. uint8 warning # Current battery warning -uint8 mode # Battery mode. Note, the normal operation mode - -uint8 BATTERY_MODE_UNKNOWN = 0 # Battery does not support a mode, or if it does, is operational -uint8 BATTERY_MODE_AUTO_DISCHARGING = 1 # Battery is auto discharging (towards storage level) -uint8 BATTERY_MODE_HOT_SWAP = 2 # Battery in hot-swap mode -uint8 BATTERY_MODE_COUNT = 3 # Counter - keep it as last element (once we're fully migrated to events interface we can just comment this)! - uint8 MAX_INSTANCES = 4 diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index 7076bea8a394..1a0817c8adbb 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -660,24 +660,6 @@ } } }, - "battery_mode_t": { - "type": "uint8_t", - "description": "Smart battery modes of operation", - "entries": { - "0": { - "name": "unknown", - "description": "unknown" - }, - "1": { - "name": "autodischarging", - "description": "auto discharging towards storage level" - }, - "2": { - "name": "hotswap", - "description": "hot-swap" - } - } - }, "esc_fault_reason_t": { "type": "uint8_t", "description": "Bitfield for ESC failure reason", diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index c51932f2ec42..5e96c39633fe 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -72,22 +72,6 @@ static constexpr const char *battery_fault_reason_str(battery_fault_reason_t bat return ""; }; - -using battery_mode_t = events::px4::enums::battery_mode_t; -static_assert(battery_status_s::BATTERY_MODE_COUNT == (static_cast(battery_mode_t::_max) + 1) - , "Battery mode flags mismatch!"); -static constexpr const char *battery_mode_str(battery_mode_t battery_mode) -{ - switch (battery_mode) { - case battery_mode_t::autodischarging: return "auto discharging"; - - case battery_mode_t::hotswap: return "hot-swap"; - - default: return "unknown"; - } -} - - void BatteryChecks::checkAndReport(const Context &context, Report &reporter) { if (circuit_breaker_enabled_by_val(_param_cbrk_supply_chk.get(), CBRK_SUPPLY_CHK_KEY)) { @@ -133,34 +117,18 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) _battery_connected_at_arming[index] = battery.connected; } - if (context.isArmed()) { - - if (!battery.connected && _battery_connected_at_arming[index]) { // If disconnected after arming - /* EVENT - */ - reporter.healthFailure(NavModes::All, health_component_t::battery, events::ID("check_battery_disconnected"), - events::Log::Emergency, "Battery {1} disconnected", index + 1); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Battery %i disconnected\t", index + 1); - } + if (context.isArmed() && !battery.connected && _battery_connected_at_arming[index]) { // If disconnected after arming + /* EVENT + */ + reporter.healthFailure(NavModes::All, health_component_t::battery, events::ID("check_battery_disconnected"), + events::Log::Emergency, "Battery {1} disconnected", index + 1); - // trigger a battery failsafe action if a battery disconnects in flight - worst_warning = battery_status_s::BATTERY_WARNING_CRITICAL; + if (reporter.mavlink_log_pub()) { + mavlink_log_critical(reporter.mavlink_log_pub(), "Battery %i disconnected\t", index + 1); } - if (battery.mode != 0) { - /* EVENT - */ - reporter.healthFailure(NavModes::All, health_component_t::battery, - events::ID("check_battery_mode"), - events::Log::Critical, "Battery {1} mode: {2}", index + 1, static_cast(battery.mode)); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Battery %d is in %s mode!\t", index + 1, - battery_mode_str(static_cast(battery.mode))); - } - } + // trigger a battery failsafe action if a battery disconnects in flight + worst_warning = battery_status_s::BATTERY_WARNING_CRITICAL; } if (battery.connected) { diff --git a/src/modules/mavlink/streams/BATTERY_STATUS.hpp b/src/modules/mavlink/streams/BATTERY_STATUS.hpp index c3d15054ac2f..633807a86e62 100644 --- a/src/modules/mavlink/streams/BATTERY_STATUS.hpp +++ b/src/modules/mavlink/streams/BATTERY_STATUS.hpp @@ -114,20 +114,7 @@ class MavlinkStreamBatteryStatus : public MavlinkStream break; } - switch (battery_status.mode) { - case (battery_status_s::BATTERY_MODE_AUTO_DISCHARGING): - bat_msg.mode = MAV_BATTERY_MODE_AUTO_DISCHARGING; - break; - - case (battery_status_s::BATTERY_MODE_HOT_SWAP): - bat_msg.mode = MAV_BATTERY_MODE_HOT_SWAP; - break; - - default: - bat_msg.mode = MAV_BATTERY_MODE_UNKNOWN; - break; - } - + bat_msg.mode = MAV_BATTERY_MODE_UNKNOWN; bat_msg.fault_bitmask = battery_status.faults; // check if temperature valid From 9ca9ae5b24772794edb129627dd4bc1b413ef08c Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Mon, 29 Jul 2024 17:19:44 +0200 Subject: [PATCH 561/652] battery: fix initialization for internal resistance estimation Don't run/initialize if number of battery cells is zero and reinitialize whenever this parameter changes. --- src/lib/battery/battery.cpp | 34 +++++++++++++++++++++------------- src/lib/battery/battery.h | 1 + 2 files changed, 22 insertions(+), 13 deletions(-) diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index 302cbca05698..4d4715a0d529 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -94,16 +94,6 @@ Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us, _param_handles.bat_avrg_current = param_find("BAT_AVRG_CURRENT"); updateParams(); - - // Internal resistance estimation initializations - _RLS_est(0) = OCV_DEFAULT * _params.n_cells; - _RLS_est(1) = R_DEFAULT * _params.n_cells; - _estimation_covariance(0, 0) = OCV_COVARIANCE * _params.n_cells; - _estimation_covariance(0, 1) = 0.f; - _estimation_covariance(1, 0) = 0.f; - _estimation_covariance(1, 1) = R_COVARIANCE * _params.n_cells; - _estimation_covariance_norm = sqrtf(powf(_estimation_covariance(0, 0), 2.f) + 2.f * powf(_estimation_covariance(1, 0), - 2.f) + powf(_estimation_covariance(1, 1), 2.f)); } void Battery::updateVoltage(const float voltage_v) @@ -118,7 +108,7 @@ void Battery::updateCurrent(const float current_a) void Battery::updateBatteryStatus(const hrt_abstime ×tamp) { - if (!_battery_initialized) { + if (!_battery_initialized && _internal_resistance_initialized && _params.n_cells > 0) { resetInternalResistanceEstimation(_voltage_v, _current_a); } @@ -172,8 +162,9 @@ battery_status_s Battery::getBatteryStatus() battery_status.internal_resistance_estimate = _internal_resistance_estimate; battery_status.ocv_estimate = _voltage_v + _internal_resistance_estimate * _params.n_cells * _current_a; battery_status.ocv_estimate_filtered = _ocv_filter_v.getState(); - battery_status.volt_based_soc_estimate = math::interpolate(_ocv_filter_v.getState() / _params.n_cells, - _params.v_empty, _params.v_charged, 0.f, 1.f); + battery_status.volt_based_soc_estimate = _params.n_cells > 0 ? math::interpolate(_ocv_filter_v.getState() / + _params.n_cells, + _params.v_empty, _params.v_charged, 0.f, 1.f) : -1.f; battery_status.voltage_prediction = _voltage_prediction; battery_status.prediction_error = _prediction_error; battery_status.estimation_covariance_norm = _estimation_covariance_norm; @@ -397,6 +388,7 @@ float Battery::computeRemainingTime(float current_a) void Battery::updateParams() { + const int n_cells = _first_parameter_update ? 0 : _params.n_cells; param_get(_param_handles.v_empty, &_params.v_empty); param_get(_param_handles.v_charged, &_params.v_charged); param_get(_param_handles.n_cells, &_params.n_cells); @@ -408,6 +400,22 @@ void Battery::updateParams() param_get(_param_handles.emergen_thr, &_params.emergen_thr); param_get(_param_handles.bat_avrg_current, &_params.bat_avrg_current); + if (n_cells != _params.n_cells) { + _internal_resistance_initialized = false; + } + + if (!_internal_resistance_initialized && _params.n_cells > 0) { + _RLS_est(0) = OCV_DEFAULT * _params.n_cells; + _RLS_est(1) = R_DEFAULT * _params.n_cells; + _estimation_covariance(0, 0) = OCV_COVARIANCE * _params.n_cells; + _estimation_covariance(0, 1) = 0.f; + _estimation_covariance(1, 0) = 0.f; + _estimation_covariance(1, 1) = R_COVARIANCE * _params.n_cells; + _estimation_covariance_norm = sqrtf(powf(_estimation_covariance(0, 0), 2.f) + 2.f * powf(_estimation_covariance(1, 0), + 2.f) + powf(_estimation_covariance(1, 1), 2.f)); + _internal_resistance_initialized = true; + } + ModuleParams::updateParams(); _first_parameter_update = false; diff --git a/src/lib/battery/battery.h b/src/lib/battery/battery.h index 9d24b7bd4448..04d018960256 100644 --- a/src/lib/battery/battery.h +++ b/src/lib/battery/battery.h @@ -184,6 +184,7 @@ class Battery : public ModuleParams void resetInternalResistanceEstimation(const float voltage_v, const float current_a); matrix::Vector2f _RLS_est; // [Open circuit voltage estimate [V], Total internal resistance estimate [Ohm]]^T matrix::Matrix2f _estimation_covariance; + bool _internal_resistance_initialized{false}; float _estimation_covariance_norm{0.f}; float _internal_resistance_estimate{0.005f}; // [Ohm] Per cell estimate of the internal resistance float _voltage_prediction{0.f}; // [V] Predicted voltage of the estimator From e5657ba011251108d116ad2992d58435899af4af Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 30 Jul 2024 10:57:08 +0200 Subject: [PATCH 562/652] battery: remove reboot required flag from BAT_N_CELLS --- src/lib/battery/module.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/src/lib/battery/module.yaml b/src/lib/battery/module.yaml index e784923250a5..b20900fa08d4 100644 --- a/src/lib/battery/module.yaml +++ b/src/lib/battery/module.yaml @@ -81,7 +81,6 @@ parameters: 14: 14S Battery 15: 15S Battery 16: 16S Battery - reboot_required: true num_instances: *max_num_config_instances instance_start: 1 default: [0, 0, 0] From b74e46b1acd7963ca51e4031d7a5dcfafd0f5b57 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Jul 2024 09:27:16 +0200 Subject: [PATCH 563/652] SITL airframes/Navigator: remvoe reference to removed param MIS_LTRMIN_ALT Signed-off-by: Silvan Fuhrer --- .../init.d-posix/airframes/1031_gazebo-classic_plane_cam | 1 - .../init.d-posix/airframes/1032_gazebo-classic_plane_catapult | 1 - .../init.d-posix/airframes/1038_gazebo-classic_glider | 1 - .../init.d-posix/airframes/1039_flightgear_rascal | 1 - .../init.d-posix/airframes/1044_gazebo-classic_plane_lidar | 1 - src/modules/navigator/rtl_direct_mission_land.cpp | 3 +-- 6 files changed, 1 insertion(+), 7 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1031_gazebo-classic_plane_cam b/ROMFS/px4fmu_common/init.d-posix/airframes/1031_gazebo-classic_plane_cam index 3dc3c9ee1a54..695f851ff08e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1031_gazebo-classic_plane_cam +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1031_gazebo-classic_plane_cam @@ -39,7 +39,6 @@ param set-default FW_T_SINK_MIN 2.2 param set-default FW_W_EN 1 -param set-default MIS_LTRMIN_ALT 30 param set-default MIS_TAKEOFF_ALT 30 param set-default NAV_ACC_RAD 15 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult b/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult index 7963669c858a..12e828c08c66 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1032_gazebo-classic_plane_catapult @@ -41,7 +41,6 @@ param set-default FW_T_SINK_MIN 2.2 param set-default FW_W_EN 1 -param set-default MIS_LTRMIN_ALT 30 param set-default MIS_TAKEOFF_ALT 30 param set-default NAV_ACC_RAD 15 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1038_gazebo-classic_glider b/ROMFS/px4fmu_common/init.d-posix/airframes/1038_gazebo-classic_glider index d5b59f700792..ef2cd026061e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1038_gazebo-classic_glider +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1038_gazebo-classic_glider @@ -39,7 +39,6 @@ param set-default FW_T_SINK_MIN 2.2 param set-default FW_W_EN 1 -param set-default MIS_LTRMIN_ALT 30 param set-default MIS_TAKEOFF_ALT 30 param set-default NAV_ACC_RAD 15 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal b/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal index 487a1729c801..544fd746e100 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1039_flightgear_rascal @@ -23,7 +23,6 @@ param set-default FW_RR_P 0.085 param set-default FW_W_EN 1 -param set-default MIS_LTRMIN_ALT 30 param set-default MIS_TAKEOFF_ALT 20 param set-default NAV_ACC_RAD 15 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1044_gazebo-classic_plane_lidar b/ROMFS/px4fmu_common/init.d-posix/airframes/1044_gazebo-classic_plane_lidar index 22d7e21119ee..23b7757d4bcd 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1044_gazebo-classic_plane_lidar +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1044_gazebo-classic_plane_lidar @@ -39,7 +39,6 @@ param set-default FW_T_SINK_MIN 2.2 param set-default FW_W_EN 1 -param set-default MIS_LTRMIN_ALT 30 param set-default MIS_TAKEOFF_ALT 30 param set-default NAV_ACC_RAD 15 diff --git a/src/modules/navigator/rtl_direct_mission_land.cpp b/src/modules/navigator/rtl_direct_mission_land.cpp index df6674e34ad8..5f55b92affd8 100644 --- a/src/modules/navigator/rtl_direct_mission_land.cpp +++ b/src/modules/navigator/rtl_direct_mission_land.cpp @@ -125,8 +125,7 @@ void RtlDirectMissionLand::setActiveMissionItems() // Climb to altitude if (_needs_climbing && _work_item_type == WorkItemType::WORK_ITEM_TYPE_DEFAULT) { - // do not use LOITER_TO_ALT for rotary wing mode as it would then always climb to at least MIS_LTRMIN_ALT, - // even if current climb altitude is below (e.g. RTL immediately after take off) + // TODO: check if we also should use NAV_CMD_LOITER_TO_ALT for rotary wing if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) { _mission_item.nav_cmd = NAV_CMD_WAYPOINT; From 75ce550db39cc5d61ba970ca5f4b6096a287827e Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 19 Jul 2024 11:25:56 +0200 Subject: [PATCH 564/652] Navigator: add terrain collision avoidance logic for Mission/RTL Avoid flying into terrain using the distance sensor. Enable through the parameter NAV_MIN_GND_DIST. Only active during commanded descents with vz>0 (to prevent climb-aways), excluding landing and VTOL transitions. It changes the altitude setpoint in the triplet to maintain the current altitude and republish the triplet. We also change the mission item altitude used for acceptance calculations to prevent getting stuck in a loop. Signed-off-by: Silvan Fuhrer --- src/modules/navigator/mission_base.cpp | 2 ++ src/modules/navigator/mission_block.cpp | 31 ++++++++++++++++++++++++ src/modules/navigator/mission_block.h | 1 + src/modules/navigator/navigator.h | 5 ++++ src/modules/navigator/navigator_main.cpp | 7 ++++++ src/modules/navigator/navigator_params.c | 18 ++++++++++++++ src/modules/navigator/rtl_direct.cpp | 5 ++++ 7 files changed, 69 insertions(+) diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index 595f548c8357..0a9a76bd2b34 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -352,6 +352,8 @@ MissionBase::on_active() } else if (_navigator->get_precland()->is_activated()) { _navigator->get_precland()->on_inactivation(); } + + updateAltToAvoidTerrainCollisionAndRepublishTriplet(_mission_item); } void MissionBase::update_mission() diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index 17dd3e620ca2..1f0c9f0dd021 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -1011,3 +1011,34 @@ void MissionBlock::startPrecLand(uint16_t land_precision) _navigator->get_precland()->on_activation(); } } + +void MissionBlock::updateAltToAvoidTerrainCollisionAndRepublishTriplet(mission_item_s mission_item) +{ + // Avoid flying into terrain using the distance sensor. Enable through the parameter NAV_MIN_GND_DIST. + // Only active during commanded descents with vz>0 (to prevent climb-aways), excluding landing and VTOL transitions. + // It changes the altitude setpoint in the triplet to maintain the current altitude and republish the triplet. + // We also change the mission item altitude used for acceptance calculations to prevent getting stuck in a loop. + + // This threshold is needed to prevent the check from re-triggering due to small altitude over-shoots while + // tracking the new altitude setpoint. + static constexpr float kAltitudeDifferenceForDescentCondition = 2.f; + + + if (_navigator->get_nav_min_gnd_dist_param() > FLT_EPSILON && _mission_item.nav_cmd != NAV_CMD_LAND + && _mission_item.nav_cmd != NAV_CMD_VTOL_LAND && _mission_item.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION + && _navigator->get_local_position()->dist_bottom_valid + && _navigator->get_local_position()->dist_bottom < _navigator->get_nav_min_gnd_dist_param() + && _navigator->get_local_position()->vz > FLT_EPSILON + && _navigator->get_global_position()->alt - get_absolute_altitude_for_item(mission_item) > + kAltitudeDifferenceForDescentCondition) { + + _navigator->sendWarningDescentStoppedDueToTerrain(); + + struct position_setpoint_s *curr_sp = &_navigator->get_position_setpoint_triplet()->current; + curr_sp->alt = _navigator->get_global_position()->alt; + _navigator->set_position_setpoint_triplet_updated(); + + _mission_item.altitude = _navigator->get_global_position()->alt; + _mission_item.altitude_is_relative = false; + } +} diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h index b97731567a29..13815b860211 100644 --- a/src/modules/navigator/mission_block.h +++ b/src/modules/navigator/mission_block.h @@ -215,6 +215,7 @@ class MissionBlock : public NavigatorMode void setLandMissionItem(mission_item_s &item, const PositionYawSetpoint &pos_yaw_sp) const; void startPrecLand(uint16_t land_precision); + void updateAltToAvoidTerrainCollisionAndRepublishTriplet(mission_item_s mission_item); /** * @brief Issue a command for mission items with a nav_cmd that specifies an action diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 03a1ea621e89..93f630dbf525 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -268,6 +268,7 @@ class Navigator : public ModuleBase, public ModuleParams float get_param_mis_takeoff_alt() const { return _param_mis_takeoff_alt.get(); } float get_yaw_timeout() const { return _param_mis_yaw_tmt.get(); } float get_yaw_threshold() const { return math::radians(_param_mis_yaw_err.get()); } + float get_nav_min_gnd_dist_param() const { return _param_nav_min_gnd_dist.get(); } float get_vtol_back_trans_deceleration() const { return _param_back_trans_dec_mss; } @@ -284,6 +285,8 @@ class Navigator : public ModuleBase, public ModuleParams void mode_completed(uint8_t nav_state, uint8_t result = mode_completed_s::RESULT_SUCCESS); + void sendWarningDescentStoppedDueToTerrain(); + private: int _local_pos_sub{-1}; @@ -402,6 +405,8 @@ class Navigator : public ModuleBase, public ModuleParams (ParamFloat) _param_nav_traff_a_ver, /**< avoidance Distance Vertical*/ (ParamInt) _param_nav_traff_collision_time, (ParamFloat) _param_min_ltr_alt, /**< minimum altitude in Loiter mode*/ + (ParamFloat) + _param_nav_min_gnd_dist, /**< minimum distance to ground (Mission and RTL)*/ // non-navigator parameters: Mission (MIS_*) (ParamFloat) _param_mis_takeoff_alt, diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 434be34e7739..f2694b595ab7 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1522,6 +1522,13 @@ void Navigator::set_gimbal_neutral() publish_vehicle_cmd(&vcmd); } +void Navigator::sendWarningDescentStoppedDueToTerrain() +{ + mavlink_log_critical(&_mavlink_log_pub, "Terrain collision risk, descent is stopped\t"); + events::send(events::ID("navigator_terrain_collision_risk"), events::Log::Critical, + "Terrain collision risk, descent is stopped"); +} + int Navigator::print_usage(const char *reason) { if (reason) { diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index c300c8e3c848..325b19abf605 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -187,3 +187,21 @@ PARAM_DEFINE_INT32(NAV_FORCE_VT, 1); * @group Mission */ PARAM_DEFINE_FLOAT(NAV_MIN_LTR_ALT, -1.f); + +/** + * Minimum height above ground during Mission and RTL + * + * Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, + * excluding landing commands. + * Requires a distance sensor to be set up. + * Note: only prevents the vehicle from descending further, but does not force it to climb. + * + * Set to a negative value to disable. + * + * @unit m + * @min -1 + * @decimal 1 + * @increment 1 + * @group Mission + */ +PARAM_DEFINE_FLOAT(NAV_MIN_GND_DIST, -1.f); diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index d2936986db9a..b028c7fb358f 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -104,6 +104,11 @@ void RtlDirect::on_active() set_rtl_item(); } + if (_rtl_state == RTLState::LOITER_HOLD) { //TODO: rename _rtl_state to _rtl_state_next + //check for terrain collision and update altitude if needed + updateAltToAvoidTerrainCollisionAndRepublishTriplet(_mission_item); + } + if (_rtl_state == RTLState::LAND && _param_rtl_pld_md.get() > 0) { // Need to update the position and type on the current setpoint triplet. _navigator->get_precland()->on_active(); From abc629c2bbc30a4f1d93ca9e2c1b7245574452fc Mon Sep 17 00:00:00 2001 From: Alexis Paques <6976744+AlexisTM@users.noreply.github.com> Date: Fri, 2 Aug 2024 17:48:55 +0200 Subject: [PATCH 565/652] zenoh: update zenoh-pico from 0.7.0 to 1.0.0 (#23462) * Update Zenoh-pico from 0.7.0 to 1.0.0 * Update the zenoh-pico version to use PX4/dev/1.0.0-px4 * Remove the rostopic and rt/ prefix * Unlike zenoh-bridge-dds we were using, zenoh-bridge-ros2dds is now adding the rt/ prefix automagically. --- .gitmodules | 2 +- boards/px4/fmu-v6x/nuttx-config/nsh/defconfig | 1 + src/modules/zenoh/CMakeLists.txt | 3 +- src/modules/zenoh/Kconfig.topics | 5 +++ .../zenoh/publishers/uorb_publisher.hpp | 2 +- .../zenoh/publishers/zenoh_publisher.cpp | 33 +++++++-------- .../zenoh/publishers/zenoh_publisher.hpp | 10 +---- .../zenoh/subscribers/uorb_subscriber.hpp | 9 ++-- .../zenoh/subscribers/zenoh_subscriber.cpp | 39 ++++++++--------- .../zenoh/subscribers/zenoh_subscriber.hpp | 12 ++---- src/modules/zenoh/zenoh-pico | 2 +- src/modules/zenoh/zenoh.cpp | 42 ++++++++++++------- 12 files changed, 81 insertions(+), 79 deletions(-) diff --git a/.gitmodules b/.gitmodules index e443da19a290..a783b1693843 100644 --- a/.gitmodules +++ b/.gitmodules @@ -71,7 +71,7 @@ [submodule "src/modules/zenoh/zenoh-pico"] path = src/modules/zenoh/zenoh-pico url = https://github.com/px4/zenoh-pico - branch = pr-zubf-werror-fix + branch = dev/1.0.0-px4 [submodule "src/lib/heatshrink/heatshrink"] path = src/lib/heatshrink/heatshrink url = https://github.com/PX4/heatshrink.git diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index 333609282e00..ec6b1c7e2b0e 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -93,6 +93,7 @@ CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 CONFIG_DEV_PIPE_MAXSIZE=1024 CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DEV_URANDOM=y CONFIG_ETH0_PHY_LAN8742A=y CONFIG_EXPERIMENTAL=y CONFIG_FAT_DMAMEMORY=y diff --git a/src/modules/zenoh/CMakeLists.txt b/src/modules/zenoh/CMakeLists.txt index 889a1994a427..e3a8166dff73 100644 --- a/src/modules/zenoh/CMakeLists.txt +++ b/src/modules/zenoh/CMakeLists.txt @@ -57,6 +57,7 @@ target_compile_options(zenohpico PUBLIC -Wno-cast-align -DZ_BATCH_SIZE_TX=512 -DZ_FRAG_MAX_SIZE=1024) +target_compile_options(zenohpico PRIVATE -Wno-missing-prototypes) if(CONFIG_PLATFORM_NUTTX) target_compile_options(zenohpico PRIVATE -DUNIX_NO_MULTICAST_IF) endif() @@ -72,7 +73,6 @@ px4_add_module( SRCS zenoh.cpp zenoh_config.cpp - zenoh.h publishers/zenoh_publisher.cpp subscribers/zenoh_subscriber.cpp MODULE_CONFIG @@ -96,6 +96,5 @@ px4_add_module( -Wno-double-promotion -Wno-unused -DZENOH_LINUX - -DZENOH_NO_STDATOMIC -D_Bool=int8_t ) diff --git a/src/modules/zenoh/Kconfig.topics b/src/modules/zenoh/Kconfig.topics index e1c2ea4ada5b..ee9fe7ce7362 100644 --- a/src/modules/zenoh/Kconfig.topics +++ b/src/modules/zenoh/Kconfig.topics @@ -573,6 +573,10 @@ menu "Zenoh publishers/subscribers" bool "rover_ackermann_guidance_status" default n + config ZENOH_PUBSUB_ROVER_ACKERMANN_STATUS + bool "rover_ackermann_status" + default n + config ZENOH_PUBSUB_RPM bool "rpm" default n @@ -1009,6 +1013,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REPLY select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REQUEST select ZENOH_PUBSUB_ROVER_ACKERMANN_GUIDANCE_STATUS + select ZENOH_PUBSUB_ROVER_ACKERMANN_STATUS select ZENOH_PUBSUB_RPM select ZENOH_PUBSUB_RTL_STATUS select ZENOH_PUBSUB_RTL_TIME_ESTIMATE diff --git a/src/modules/zenoh/publishers/uorb_publisher.hpp b/src/modules/zenoh/publishers/uorb_publisher.hpp index b541bfd1dd7c..fd41e4f2e88c 100644 --- a/src/modules/zenoh/publishers/uorb_publisher.hpp +++ b/src/modules/zenoh/publishers/uorb_publisher.hpp @@ -51,7 +51,7 @@ class uORB_Zenoh_Publisher : public Zenoh_Publisher { public: uORB_Zenoh_Publisher(const orb_metadata *meta, const uint32_t *ops) : - Zenoh_Publisher(true), + Zenoh_Publisher(), _uorb_meta{meta}, _cdr_ops(ops) { diff --git a/src/modules/zenoh/publishers/zenoh_publisher.cpp b/src/modules/zenoh/publishers/zenoh_publisher.cpp index 1e312ffea502..8ce688d2b787 100644 --- a/src/modules/zenoh/publishers/zenoh_publisher.cpp +++ b/src/modules/zenoh/publishers/zenoh_publisher.cpp @@ -42,9 +42,8 @@ #include "zenoh_publisher.hpp" -Zenoh_Publisher::Zenoh_Publisher(bool rostopic) +Zenoh_Publisher::Zenoh_Publisher() { - this->_rostopic = rostopic; this->_topic[0] = 0x0; } @@ -59,24 +58,18 @@ int Zenoh_Publisher::undeclare_publisher() return 0; } -int Zenoh_Publisher::declare_publisher(z_session_t s, const char *keyexpr) +int Zenoh_Publisher::declare_publisher(z_owned_session_t s, const char *keyexpr) { - if (_rostopic) { - strncpy(this->_topic, (char *)_rt_prefix, _rt_prefix_offset); + strncpy(this->_topic, keyexpr, sizeof(this->_topic)); - if (keyexpr[0] == '/') { - strncpy(this->_topic + _rt_prefix_offset, keyexpr + 1, sizeof(this->_topic) - _rt_prefix_offset); + z_view_keyexpr_t ke; + z_view_keyexpr_from_str(&ke, this->_topic); - } else { - strncpy(this->_topic + _rt_prefix_offset, keyexpr, sizeof(this->_topic) - _rt_prefix_offset); - } - - } else { - strncpy(this->_topic, keyexpr, sizeof(this->_topic)); + if (z_declare_publisher(&_pub, z_loan(s), z_loan(ke), NULL) < 0) { + printf("Unable to declare publisher for key expression!\n"); + return -1; } - _pub = z_declare_publisher(s, z_keyexpr(this->_topic), NULL); - if (!z_publisher_check(&_pub)) { printf("Unable to declare publisher for key expression!\n"); return -1; @@ -87,9 +80,13 @@ int Zenoh_Publisher::declare_publisher(z_session_t s, const char *keyexpr) int8_t Zenoh_Publisher::publish(const uint8_t *buf, int size) { - z_publisher_put_options_t options = z_publisher_put_options_default(); - options.encoding = z_encoding(Z_ENCODING_PREFIX_APP_CUSTOM, NULL); - return z_publisher_put(z_publisher_loan(&_pub), buf, size, &options); + z_publisher_put_options_t options; + z_publisher_put_options_default(&options); + options.encoding = NULL; + + z_owned_bytes_t payload; + z_bytes_serialize_from_slice(&payload, buf, size); + return z_publisher_put(z_loan(_pub), z_move(payload), &options); } void Zenoh_Publisher::print() diff --git a/src/modules/zenoh/publishers/zenoh_publisher.hpp b/src/modules/zenoh/publishers/zenoh_publisher.hpp index 1d88a453e2f7..a12849c78682 100644 --- a/src/modules/zenoh/publishers/zenoh_publisher.hpp +++ b/src/modules/zenoh/publishers/zenoh_publisher.hpp @@ -51,10 +51,10 @@ class Zenoh_Publisher : public ListNode { public: - Zenoh_Publisher(bool rostopic = true); + Zenoh_Publisher(); virtual ~Zenoh_Publisher(); - virtual int declare_publisher(z_session_t s, const char *keyexpr); + virtual int declare_publisher(z_owned_session_t s, const char *keyexpr); virtual int undeclare_publisher(); @@ -66,11 +66,5 @@ class Zenoh_Publisher : public ListNode int8_t publish(const uint8_t *, int size); z_owned_publisher_t _pub; - char _topic[60]; // The Topic name is somewhere is the Zenoh stack as well but no good api to fetch it. - - // Indicates ROS2 Topic namespace - bool _rostopic; - const char *_rt_prefix = "rt/"; - const size_t _rt_prefix_offset = 3; // "rt/" are 3 chars }; diff --git a/src/modules/zenoh/subscribers/uorb_subscriber.hpp b/src/modules/zenoh/subscribers/uorb_subscriber.hpp index 550c1a3f4584..bd59adb84606 100644 --- a/src/modules/zenoh/subscribers/uorb_subscriber.hpp +++ b/src/modules/zenoh/subscribers/uorb_subscriber.hpp @@ -50,7 +50,7 @@ class uORB_Zenoh_Subscriber : public Zenoh_Subscriber { public: uORB_Zenoh_Subscriber(const orb_metadata *meta, const uint32_t *ops) : - Zenoh_Subscriber(true), + Zenoh_Subscriber(), _uorb_meta{meta}, _cdr_ops(ops) { @@ -61,11 +61,14 @@ class uORB_Zenoh_Subscriber : public Zenoh_Subscriber ~uORB_Zenoh_Subscriber() override = default; // Update the uORB Subscription and broadcast a Zenoh ROS2 message - void data_handler(const z_sample_t *sample) + void data_handler(const z_loaned_sample_t *sample) { char data[_uorb_meta->o_size]; - dds_istream_t is = {.m_buffer = (unsigned char *)(sample->payload.start), .m_size = static_cast(sample->payload.len), + const z_loaned_bytes_t *payload = z_sample_payload(sample); + size_t len = z_bytes_len(payload); + + dds_istream_t is = {.m_buffer = (unsigned char *)(payload), .m_size = static_cast(len), .m_index = 4, .m_xcdr_version = DDSI_RTPS_CDR_ENC_VERSION_2 }; dds_stream_read(&is, data, &dds_allocator, _cdr_ops); diff --git a/src/modules/zenoh/subscribers/zenoh_subscriber.cpp b/src/modules/zenoh/subscribers/zenoh_subscriber.cpp index aab66ee5bdba..79f37d89812a 100644 --- a/src/modules/zenoh/subscribers/zenoh_subscriber.cpp +++ b/src/modules/zenoh/subscribers/zenoh_subscriber.cpp @@ -41,22 +41,23 @@ #include "zenoh_subscriber.hpp" -static void data_handler_cb(const z_sample_t *sample, void *arg) +static void data_handler_cb(const z_loaned_sample_t *sample, void *arg) { static_cast(arg)->data_handler(sample); } -void Zenoh_Subscriber::data_handler(const z_sample_t *sample) +void Zenoh_Subscriber::data_handler(const z_loaned_sample_t *sample) { - z_owned_str_t keystr = z_keyexpr_to_string(sample->keyexpr); - printf(">> [Subscriber] Received ('%s' size '%d')\n", z_str_loan(&keystr), (int)sample->payload.len); - z_str_drop(z_str_move(&keystr)); + z_view_string_t keystr; + z_keyexpr_as_view_string(z_sample_keyexpr(sample), &keystr); + z_owned_slice_t value; + z_bytes_deserialize_into_slice(z_sample_payload(sample), &value); + printf(">> [Subscriber] Received ('%s' size '%d')\n", z_string_data(z_loan(keystr)), (int)z_slice_len(z_loan(value))); } -Zenoh_Subscriber::Zenoh_Subscriber(bool rostopic) +Zenoh_Subscriber::Zenoh_Subscriber() { - this->_rostopic = rostopic; this->_topic[0] = 0x0; } @@ -71,27 +72,21 @@ int Zenoh_Subscriber::undeclare_subscriber() return 0; } -int Zenoh_Subscriber::declare_subscriber(z_session_t s, const char *keyexpr) +int Zenoh_Subscriber::declare_subscriber(z_owned_session_t s, const char *keyexpr) { - z_owned_closure_sample_t callback = z_closure_sample(data_handler_cb, NULL, this); + z_owned_closure_sample_t callback; + z_closure_sample(&callback, data_handler_cb, NULL, this); - if (_rostopic) { - strncpy(this->_topic, (char *)_rt_prefix, _rt_prefix_offset); + strncpy(this->_topic, keyexpr, sizeof(this->_topic)); - if (keyexpr[0] == '/') { - strncpy(this->_topic + _rt_prefix_offset, keyexpr + 1, sizeof(this->_topic) - _rt_prefix_offset); + z_view_keyexpr_t ke; + z_view_keyexpr_from_str(&ke, this->_topic); - } else { - strncpy(this->_topic + _rt_prefix_offset, keyexpr, sizeof(this->_topic) - _rt_prefix_offset); - } - - } else { - strncpy(this->_topic, (char *)keyexpr, sizeof(this->_topic)); + if (z_declare_subscriber(&_sub, z_loan(s), z_loan(ke), z_closure_sample_move(&callback), NULL) < 0) { + printf("Unable to declare subscriber.\n"); + exit(-1); } - _sub = z_declare_subscriber(s, z_keyexpr(this->_topic), z_closure_sample_move(&callback), NULL); - - if (!z_subscriber_check(&_sub)) { printf("Unable to declare subscriber for key expression!\n %s\n", keyexpr); return -1; diff --git a/src/modules/zenoh/subscribers/zenoh_subscriber.hpp b/src/modules/zenoh/subscribers/zenoh_subscriber.hpp index e3f1200e9245..1b6d10922045 100644 --- a/src/modules/zenoh/subscribers/zenoh_subscriber.hpp +++ b/src/modules/zenoh/subscribers/zenoh_subscriber.hpp @@ -55,14 +55,14 @@ class Zenoh_Subscriber : public ListNode { public: - Zenoh_Subscriber(bool rostopic = true); + Zenoh_Subscriber(); virtual ~Zenoh_Subscriber(); - virtual int declare_subscriber(z_session_t s, const char *keyexpr); + virtual int declare_subscriber(z_owned_session_t s, const char *keyexpr); virtual int undeclare_subscriber(); - virtual void data_handler(const z_sample_t *sample); + virtual void data_handler(const z_loaned_sample_t *sample); virtual void print(); @@ -71,10 +71,4 @@ class Zenoh_Subscriber : public ListNode z_owned_subscriber_t _sub; char _topic[60]; // The Topic name is somewhere is the Zenoh stack as well but no good api to fetch it. - - - // Indicates ROS2 Topic namespace - bool _rostopic; - const char *_rt_prefix = "rt/"; - const size_t _rt_prefix_offset = 3; // "rt/" are 3 chars }; diff --git a/src/modules/zenoh/zenoh-pico b/src/modules/zenoh/zenoh-pico index 22bbfc215092..fff1a8c168e1 160000 --- a/src/modules/zenoh/zenoh-pico +++ b/src/modules/zenoh/zenoh-pico @@ -1 +1 @@ -Subproject commit 22bbfc215092a051341c234fdcf68f5baa267dec +Subproject commit fff1a8c168e10d4ed9cbf2aa7d67ede07f239c52 diff --git a/src/modules/zenoh/zenoh.cpp b/src/modules/zenoh/zenoh.cpp index 0caf2c5eaa5f..6411734a2918 100644 --- a/src/modules/zenoh/zenoh.cpp +++ b/src/modules/zenoh/zenoh.cpp @@ -32,6 +32,8 @@ ****************************************************************************/ #include "zenoh.h" +#include "zenoh-pico/api/macros.h" +#include "zenoh-pico/api/primitives.h" #include #include #include @@ -78,27 +80,39 @@ void ZENOH::run() z_config.getNetworkConfig(mode, locator); - z_owned_config_t config = z_config_default(); - zp_config_insert(z_config_loan(&config), Z_CONFIG_MODE_KEY, z_string_make(mode)); + z_owned_config_t config; + z_config_default(&config); + zp_config_insert(z_loan_mut(config), Z_CONFIG_MODE_KEY, mode); if (locator[0] != 0) { - zp_config_insert(z_config_loan(&config), Z_CONFIG_PEER_KEY, z_string_make(locator)); + zp_config_insert(z_loan_mut(config), Z_CONFIG_CONNECT_KEY, locator); } else if (strcmp(Z_CONFIG_MODE_PEER, mode) == 0) { - zp_config_insert(z_config_loan(&config), Z_CONFIG_PEER_KEY, z_string_make(Z_CONFIG_MULTICAST_LOCATOR_DEFAULT)); + zp_config_insert(z_loan_mut(config), Z_CONFIG_CONNECT_KEY, Z_CONFIG_MULTICAST_LOCATOR_DEFAULT); } PX4_INFO("Opening session..."); - z_owned_session_t s = z_open(z_config_move(&config)); + z_owned_session_t s; + ret = z_open(&s, z_move(config)); + + if (ret < 0) { + PX4_ERR("Unable to open session, ret: %d", ret); + return; + } + + PX4_INFO("Checking session..."); if (!z_session_check(&s)) { - PX4_ERR("Unable to open session!"); + PX4_ERR("Unable to check session!"); return; } + PX4_INFO("Starting reading/writing tasks..."); + // Start read and lease tasks for zenoh-pico - if (zp_start_read_task(z_session_loan(&s), NULL) < 0 || zp_start_lease_task(z_session_loan(&s), NULL) < 0) { + if (zp_start_read_task(z_loan_mut(s), NULL) < 0 || zp_start_lease_task(z_loan_mut(s), NULL) < 0) { PX4_ERR("Unable to start read and lease tasks"); + z_close(z_move(s)); return; } @@ -114,7 +128,7 @@ void ZENOH::run() _zenoh_subscribers[i] = genSubscriber(type); if (_zenoh_subscribers[i] != 0) { - _zenoh_subscribers[i]->declare_subscriber(z_session_loan(&s), topic); + _zenoh_subscribers[i]->declare_subscriber(s, topic); } @@ -141,7 +155,7 @@ void ZENOH::run() _zenoh_publishers[i] = genPublisher(type); if (_zenoh_publishers[i] != 0) { - _zenoh_publishers[i]->declare_publisher(z_session_loan(&s), topic); + _zenoh_publishers[i]->declare_publisher(s, topic); _zenoh_publishers[i]->setPollFD(&pfds[i]); } } @@ -154,7 +168,7 @@ void ZENOH::run() if (_pub_count == 0) { // Nothing to publish but we don't want to stop this thread while (!should_exit()) { - sleep(2); + usleep(1000); } } @@ -194,8 +208,8 @@ void ZENOH::run() free(_zenoh_publishers); // Stop read and lease tasks for zenoh-pico - zp_stop_read_task(z_session_loan(&s)); - zp_stop_lease_task(z_session_loan(&s)); + zp_stop_read_task(z_session_loan_mut(&s)); + zp_stop_lease_task(z_session_loan_mut(&s)); z_close(z_session_move(&s)); exit_and_cleanup(); @@ -234,8 +248,8 @@ Zenoh demo bridge PX4_INFO_RAW(" addsubscriber Publish Zenoh topic to uORB\n"); PX4_INFO_RAW(" net Zenoh network mode\n"); PX4_INFO_RAW(" values: client|peer \n"); - PX4_INFO_RAW(" client: locator address for router\n"); - PX4_INFO_RAW(" peer: multicast address e.g. udp/224.0.0.225:7447#iface=eth0\n"); + PX4_INFO_RAW(" client: locator address e.g. tcp/10.41.10.1:7447#iface=eth0\n"); + PX4_INFO_RAW(" peer: multicast address e.g. udp/224.0.0.224:7446#iface=eth0\n"); return 0; } From d4d60a5181b83e51d63ee5af6befaf33d873df5c Mon Sep 17 00:00:00 2001 From: Alexis Paques Date: Fri, 2 Aug 2024 15:14:30 +0200 Subject: [PATCH 566/652] Add missing rc.sysinit file in the ROMFS --- ROMFS/px4fmu_common/init.d/CMakeLists.txt | 1 + ROMFS/px4fmu_common/init.d/rc.sysinit | 4 ++++ 2 files changed, 5 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/rc.sysinit diff --git a/ROMFS/px4fmu_common/init.d/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/CMakeLists.txt index 90b14f812f02..24dea3fcda93 100644 --- a/ROMFS/px4fmu_common/init.d/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/CMakeLists.txt @@ -44,6 +44,7 @@ px4_add_romfs_files( # TODO rc.balloon_apps rc.balloon_defaults + rc.sysinit ) if(CONFIG_MODULES_AIRSHIP_ATT_CONTROL) diff --git a/ROMFS/px4fmu_common/init.d/rc.sysinit b/ROMFS/px4fmu_common/init.d/rc.sysinit new file mode 100644 index 000000000000..9f878a1387bb --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.sysinit @@ -0,0 +1,4 @@ +#!/bin/sh +# +# Standard system init script +# From 4883f2128a02286df603d27104ed8a5110ee6d4c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 30 Jul 2024 11:52:18 +0200 Subject: [PATCH 567/652] commander: allow external modes more time for initial response We've come accross a case where a ROS node would consistently take something over 800 ms until the first arming check request subscription callback was triggered. After the first sample, the callback always triggered within the expected timeframe. Therefore this patch allows for more time right after registration until timing out. --- .../HealthAndArmingChecks/checks/externalChecks.cpp | 7 ++++++- .../HealthAndArmingChecks/checks/externalChecks.hpp | 4 ++++ 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp b/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp index c60a9a4af05e..8ef3c5cfa966 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp @@ -64,6 +64,7 @@ int ExternalChecks::addRegistration(int8_t nav_mode_id, int8_t replaces_nav_stat _active_registrations_mask |= 1 << free_registration_index; _registrations[free_registration_index].nav_mode_id = nav_mode_id; _registrations[free_registration_index].replaces_nav_state = replaces_nav_state; + _registrations[free_registration_index].waiting_for_first_response = true; _registrations[free_registration_index].num_no_response = 0; _registrations[free_registration_index].unresponsive = false; _registrations[free_registration_index].total_num_unresponsive = 0; @@ -230,6 +231,7 @@ void ExternalChecks::update() && _current_request_id == reply.request_id) { _reply_received_mask |= 1u << reply.registration_id; _registrations[reply.registration_id].num_no_response = 0; + _registrations[reply.registration_id].waiting_for_first_response = false; // Prevent toggling between unresponsive & responsive state if (_registrations[reply.registration_id].total_num_unresponsive <= 3) { @@ -253,7 +255,10 @@ void ExternalChecks::update() for (int i = 0; i < MAX_NUM_REGISTRATIONS; ++i) { if ((1u << i) & no_reply) { - if (!_registrations[i].unresponsive && ++_registrations[i].num_no_response >= NUM_NO_REPLY_UNTIL_UNRESPONSIVE) { + const int max_num_no_reply = + _registrations[i].waiting_for_first_response ? NUM_NO_REPLY_UNTIL_UNRESPONSIVE_INIT : NUM_NO_REPLY_UNTIL_UNRESPONSIVE; + + if (!_registrations[i].unresponsive && ++_registrations[i].num_no_response > max_num_no_reply) { // Clear immediately if not a mode if (_registrations[i].nav_mode_id == -1) { removeRegistration(i, -1); diff --git a/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.hpp b/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.hpp index b4ee24cba6d5..7129e4620361 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.hpp @@ -72,6 +72,9 @@ class ExternalChecks : public HealthAndArmingCheckBase static constexpr hrt_abstime UPDATE_INTERVAL = 300_ms; static_assert(REQUEST_TIMEOUT < UPDATE_INTERVAL, "keep timeout < update interval"); static constexpr int NUM_NO_REPLY_UNTIL_UNRESPONSIVE = 3; ///< Mode timeout = this value * UPDATE_INTERVAL + /// Timeout directly after registering (in some cases ROS can take a while until the subscription gets the first + /// sample, around 800ms was observed) + static constexpr int NUM_NO_REPLY_UNTIL_UNRESPONSIVE_INIT = 10; void checkNonRegisteredModes(const Context &context, Report &reporter) const; @@ -83,6 +86,7 @@ class ExternalChecks : public HealthAndArmingCheckBase int8_t nav_mode_id{-1}; ///< associated mode, -1 if none int8_t replaces_nav_state{-1}; + bool waiting_for_first_response{true}; uint8_t num_no_response{0}; bool unresponsive{false}; uint8_t total_num_unresponsive{0}; From 326e2a9f5cf6dceeb6ef7c9e2bdf5eec89edf411 Mon Sep 17 00:00:00 2001 From: sbtjagu <145494402+sbtjagu@users.noreply.github.com> Date: Mon, 5 Aug 2024 13:02:12 +0200 Subject: [PATCH 568/652] ackermann: add protection against float precision problem in acceptance radius update (#23478) * ackermann: add protection against float precision problem in acceptance radius update * ackermann: protect against divide-by-zero --------- Co-authored-by: Mathieu Bresciani --- .../RoverAckermannGuidance/RoverAckermannGuidance.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index db0495b67a3e..ade89f6c7e18 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -268,8 +268,9 @@ float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_ned // Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment if (curr_to_next_wp_ned.norm() > FLT_EPSILON && curr_to_prev_wp_ned.norm() > FLT_EPSILON) { - const float theta = acosf((curr_to_prev_wp_ned * curr_to_next_wp_ned) / (curr_to_prev_wp_ned.norm() * - curr_to_next_wp_ned.norm())) / 2.f; + 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 + const float theta = acosf(cosin) / 2.f; const float min_turning_radius = wheel_base / sinf(max_steer_angle); const float acceptance_radius_temp = min_turning_radius / tanf(theta); const float acceptance_radius_temp_scaled = acceptance_radius_gain * From 84d4ee0e60550646007370926400597913e3e4e1 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 5 Aug 2024 14:32:20 +0200 Subject: [PATCH 569/652] zenoh-pico: update to correct dev/1.0.0 branch which is up to date containing "Use SO_REUSEPORT only if it exists" and is advertised by GitHub because the commit is on a branch --- src/modules/zenoh/zenoh-pico | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/zenoh/zenoh-pico b/src/modules/zenoh/zenoh-pico index fff1a8c168e1..f093aa7955bb 160000 --- a/src/modules/zenoh/zenoh-pico +++ b/src/modules/zenoh/zenoh-pico @@ -1 +1 @@ -Subproject commit fff1a8c168e10d4ed9cbf2aa7d67ede07f239c52 +Subproject commit f093aa7955bb24dfa3e626de084583711e3bac5c From 8ed3489bd1af260b01e4932b93ddc03bc3f81a19 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 6 Aug 2024 10:48:12 +0200 Subject: [PATCH 570/652] hardfault_log: revert to explicit path to not trip the module documentation parser - the module documentation parser can only resolve defines from the same file - also it cannot deal with defines embeded in strings - what board should it add for the general documentation anyways? As a result of these issues I suggest to stay with the original hardcoded /fs/microsd for the documentation. It's still the most common path as far as I can see. --- src/systemcmds/hardfault_log/hardfault_log.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/hardfault_log/hardfault_log.c b/src/systemcmds/hardfault_log/hardfault_log.c index bad376b25edc..f8ff269ec6b8 100644 --- a/src/systemcmds/hardfault_log/hardfault_log.c +++ b/src/systemcmds/hardfault_log/hardfault_log.c @@ -1289,7 +1289,7 @@ static void print_usage(void) "Hardfault type: 0=divide by 0, 1=Assertion, 2=jump to 0x0, 3=write to 0x0 (default=0)", true); PRINT_MODULE_USAGE_COMMAND_DESCR("commit", - "Write uncommitted hardfault to " CONFIG_BOARD_ROOT_PATH "/fault_%i.txt (and rearm, but don't reset)"); + "Write uncommitted hardfault to /fs/microsd/fault_%i.txt (and rearm, but don't reset)"); PRINT_MODULE_USAGE_COMMAND_DESCR("count", "Read the reboot counter, counts the number of reboots of an uncommitted hardfault (returned as the exit code of the program)"); PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reset the reboot counter"); From d2478d00cf612c8869f6a90ef3617f1f6c095499 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 5 Aug 2024 11:28:49 +0200 Subject: [PATCH 571/652] ekf2: only allow ref sensor to reset height --- .../barometer/baro_height_control.cpp | 9 +- .../external_vision/ev_height_control.cpp | 2 +- .../aid_sources/gnss/gnss_height_control.cpp | 4 +- .../range_finder/range_height_control.cpp | 2 +- src/modules/ekf2/test/sensor_simulator/gps.h | 1 + .../ekf2/test/test_EKF_height_fusion.cpp | 87 +++++++++++++++++++ 6 files changed, 98 insertions(+), 7 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index 264c826738f2..dc6d36bcb5c7 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -126,7 +126,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max); - if (isHeightResetRequired()) { + if (isHeightResetRequired() && (_height_sensor_ref == HeightSensor::BARO)) { // All height sources are failing ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); @@ -142,10 +142,13 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) aid_src.time_last_fuse = imu_sample.time_us; } else if (is_fusion_failing) { - // Some other height source is still working ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME); stopBaroHgtFusion(); - _baro_hgt_faulty = true; + + if (isRecent(_time_last_hgt_fuse, _params.hgt_fusion_timeout_max)) { + // Some other height source is still working + _baro_hgt_faulty = true; + } } } else { diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp index e7b6f13f1181..440c0fe7acf6 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp @@ -142,7 +142,7 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max); - if (isHeightResetRequired() && quality_sufficient) { + if (isHeightResetRequired() && quality_sufficient && (_height_sensor_ref == HeightSensor::EV)) { // All height sources are failing ECL_WARN("%s fusion reset required, all height sources failing", AID_SRC_NAME); _information_events.flags.reset_hgt_to_ev = true; diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index c141d415eec5..91a8685cebae 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -100,12 +100,12 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max); - if (isHeightResetRequired()) { + if (isHeightResetRequired() && (_height_sensor_ref == HeightSensor::GNSS)) { // All height sources are failing ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_gps = true; - resetVerticalPositionTo(-(measurement - bias_est.getBias()), measurement_var); + resetVerticalPositionTo(aid_src.observation, measurement_var); bias_est.setBias(_state.pos(2) + measurement); aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp index 6c33d4db639a..0aafe8a1b00d 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 @@ -173,7 +173,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max); - if (isHeightResetRequired() && _control_status.flags.rng_hgt) { + if (isHeightResetRequired() && _control_status.flags.rng_hgt && (_height_sensor_ref == HeightSensor::RANGE)) { // All height sources are failing ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); diff --git a/src/modules/ekf2/test/sensor_simulator/gps.h b/src/modules/ekf2/test/sensor_simulator/gps.h index f962cc9bced7..e8ff206916f7 100644 --- a/src/modules/ekf2/test/sensor_simulator/gps.h +++ b/src/modules/ekf2/test/sensor_simulator/gps.h @@ -66,6 +66,7 @@ class Gps: public Sensor void setPdop(const float pdop); gnssSample getDefaultGpsData(); + const gnssSample &getData() const { return _gps_data; } private: void send(uint64_t time) override; diff --git a/src/modules/ekf2/test/test_EKF_height_fusion.cpp b/src/modules/ekf2/test/test_EKF_height_fusion.cpp index c80939f1ba6e..b322a2818245 100644 --- a/src/modules/ekf2/test/test_EKF_height_fusion.cpp +++ b/src/modules/ekf2/test/test_EKF_height_fusion.cpp @@ -261,6 +261,93 @@ TEST_F(EkfHeightFusionTest, gpsRefFailOver) EXPECT_TRUE(_ekf->getHeightSensorRef() == HeightSensor::UNKNOWN); } +TEST_F(EkfHeightFusionTest, gpsRefAllHgtFailReset) +{ + // GIVEN: EKF that fuses GNSS (reference) and baro + _sensor_simulator.startBaro(); + _sensor_simulator.startGps(); + _ekf_wrapper.setGpsHeightRef(); + _ekf_wrapper.enableBaroHeightFusion(); + _ekf_wrapper.enableGpsHeightFusion(); + + _sensor_simulator.runSeconds(11); + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsHeightFusion()); + EXPECT_TRUE(_ekf_wrapper.isIntendingBaroHeightFusion()); + EXPECT_TRUE(_ekf->getHeightSensorRef() == HeightSensor::GNSS); + + const Vector3f previous_position = _ekf->getPosition(); + + ResetLoggingChecker reset_logging_checker(_ekf); + reset_logging_checker.capturePreResetState(); + + // WHEN: + const float gnss_height_step = 10.f; + _sensor_simulator._gps.stepHeightByMeters(gnss_height_step); + + const float baro_height_step = 5.f; + _sensor_simulator._baro.setData(_sensor_simulator._baro.getData() + baro_height_step); + _sensor_simulator.runSeconds(15); + + // THEN: then the fusion of both sensors starts to fail and the height is reset to the + // reference sensor (GNSS) + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsHeightFusion()); + EXPECT_TRUE(_ekf_wrapper.isIntendingBaroHeightFusion()); + + const Vector3f new_position = _ekf->getPosition(); + EXPECT_NEAR(new_position(2), previous_position(2) - gnss_height_step, 0.2f); + + // Also check the reset counters to make sure the reset logic triggered + reset_logging_checker.capturePostResetState(); + EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(1)); + EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); +} + +TEST_F(EkfHeightFusionTest, baroRefAllHgtFailReset) +{ + // GIVEN: EKF that fuses GNSS and baro (reference) + _sensor_simulator.startBaro(); + _sensor_simulator.startGps(); + _ekf_wrapper.setBaroHeightRef(); + _ekf_wrapper.enableBaroHeightFusion(); + _ekf_wrapper.enableGpsHeightFusion(); + + _sensor_simulator.runSeconds(11); + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsHeightFusion()); + EXPECT_TRUE(_ekf_wrapper.isIntendingBaroHeightFusion()); + EXPECT_TRUE(_ekf->getHeightSensorRef() == HeightSensor::BARO); + + const Vector3f previous_position = _ekf->getPosition(); + + ResetLoggingChecker reset_logging_checker(_ekf); + reset_logging_checker.capturePreResetState(); + + // WHEN: + const float gnss_height_step = 10.f; + _sensor_simulator._gps.stepHeightByMeters(gnss_height_step); + + const float baro_height_step = 5.f; + _sensor_simulator._baro.setData(_sensor_simulator._baro.getData() + baro_height_step); + _sensor_simulator.runSeconds(20); + + // THEN: then the fusion of both sensors starts to fail and the height is reset to the + // reference sensor (baro) + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsHeightFusion()); + EXPECT_TRUE(_ekf_wrapper.isIntendingBaroHeightFusion()); + + const Vector3f new_position = _ekf->getPosition(); + EXPECT_NEAR(new_position(2), previous_position(2) - baro_height_step, 0.2f); + + // Also check the reset counters to make sure the reset logic triggered + reset_logging_checker.capturePostResetState(); + + // The velocity does not reset as baro only provides height measurement + EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); + + // The height resets twice in a row as the baro innovation is not corrected after a height + // reset and triggers a new reset at the next iteration + EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(2)); +} + TEST_F(EkfHeightFusionTest, changeEkfOriginAlt) { _sensor_simulator.startBaro(); From 3157a4e1712e4e0c402e345b4315d93fad5799e1 Mon Sep 17 00:00:00 2001 From: Thomas Frans <160142177+flyingthingsintothings@users.noreply.github.com> Date: Wed, 7 Aug 2024 00:46:18 +0200 Subject: [PATCH 572/652] gnss: update supported baud rates (#23415) * gnss: update supported baud rates The Septentrio GNSS driver requires certain baud rates to test all the supported baud rates of the receiver. Without these changes, certain "non-standard" ones would print an error to the MAVLink console when the driver was started through the console. * platforms: add missing baudrate defines --------- Co-authored-by: Thomas Frans Co-authored-by: Julian Oes --- platforms/nuttx/src/px4/common/SerialImpl.cpp | 24 +++++++++++++++++++ platforms/posix/src/px4/common/SerialImpl.cpp | 24 +++++++++++++++++++ 2 files changed, 48 insertions(+) diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index 7fc5ea7520a2..4264976f4471 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -97,12 +97,36 @@ bool SerialImpl::configure() case 460800: speed = B460800; break; +#ifndef B500000 +#define B500000 500000 +#endif + + case 500000: speed = B500000; break; + +#ifndef B576000 +#define B576000 576000 +#endif + + case 576000: speed = B576000; break; + #ifndef B921600 #define B921600 921600 #endif case 921600: speed = B921600; break; +#ifndef B1000000 +#define B1000000 1000000 +#endif + + case 1000000: speed = B1000000; break; + +#ifndef B1500000 +#define B1500000 1500000 +#endif + + case 1500000: speed = B1500000; break; + default: speed = _baudrate; PX4_WARN("Using non-standard baudrate: %lu", _baudrate); diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 822ed4255ec0..2298c3829263 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -90,12 +90,36 @@ bool SerialImpl::configure() case 460800: speed = B460800; break; +#ifndef B500000 +#define B500000 500000 +#endif + + case 500000: speed = B500000; break; + +#ifndef B576000 +#define B576000 576000 +#endif + + case 576000: speed = B576000; break; + #ifndef B921600 #define B921600 921600 #endif case 921600: speed = B921600; break; +#ifndef B1000000 +#define B1000000 1000000 +#endif + + case 1000000: speed = B1000000; break; + +#ifndef B1500000 +#define B1500000 1500000 +#endif + + case 1500000: speed = B1500000; break; + default: speed = _baudrate; PX4_WARN("Using non-standard baudrate: %u", _baudrate); From bfcd4564a6caf1549fcb681b162546f965181fc2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 7 Aug 2024 08:17:03 +0200 Subject: [PATCH 573/652] fix metadata.cmake: add missing paths to json & xml parameter outputs (#23464) --- cmake/metadata.cmake | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/metadata.cmake b/cmake/metadata.cmake index 59ae6bd82990..ef946c703159 100644 --- a/cmake/metadata.cmake +++ b/cmake/metadata.cmake @@ -74,13 +74,13 @@ add_custom_target(metadata_parameters --markdown ${PX4_BINARY_DIR}/docs/parameters.md COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/src/lib/parameters/px_process_params.py - --src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d` + --src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d` ${generated_params_dir} --inject-xml ${PX4_SOURCE_DIR}/src/lib/parameters/parameters_injected.xml --json ${PX4_BINARY_DIR}/docs/parameters.json --compress COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/src/lib/parameters/px_process_params.py - --src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d` + --src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d` ${generated_params_dir} --inject-xml ${PX4_SOURCE_DIR}/src/lib/parameters/parameters_injected.xml --xml ${PX4_BINARY_DIR}/docs/parameters.xml From 33d99a13e835743943b15fe8a75c00acd2fe01b9 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Wed, 7 Aug 2024 09:53:37 +0200 Subject: [PATCH 574/652] differential: restructure and update module (#23430) * differential: rename module * differential: restructure and update module --- .../init.d-posix/airframes/4009_gz_r1_rover | 24 +- .../init.d-posix/airframes/4011_gz_lawnmower | 12 +- ROMFS/px4fmu_common/init.d/CMakeLists.txt | 2 +- .../init.d/airframes/CMakeLists.txt | 2 +- .../init.d/rc.rover_differential_apps | 2 +- .../init.d/rc.rover_differential_defaults | 11 +- boards/px4/fmu-v5/rover.px4board | 3 +- boards/px4/fmu-v5x/default.px4board | 1 - boards/px4/fmu-v5x/rover.px4board | 2 + boards/px4/fmu-v6c/rover.px4board | 3 +- boards/px4/fmu-v6u/rover.px4board | 3 +- boards/px4/fmu-v6x/rover.px4board | 3 +- boards/px4/fmu-v6xrt/rover.px4board | 3 +- boards/px4/sitl/default.px4board | 2 +- msg/CMakeLists.txt | 3 +- msg/DifferentialDriveSetpoint.msg | 8 - msg/RoverDifferentialGuidanceStatus.msg | 10 + msg/RoverDifferentialStatus.msg | 8 + .../control_allocator/ControlAllocator.cpp | 2 +- .../differential_drive/DifferentialDrive.cpp | 191 ------------- .../DifferentialDriveControl/CMakeLists.txt | 39 --- .../DifferentialDriveControl.cpp | 109 -------- .../DifferentialDriveControl.hpp | 91 ------- .../DifferentialDriveGuidance.cpp | 138 ---------- .../DifferentialDriveGuidance.hpp | 140 ---------- .../CMakeLists.txt | 40 --- .../DifferentialDriveKinematics.cpp | 97 ------- .../DifferentialDriveKinematics.hpp | 103 ------- .../DifferentialDriveKinematicsTest.cpp | 168 ------------ src/modules/differential_drive/Kconfig | 6 - src/modules/logger/logged_topics.cpp | 4 +- .../CMakeLists.txt | 17 +- src/modules/rover_differential/Kconfig | 6 + .../rover_differential/RoverDifferential.cpp | 256 ++++++++++++++++++ .../RoverDifferential.hpp} | 83 ++++-- .../RoverDifferentialGuidance}/CMakeLists.txt | 7 +- .../RoverDifferentialGuidance.cpp | 247 +++++++++++++++++ .../RoverDifferentialGuidance.hpp | 163 +++++++++++ .../module.yaml | 130 ++++++--- src/modules/uxrce_dds_client/dds_topics.yaml | 3 - 40 files changed, 902 insertions(+), 1240 deletions(-) delete mode 100644 msg/DifferentialDriveSetpoint.msg create mode 100644 msg/RoverDifferentialGuidanceStatus.msg create mode 100644 msg/RoverDifferentialStatus.msg delete mode 100644 src/modules/differential_drive/DifferentialDrive.cpp delete mode 100644 src/modules/differential_drive/DifferentialDriveControl/CMakeLists.txt delete mode 100644 src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.cpp delete mode 100644 src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.hpp delete mode 100644 src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.cpp delete mode 100644 src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.hpp delete mode 100644 src/modules/differential_drive/DifferentialDriveKinematics/CMakeLists.txt delete mode 100644 src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.cpp delete mode 100644 src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.hpp delete mode 100644 src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematicsTest.cpp delete mode 100644 src/modules/differential_drive/Kconfig rename src/modules/{differential_drive => rover_differential}/CMakeLists.txt (84%) create mode 100644 src/modules/rover_differential/Kconfig create mode 100644 src/modules/rover_differential/RoverDifferential.cpp rename src/modules/{differential_drive/DifferentialDrive.hpp => rover_differential/RoverDifferential.hpp} (53%) rename src/modules/{differential_drive/DifferentialDriveGuidance => rover_differential/RoverDifferentialGuidance}/CMakeLists.txt (89%) create mode 100644 src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp create mode 100644 src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp rename src/modules/{differential_drive => rover_differential}/module.yaml (55%) 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 80664cf661c0..7697e23db769 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 @@ -6,16 +6,36 @@ . ${R}etc/init.d/rc.rover_differential_defaults PX4_SIMULATOR=${PX4_SIMULATOR:=gz} -PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} +PX4_GZ_WORLD=${PX4_GZ_WORLD:=rover} PX4_SIM_MODEL=${PX4_SIM_MODEL:=r1_rover} 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_MAX_YAW_RATE 180 +param set-default RD_MISS_SPD_DEF 7 +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 30 +param set-default PP_LOOKAHD_MIN 2 +param set-default PP_LOOKAHD_GAIN 1 + # Simulated sensors param set-default SENS_EN_GPSSIM 1 param set-default SENS_EN_BAROSIM 0 param set-default SENS_EN_MAGSIM 1 -param set-default SENS_EN_ARSPDSIM 1 +param set-default SENS_EN_ARSPDSIM 0 # Actuator mapping param set-default SIM_GZ_WH_FUNC1 101 # right wheel 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 1dcb917a09ad..01fc515c4370 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower @@ -20,9 +20,9 @@ param set-default SENS_EN_ARSPDSIM 1 param set-default COM_ARM_WO_GPS 1 # Set Differential Drive Kinematics Library parameters: -param set RDD_WHEEL_BASE 0.9 -param set RDD_WHEEL_RADIUS 0.22 -param set RDD_WHEEL_SPEED 10.0 # Maximum wheel speed rad/s, approx 8 km/h +param set RD_WHEEL_BASE 0.9 +param set RD_WHEEL_RADIUS 0.22 +param set RD_WHEEL_SPEED 10.0 # Maximum wheel speed rad/s, approx 8 km/h # Actuator mapping - set SITL motors/servos output parameters: @@ -41,9 +41,9 @@ param set-default SIM_GZ_WH_FUNC2 102 # left wheel param set-default SIM_GZ_WH_REV 0 # no need to reverse any wheels -# Note: The servo configurations ( SIM_GZ_SV_FUNC*) outlined below are intended for educational purposes in this simulation. -# They do not have physical effects in the simulated environment, except for actuating the joints. Their definitions are meant to demonstrate -# how actuators could be mapped and configured in a real-world application, providing a foundation for understanding and implementing actuator +# Note: The servo configurations ( SIM_GZ_SV_FUNC*) outlined below are intended for educational purposes in this simulation. +# They do not have physical effects in the simulated environment, except for actuating the joints. Their definitions are meant to demonstrate +# how actuators could be mapped and configured in a real-world application, providing a foundation for understanding and implementing actuator # controls in practical scenarios. # Cutter deck blades clutch, PCA9685 servo channel 3, "RC FLAPS" (406) - leftmost switch, or "Servo 3" (203): diff --git a/ROMFS/px4fmu_common/init.d/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/CMakeLists.txt index 24dea3fcda93..3319779096c5 100644 --- a/ROMFS/px4fmu_common/init.d/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/CMakeLists.txt @@ -78,7 +78,7 @@ if(CONFIG_MODULES_ROVER_POS_CONTROL) ) endif() -if(CONFIG_MODULES_DIFFERENTIAL_DRIVE) +if(CONFIG_MODULES_ROVER_DIFFERENTIAL) px4_add_romfs_files( rc.rover_differential_apps rc.rover_differential_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index f763a4376606..c6bae3566a1d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -143,7 +143,7 @@ if(CONFIG_MODULES_ROVER_POS_CONTROL) ) endif() -if(CONFIG_MODULES_DIFFERENTIAL_DRIVE) +if(CONFIG_MODULES_ROVER_DIFFERENTIAL) px4_add_romfs_files( 50003_aion_robotics_r1_rover ) diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps index 275664af7e26..4acbe8301404 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps @@ -2,7 +2,7 @@ # Standard apps for a differential drive rover. # Start rover differential drive controller. -differential_drive start +rover_differential start # Start Land Detector. land_detector start rover diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults index e0cace3a3238..4cddd44f89e3 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults @@ -3,9 +3,8 @@ set VEHICLE_TYPE rover_differential -param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER - -param set-default CA_AIRFRAME 6 # Rover (Differential) -param set-default CA_R_REV 3 # Right and left motors reversible - -param set-default EKF2_MAG_TYPE 1 # make sure magnetometer is fused even when not flying +param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER +param set-default CA_AIRFRAME 6 # Rover (Differential) +param set-default CA_R_REV 3 # Right and left motors reversible +param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius +param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying diff --git a/boards/px4/fmu-v5/rover.px4board b/boards/px4/fmu-v5/rover.px4board index 92c265280ab9..07bfbe094121 100644 --- a/boards/px4/fmu-v5/rover.px4board +++ b/boards/px4/fmu-v5/rover.px4board @@ -17,5 +17,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_DRIVERS_ROBOCLAW=y diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 46d04d8cc2eb..a48b0956876b 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -54,7 +54,6 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_DATAMAN=y -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y CONFIG_MODULES_EKF2=y CONFIG_MODULES_ESC_BATTERY=y CONFIG_MODULES_EVENTS=y diff --git a/boards/px4/fmu-v5x/rover.px4board b/boards/px4/fmu-v5x/rover.px4board index 738e6d9b0d0a..4a4458c2e6bc 100644 --- a/boards/px4/fmu-v5x/rover.px4board +++ b/boards/px4/fmu-v5x/rover.px4board @@ -14,4 +14,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set +CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_DRIVERS_ROBOCLAW=y diff --git a/boards/px4/fmu-v6c/rover.px4board b/boards/px4/fmu-v6c/rover.px4board index 553bc76a52c7..7ded4008d8af 100644 --- a/boards/px4/fmu-v6c/rover.px4board +++ b/boards/px4/fmu-v6c/rover.px4board @@ -13,5 +13,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_DRIVERS_ROBOCLAW=y diff --git a/boards/px4/fmu-v6u/rover.px4board b/boards/px4/fmu-v6u/rover.px4board index 553bc76a52c7..7ded4008d8af 100644 --- a/boards/px4/fmu-v6u/rover.px4board +++ b/boards/px4/fmu-v6u/rover.px4board @@ -13,5 +13,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_DRIVERS_ROBOCLAW=y diff --git a/boards/px4/fmu-v6x/rover.px4board b/boards/px4/fmu-v6x/rover.px4board index 553bc76a52c7..7ded4008d8af 100644 --- a/boards/px4/fmu-v6x/rover.px4board +++ b/boards/px4/fmu-v6x/rover.px4board @@ -13,5 +13,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_DRIVERS_ROBOCLAW=y diff --git a/boards/px4/fmu-v6xrt/rover.px4board b/boards/px4/fmu-v6xrt/rover.px4board index 101555842444..95a01552267c 100644 --- a/boards/px4/fmu-v6xrt/rover.px4board +++ b/boards/px4/fmu-v6xrt/rover.px4board @@ -14,5 +14,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_EKF2_AUX_GLOBAL_POSITION=y # CONFIG_EKF2_WIND is not set -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_DRIVERS_ROBOCLAW=y diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index d46a7cc7e70f..784be31db67a 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -13,7 +13,6 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_DATAMAN=y -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y CONFIG_MODULES_EKF2=y CONFIG_EKF2_VERBOSE_STATUS=y CONFIG_EKF2_AUX_GLOBAL_POSITION=y @@ -47,6 +46,7 @@ CONFIG_MODULES_PAYLOAD_DELIVERER=y CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_REPLAY=y CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_COMMON_SIMULATION=y diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 65ec54d8b01e..f0f6d520c701 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -71,7 +71,6 @@ set(msg_files DebugKeyValue.msg DebugValue.msg DebugVect.msg - DifferentialDriveSetpoint.msg DifferentialPressure.msg DistanceSensor.msg Ekf2Timestamps.msg @@ -181,6 +180,8 @@ set(msg_files RegisterExtComponentRequest.msg RoverAckermannGuidanceStatus.msg RoverAckermannStatus.msg + RoverDifferentialGuidanceStatus.msg + RoverDifferentialStatus.msg Rpm.msg RtlStatus.msg RtlTimeEstimate.msg diff --git a/msg/DifferentialDriveSetpoint.msg b/msg/DifferentialDriveSetpoint.msg deleted file mode 100644 index f7e4c5840099..000000000000 --- a/msg/DifferentialDriveSetpoint.msg +++ /dev/null @@ -1,8 +0,0 @@ -uint64 timestamp # time since system start (microseconds) - -float32 speed # [m/s] collective roll-off speed in body x-axis -bool closed_loop_speed_control # true if speed is controlled using estimator feedback, false if direct feed-forward -float32 yaw_rate # [rad/s] yaw rate -bool closed_loop_yaw_rate_control # true if yaw rate is controlled using gyroscope feedback, false if direct feed-forward - -# TOPICS differential_drive_setpoint differential_drive_control_output diff --git a/msg/RoverDifferentialGuidanceStatus.msg b/msg/RoverDifferentialGuidanceStatus.msg new file mode 100644 index 000000000000..836546e7ebb7 --- /dev/null +++ b/msg/RoverDifferentialGuidanceStatus.msg @@ -0,0 +1,10 @@ +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/RoverDifferentialStatus.msg b/msg/RoverDifferentialStatus.msg new file mode 100644 index 000000000000..31907ffa6477 --- /dev/null +++ b/msg/RoverDifferentialStatus.msg @@ -0,0 +1,8 @@ +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_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 + +# TOPICS rover_differential_status diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index 3399bd619016..48363eeb1e38 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -239,7 +239,7 @@ ControlAllocator::update_effectiveness_source() break; case EffectivenessSource::ROVER_DIFFERENTIAL: - // differential_drive_control does allocation and publishes directly to actuator_motors topic + // rover_differential_control does allocation and publishes directly to actuator_motors topic break; case EffectivenessSource::FIXED_WING: diff --git a/src/modules/differential_drive/DifferentialDrive.cpp b/src/modules/differential_drive/DifferentialDrive.cpp deleted file mode 100644 index a1d34e01e7d2..000000000000 --- a/src/modules/differential_drive/DifferentialDrive.cpp +++ /dev/null @@ -1,191 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023-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 "DifferentialDrive.hpp" - -DifferentialDrive::DifferentialDrive() : - ModuleParams(nullptr), - ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) -{ - updateParams(); -} - -bool DifferentialDrive::init() -{ - ScheduleOnInterval(10_ms); // 100 Hz - return true; -} - -void DifferentialDrive::updateParams() -{ - ModuleParams::updateParams(); - - _differential_drive_kinematics.setWheelBase(_param_rdd_wheel_base.get()); - - _max_speed = _param_rdd_wheel_speed.get() * _param_rdd_wheel_radius.get(); - _differential_drive_guidance.setMaxSpeed(_max_speed); - _differential_drive_kinematics.setMaxSpeed(_max_speed); - - _max_angular_velocity = _max_speed / (_param_rdd_wheel_base.get() / 2.f); - _differential_drive_guidance.setMaxAngularVelocity(_max_angular_velocity); - _differential_drive_kinematics.setMaxAngularVelocity(_max_angular_velocity); -} - -void DifferentialDrive::Run() -{ - if (should_exit()) { - ScheduleClear(); - exit_and_cleanup(); - return; - } - - hrt_abstime now = hrt_absolute_time(); - const float dt = math::min((now - _time_stamp_last), 5000_ms) / 1e6f; - _time_stamp_last = now; - - if (_parameter_update_sub.updated()) { - parameter_update_s parameter_update; - _parameter_update_sub.copy(¶meter_update); - updateParams(); - } - - if (_vehicle_control_mode_sub.updated()) { - vehicle_control_mode_s vehicle_control_mode{}; - - if (_vehicle_control_mode_sub.copy(&vehicle_control_mode)) { - _manual_driving = vehicle_control_mode.flag_control_manual_enabled; - _mission_driving = vehicle_control_mode.flag_control_auto_enabled; - } - } - - if (_vehicle_status_sub.updated()) { - vehicle_status_s vehicle_status{}; - - if (_vehicle_status_sub.copy(&vehicle_status)) { - const bool armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED); - const bool spooled_up = armed && (hrt_elapsed_time(&vehicle_status.armed_time) > _param_com_spoolup_time.get() * 1_s); - _differential_drive_kinematics.setArmed(spooled_up); - _acro_driving = (vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_ACRO); - } - } - - if (_manual_driving) { - // Manual mode - // directly produce setpoints from the manual control setpoint (joystick) - if (_manual_control_setpoint_sub.updated()) { - manual_control_setpoint_s manual_control_setpoint{}; - - if (_manual_control_setpoint_sub.copy(&manual_control_setpoint)) { - differential_drive_setpoint_s setpoint{}; - setpoint.speed = manual_control_setpoint.throttle * math::max(0.f, _param_rdd_speed_scale.get()) * _max_speed; - setpoint.yaw_rate = manual_control_setpoint.roll * _param_rdd_ang_velocity_scale.get() * _max_angular_velocity; - - // if acro mode, we activate the yaw rate control - if (_acro_driving) { - setpoint.closed_loop_speed_control = false; - setpoint.closed_loop_yaw_rate_control = true; - - } else { - setpoint.closed_loop_speed_control = false; - setpoint.closed_loop_yaw_rate_control = false; - } - - setpoint.timestamp = now; - _differential_drive_setpoint_pub.publish(setpoint); - } - } - - } else if (_mission_driving) { - // Mission mode - // directly receive setpoints from the guidance library - _differential_drive_guidance.computeGuidance( - _differential_drive_control.getVehicleYaw(), - _differential_drive_control.getVehicleBodyYawRate(), - dt - ); - } - - _differential_drive_control.control(dt); - _differential_drive_kinematics.allocate(); -} - -int DifferentialDrive::task_spawn(int argc, char *argv[]) -{ - DifferentialDrive *instance = new DifferentialDrive(); - - if (instance) { - _object.store(instance); - _task_id = task_id_is_work_queue; - - if (instance->init()) { - return PX4_OK; - } - - } else { - PX4_ERR("alloc failed"); - } - - delete instance; - _object.store(nullptr); - _task_id = -1; - - return PX4_ERROR; -} - -int DifferentialDrive::custom_command(int argc, char *argv[]) -{ - return print_usage("unknown command"); -} - -int DifferentialDrive::print_usage(const char *reason) -{ - if (reason) { - PX4_ERR("%s\n", reason); - } - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Rover Differential Drive controller. -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("differential_drive", "controller"); - PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - return 0; -} - -extern "C" __EXPORT int differential_drive_main(int argc, char *argv[]) -{ - return DifferentialDrive::main(argc, argv); -} diff --git a/src/modules/differential_drive/DifferentialDriveControl/CMakeLists.txt b/src/modules/differential_drive/DifferentialDriveControl/CMakeLists.txt deleted file mode 100644 index 4610fa6c3d4d..000000000000 --- a/src/modules/differential_drive/DifferentialDriveControl/CMakeLists.txt +++ /dev/null @@ -1,39 +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(DifferentialDriveControl - DifferentialDriveControl.cpp -) - -target_link_libraries(DifferentialDriveControl PUBLIC pid) -target_include_directories(DifferentialDriveControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.cpp b/src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.cpp deleted file mode 100644 index 728c5e666a10..000000000000 --- a/src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.cpp +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023-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 "DifferentialDriveControl.hpp" - -using namespace matrix; - -DifferentialDriveControl::DifferentialDriveControl(ModuleParams *parent) : ModuleParams(parent) -{ - pid_init(&_pid_angular_velocity, PID_MODE_DERIVATIV_NONE, 0.001f); - pid_init(&_pid_speed, PID_MODE_DERIVATIV_NONE, 0.001f); -} - -void DifferentialDriveControl::updateParams() -{ - ModuleParams::updateParams(); - - pid_set_parameters(&_pid_angular_velocity, - _param_rdd_p_gain_angular_velocity.get(), // Proportional gain - _param_rdd_i_gain_angular_velocity.get(), // Integral gain - 0, // Derivative gain - 20, // Integral limit - 200); // Output limit - - pid_set_parameters(&_pid_speed, - _param_rdd_p_gain_speed.get(), // Proportional gain - _param_rdd_i_gain_speed.get(), // Integral gain - 0, // Derivative gain - 2, // Integral limit - 200); // Output limit -} - -void DifferentialDriveControl::control(float dt) -{ - if (_vehicle_angular_velocity_sub.updated()) { - vehicle_angular_velocity_s vehicle_angular_velocity{}; - - if (_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{}; - - if (_vehicle_attitude_sub.copy(&vehicle_attitude)) { - _vehicle_attitude_quaternion = 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{}; - - if (_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); - } - } - - _differential_drive_setpoint_sub.update(&_differential_drive_setpoint); - - // PID to reach setpoint using control_output - differential_drive_setpoint_s differential_drive_control_output = _differential_drive_setpoint; - - if (_differential_drive_setpoint.closed_loop_speed_control) { - differential_drive_control_output.speed += - pid_calculate(&_pid_speed, _differential_drive_setpoint.speed, _vehicle_forward_speed, 0, dt); - } - - if (_differential_drive_setpoint.closed_loop_yaw_rate_control) { - differential_drive_control_output.yaw_rate += - pid_calculate(&_pid_angular_velocity, _differential_drive_setpoint.yaw_rate, _vehicle_body_yaw_rate, 0, dt); - } - - differential_drive_control_output.timestamp = hrt_absolute_time(); - _differential_drive_control_output_pub.publish(differential_drive_control_output); -} diff --git a/src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.hpp b/src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.hpp deleted file mode 100644 index 8d3b7e1c216c..000000000000 --- a/src/modules/differential_drive/DifferentialDriveControl/DifferentialDriveControl.hpp +++ /dev/null @@ -1,91 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023-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. - * - ****************************************************************************/ - -/** - * @file DifferentialDriveControl.hpp - * - * Controller for heading rate and forward speed. - */ - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -class DifferentialDriveControl : public ModuleParams -{ -public: - DifferentialDriveControl(ModuleParams *parent); - ~DifferentialDriveControl() = default; - - void control(float dt); - float getVehicleBodyYawRate() const { return _vehicle_body_yaw_rate; } - float getVehicleYaw() const { return _vehicle_yaw; } - -protected: - void updateParams() override; - -private: - uORB::Subscription _differential_drive_setpoint_sub{ORB_ID(differential_drive_setpoint)}; - uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; - uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; - uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; - - uORB::Publication _differential_drive_control_output_pub{ORB_ID(differential_drive_control_output)}; - - differential_drive_setpoint_s _differential_drive_setpoint{}; - - matrix::Quatf _vehicle_attitude_quaternion{}; - float _vehicle_yaw{0.f}; - - // States - float _vehicle_body_yaw_rate{0.f}; - float _vehicle_forward_speed{0.f}; - - PID_t _pid_angular_velocity; ///< The PID controller for yaw rate. - PID_t _pid_speed; ///< The PID controller for velocity. - - DEFINE_PARAMETERS( - (ParamFloat) _param_rdd_p_gain_speed, - (ParamFloat) _param_rdd_i_gain_speed, - (ParamFloat) _param_rdd_p_gain_angular_velocity, - (ParamFloat) _param_rdd_i_gain_angular_velocity - ) -}; diff --git a/src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.cpp b/src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.cpp deleted file mode 100644 index df453ff8b5c0..000000000000 --- a/src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.cpp +++ /dev/null @@ -1,138 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023-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 "DifferentialDriveGuidance.hpp" - -#include - -using namespace matrix; - -DifferentialDriveGuidance::DifferentialDriveGuidance(ModuleParams *parent) : ModuleParams(parent) -{ - updateParams(); - - pid_init(&_heading_p_controller, PID_MODE_DERIVATIV_NONE, 0.001f); -} - -void DifferentialDriveGuidance::computeGuidance(float yaw, float angular_velocity, float dt) -{ - if (_position_setpoint_triplet_sub.updated()) { - _position_setpoint_triplet_sub.copy(&_position_setpoint_triplet); - } - - if (_vehicle_global_position_sub.updated()) { - _vehicle_global_position_sub.copy(&_vehicle_global_position); - } - - matrix::Vector2d global_position(_vehicle_global_position.lat, _vehicle_global_position.lon); - matrix::Vector2d current_waypoint(_position_setpoint_triplet.current.lat, _position_setpoint_triplet.current.lon); - matrix::Vector2d next_waypoint(_position_setpoint_triplet.next.lat, _position_setpoint_triplet.next.lon); - - const float distance_to_next_wp = get_distance_to_next_waypoint(global_position(0), global_position(1), - current_waypoint(0), - current_waypoint(1)); - - float desired_heading = get_bearing_to_next_waypoint(global_position(0), global_position(1), current_waypoint(0), - current_waypoint(1)); - float heading_error = matrix::wrap_pi(desired_heading - yaw); - - if (_current_waypoint != current_waypoint) { - _currentState = GuidanceState::TURNING; - } - - // Make rover stop when it arrives at the last waypoint instead of loitering and driving around weirdly. - if ((current_waypoint == next_waypoint) && distance_to_next_wp <= _param_nav_acc_rad.get()) { - _currentState = GuidanceState::GOAL_REACHED; - } - - float desired_speed = 0.f; - - switch (_currentState) { - case GuidanceState::TURNING: - desired_speed = 0.f; - - if (fabsf(heading_error) < 0.05f) { - _currentState = GuidanceState::DRIVING; - } - - break; - - case GuidanceState::DRIVING: { - const float max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_rdd_max_jerk.get(), - _param_rdd_max_accel.get(), distance_to_next_wp, 0.0f); - _forwards_velocity_smoothing.updateDurations(max_velocity); - _forwards_velocity_smoothing.updateTraj(dt); - desired_speed = math::interpolate(abs(heading_error), 0.1f, 0.8f, - _forwards_velocity_smoothing.getCurrentVelocity(), 0.0f); - break; - } - - case GuidanceState::GOAL_REACHED: - // temporary till I find a better way to stop the vehicle - desired_speed = 0.f; - heading_error = 0.f; - angular_velocity = 0.f; - _desired_angular_velocity = 0.f; - break; - } - - // Compute the desired angular velocity relative to the heading error, to steer the vehicle towards the next waypoint. - float angular_velocity_pid = pid_calculate(&_heading_p_controller, heading_error, angular_velocity, 0, - dt) + heading_error; - - differential_drive_setpoint_s output{}; - output.speed = math::constrain(desired_speed, -_max_speed, _max_speed); - output.yaw_rate = math::constrain(angular_velocity_pid, -_max_angular_velocity, _max_angular_velocity); - output.closed_loop_speed_control = output.closed_loop_yaw_rate_control = true; - output.timestamp = hrt_absolute_time(); - - _differential_drive_setpoint_pub.publish(output); - - _current_waypoint = current_waypoint; -} - -void DifferentialDriveGuidance::updateParams() -{ - ModuleParams::updateParams(); - - pid_set_parameters(&_heading_p_controller, - _param_rdd_p_gain_heading.get(), // Proportional gain - 0, // Integral gain - 0, // Derivative gain - 0, // Integral limit - 200); // Output limit - - _forwards_velocity_smoothing.setMaxJerk(_param_rdd_max_jerk.get()); - _forwards_velocity_smoothing.setMaxAccel(_param_rdd_max_accel.get()); - _forwards_velocity_smoothing.setMaxVel(_max_speed); -} diff --git a/src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.hpp b/src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.hpp deleted file mode 100644 index 0a5a29bbca0b..000000000000 --- a/src/modules/differential_drive/DifferentialDriveGuidance/DifferentialDriveGuidance.hpp +++ /dev/null @@ -1,140 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023-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 -#include - -#include -#include - -#include -#include -#include -#include -#include - -#include - - -/** - * @brief Enum class for the different states of guidance. - */ -enum class GuidanceState { - TURNING, ///< The vehicle is currently turning. - DRIVING, ///< The vehicle is currently driving straight. - GOAL_REACHED ///< The vehicle has reached its goal. -}; - -/** - * @brief Class for differential drive guidance. - */ -class DifferentialDriveGuidance : public ModuleParams -{ -public: - /** - * @brief Constructor for DifferentialDriveGuidance. - * @param parent The parent ModuleParams object. - */ - DifferentialDriveGuidance(ModuleParams *parent); - ~DifferentialDriveGuidance() = default; - - /** - * @brief Compute guidance for the vehicle. - * @param global_pos The global position of the vehicle in degrees. - * @param current_waypoint The current waypoint the vehicle is heading towards in degrees. - * @param next_waypoint The next waypoint the vehicle will head towards after reaching the current waypoint in degrees. - * @param vehicle_yaw The yaw orientation of the vehicle in radians. - * @param body_velocity The velocity of the vehicle in m/s. - * @param angular_velocity The angular velocity of the vehicle in rad/s. - * @param dt The time step in seconds. - */ - void computeGuidance(float yaw, float angular_velocity, float dt); - - /** - * @brief Set the maximum speed for the vehicle. - * @param max_speed The maximum speed in m/s. - * @return The set maximum speed in m/s. - */ - float setMaxSpeed(float max_speed) { return _max_speed = max_speed; } - - - /** - * @brief Set the maximum angular velocity for the vehicle. - * @param max_angular_velocity The maximum angular velocity in rad/s. - * @return The set maximum angular velocity in rad/s. - */ - float setMaxAngularVelocity(float max_angular_velocity) { return _max_angular_velocity = max_angular_velocity; } - -protected: - /** - * @brief Update the parameters of the module. - */ - void updateParams() override; - -private: - uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; - uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; - - uORB::Publication _differential_drive_setpoint_pub{ORB_ID(differential_drive_setpoint)}; - - position_setpoint_triplet_s _position_setpoint_triplet{}; - vehicle_global_position_s _vehicle_global_position{}; - - GuidanceState _currentState; ///< The current state of guidance. - - float _desired_angular_velocity; ///< The desired angular velocity. - - float _max_speed; ///< The maximum speed. - float _max_angular_velocity; ///< The maximum angular velocity. - - matrix::Vector2d _current_waypoint; ///< The current waypoint. - - VelocitySmoothing _forwards_velocity_smoothing; ///< The velocity smoothing for forward motion. - PositionSmoothing _position_smoothing; ///< The position smoothing. - - PID_t _heading_p_controller; ///< The PID controller for yaw rate. - - DEFINE_PARAMETERS( - (ParamFloat) _param_rdd_p_gain_heading, - (ParamFloat) _param_nav_acc_rad, - (ParamFloat) _param_rdd_max_jerk, - (ParamFloat) _param_rdd_max_accel - ) -}; diff --git a/src/modules/differential_drive/DifferentialDriveKinematics/CMakeLists.txt b/src/modules/differential_drive/DifferentialDriveKinematics/CMakeLists.txt deleted file mode 100644 index c556db2b8f3f..000000000000 --- a/src/modules/differential_drive/DifferentialDriveKinematics/CMakeLists.txt +++ /dev/null @@ -1,40 +0,0 @@ -############################################################################ -# -# Copyright (c) 2023-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(DifferentialDriveKinematics - DifferentialDriveKinematics.cpp -) - -target_include_directories(DifferentialDriveKinematics PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) - -px4_add_functional_gtest(SRC DifferentialDriveKinematicsTest.cpp LINKLIBS DifferentialDriveKinematics) diff --git a/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.cpp b/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.cpp deleted file mode 100644 index 42fcbea56b66..000000000000 --- a/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.cpp +++ /dev/null @@ -1,97 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2023-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 "DifferentialDriveKinematics.hpp" - -#include - -using namespace matrix; -using namespace time_literals; - -DifferentialDriveKinematics::DifferentialDriveKinematics(ModuleParams *parent) : ModuleParams(parent) -{} - -void DifferentialDriveKinematics::allocate() -{ - hrt_abstime now = hrt_absolute_time(); - - if (_differential_drive_control_output_sub.updated()) { - _differential_drive_control_output_sub.copy(&_differential_drive_control_output); - } - - const bool setpoint_timeout = (_differential_drive_control_output.timestamp + 100_ms) < now; - - Vector2f wheel_speeds = - computeInverseKinematics(_differential_drive_control_output.speed, _differential_drive_control_output.yaw_rate); - - if (!_armed || setpoint_timeout) { - wheel_speeds = {}; // stop - } - - wheel_speeds = matrix::constrain(wheel_speeds, -1.f, 1.f); - - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); // should be 3 see rc.rover_differential_defaults - wheel_speeds.copyTo(actuator_motors.control); - actuator_motors.timestamp = now; - _actuator_motors_pub.publish(actuator_motors); -} - -matrix::Vector2f DifferentialDriveKinematics::computeInverseKinematics(float linear_velocity_x, float yaw_rate) const -{ - if (_max_speed < FLT_EPSILON) { - return Vector2f(); - } - - linear_velocity_x = math::constrain(linear_velocity_x, -_max_speed, _max_speed); - yaw_rate = math::constrain(yaw_rate, -_max_angular_velocity, _max_angular_velocity); - - const float rotational_velocity = (_wheel_base / 2.f) * yaw_rate; - float combined_velocity = fabsf(linear_velocity_x) + fabsf(rotational_velocity); - - // Compute an initial gain - float gain = 1.0f; - - if (combined_velocity > _max_speed) { - float excess_velocity = fabsf(combined_velocity - _max_speed); - const float adjusted_linear_velocity = fabsf(linear_velocity_x) - excess_velocity; - gain = adjusted_linear_velocity / fabsf(linear_velocity_x); - } - - // Apply the gain - linear_velocity_x *= gain; - - // Calculate the left and right wheel speeds - return Vector2f(linear_velocity_x - rotational_velocity, - linear_velocity_x + rotational_velocity) / _max_speed; -} diff --git a/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.hpp b/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.hpp deleted file mode 100644 index 524a5520a78f..000000000000 --- a/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematics.hpp +++ /dev/null @@ -1,103 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023-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 -#include - -/** - * @brief Differential Drive Kinematics class for computing the kinematics of a differential drive robot. - * - * This class provides functions to set the wheel base and radius, and to compute the inverse kinematics - * given linear velocity and yaw rate. - */ -class DifferentialDriveKinematics : public ModuleParams -{ -public: - DifferentialDriveKinematics(ModuleParams *parent); - ~DifferentialDriveKinematics() = default; - - /** - * @brief Sets the wheel base of the robot. - * - * @param wheel_base The distance between the centers of the wheels. - */ - void setWheelBase(const float wheel_base) { _wheel_base = wheel_base; }; - - /** - * @brief Sets the maximum speed of the robot. - * - * @param max_speed The maximum speed of the robot. - */ - void setMaxSpeed(const float max_speed) { _max_speed = max_speed; }; - - /** - * @brief Sets the maximum angular speed of the robot. - * - * @param max_angular_speed The maximum angular speed of the robot. - */ - void setMaxAngularVelocity(const float max_angular_velocity) { _max_angular_velocity = max_angular_velocity; }; - - void setArmed(const bool armed) { _armed = armed; }; - - void allocate(); - - /** - * @brief Computes the inverse kinematics for differential drive. - * - * @param linear_velocity_x Linear velocity along the x-axis. - * @param yaw_rate Yaw rate of the robot. - * @return matrix::Vector2f Motor velocities for the right and left motors. - */ - matrix::Vector2f computeInverseKinematics(float linear_velocity_x, float yaw_rate) const; - -private: - uORB::Subscription _differential_drive_control_output_sub{ORB_ID(differential_drive_control_output)}; - uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; - - differential_drive_setpoint_s _differential_drive_control_output{}; - bool _armed = false; - - float _wheel_base{0.f}; - float _max_speed{0.f}; - float _max_angular_velocity{0.f}; - - DEFINE_PARAMETERS( - (ParamInt) _param_r_rev - ) -}; diff --git a/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematicsTest.cpp b/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematicsTest.cpp deleted file mode 100644 index b3c4935c1d9d..000000000000 --- a/src/modules/differential_drive/DifferentialDriveKinematics/DifferentialDriveKinematicsTest.cpp +++ /dev/null @@ -1,168 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2023-2024 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include "DifferentialDriveKinematics.hpp" -#include - -using namespace matrix; - -class DifferentialDriveKinematicsTest : public ::testing::Test -{ -public: - DifferentialDriveKinematics kinematics{nullptr}; -}; - -TEST_F(DifferentialDriveKinematicsTest, AllZeroInputCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(10.f); - kinematics.setMaxAngularVelocity(10.f); - - // Test with zero linear velocity and zero yaw rate (stationary vehicle) - EXPECT_EQ(kinematics.computeInverseKinematics(0.f, 0.f), Vector2f()); -} - - -TEST_F(DifferentialDriveKinematicsTest, InvalidParameterCase) -{ - kinematics.setWheelBase(0.f); - kinematics.setMaxSpeed(10.f); - kinematics.setMaxAngularVelocity(10.f); - - // Test with invalid parameters (zero wheel base and wheel radius) - EXPECT_EQ(kinematics.computeInverseKinematics(0.f, .1f), Vector2f()); -} - - -TEST_F(DifferentialDriveKinematicsTest, UnitCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(10.f); - kinematics.setMaxAngularVelocity(10.f); - - // Test with unit values for linear velocity and yaw rate - EXPECT_EQ(kinematics.computeInverseKinematics(1.f, 1.f), Vector2f(0.05f, 0.15f)); -} - - -TEST_F(DifferentialDriveKinematicsTest, UnitSaturationCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Test with unit values for linear velocity and yaw rate, but with max speed that requires saturation - EXPECT_EQ(kinematics.computeInverseKinematics(1.f, 1.f), Vector2f(0, 1)); -} - - -TEST_F(DifferentialDriveKinematicsTest, OppositeUnitSaturationCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Negative linear velocity for backward motion and positive yaw rate for turning right - EXPECT_EQ(kinematics.computeInverseKinematics(-1.f, 1.f), Vector2f(-1, 0)); -} - -TEST_F(DifferentialDriveKinematicsTest, RandomCase) -{ - kinematics.setWheelBase(2.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Negative linear velocity for backward motion and positive yaw rate for turning right - EXPECT_EQ(kinematics.computeInverseKinematics(0.5f, 0.7f), Vector2f(-0.4f, 1.0f)); -} - -TEST_F(DifferentialDriveKinematicsTest, RotateInPlaceCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Test rotating in place (zero linear velocity, non-zero yaw rate) - EXPECT_EQ(kinematics.computeInverseKinematics(0.f, 1.f), Vector2f(-0.5f, 0.5f)); -} - -TEST_F(DifferentialDriveKinematicsTest, StraightMovementCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Test moving straight (non-zero linear velocity, zero yaw rate) - EXPECT_EQ(kinematics.computeInverseKinematics(1.f, 0.f), Vector2f(1.f, 1.f)); -} - -TEST_F(DifferentialDriveKinematicsTest, MinInputValuesCase) -{ - kinematics.setWheelBase(FLT_MIN); - kinematics.setMaxSpeed(FLT_MIN); - kinematics.setMaxAngularVelocity(FLT_MIN); - - // Test with minimum possible input values - EXPECT_EQ(kinematics.computeInverseKinematics(FLT_MIN, FLT_MIN), Vector2f(0.f, 0.f)); -} - -TEST_F(DifferentialDriveKinematicsTest, MaxSpeedLimitCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Test with high linear velocity and yaw rate, expecting speeds to be scaled down to fit the max speed - EXPECT_EQ(kinematics.computeInverseKinematics(10.f, 10.f), Vector2f(0.f, 1.f)); -} - -TEST_F(DifferentialDriveKinematicsTest, MaxSpeedForwardsCase) -{ - kinematics.setWheelBase(1.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Test with high linear velocity and yaw rate, expecting speeds to be scaled down to fit the max speed - EXPECT_EQ(kinematics.computeInverseKinematics(10.f, 0.f), Vector2f(1.f, 1.f)); -} - -TEST_F(DifferentialDriveKinematicsTest, MaxAngularCase) -{ - kinematics.setWheelBase(2.f); - kinematics.setMaxSpeed(1.f); - kinematics.setMaxAngularVelocity(1.f); - - // Test with high linear velocity and yaw rate, expecting speeds to be scaled down to fit the max speed - EXPECT_EQ(kinematics.computeInverseKinematics(0.f, 10.f), Vector2f(-1.f, 1.f)); -} diff --git a/src/modules/differential_drive/Kconfig b/src/modules/differential_drive/Kconfig deleted file mode 100644 index a95897e91f99..000000000000 --- a/src/modules/differential_drive/Kconfig +++ /dev/null @@ -1,6 +0,0 @@ -menuconfig MODULES_DIFFERENTIAL_DRIVE - bool "differential_drive" - default n - depends on MODULES_CONTROL_ALLOCATOR - ---help--- - Enable support for control of differential drive rovers diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index fc187a954d0e..24b5004ee9af 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -58,8 +58,6 @@ void LoggedTopics::add_default_topics() add_topic("commander_state"); add_topic("config_overrides"); add_topic("cpuload"); - add_optional_topic("differential_drive_control_output", 100); - add_optional_topic("differential_drive_setpoint", 100); add_optional_topic("external_ins_attitude"); add_optional_topic("external_ins_global_position"); add_optional_topic("external_ins_local_position"); @@ -105,6 +103,8 @@ void LoggedTopics::add_default_topics() add_topic("radio_status"); 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_status", 100); add_topic("rtl_time_estimate", 1000); add_topic("rtl_status", 2000); add_optional_topic("sensor_airflow", 100); diff --git a/src/modules/differential_drive/CMakeLists.txt b/src/modules/rover_differential/CMakeLists.txt similarity index 84% rename from src/modules/differential_drive/CMakeLists.txt rename to src/modules/rover_differential/CMakeLists.txt index 2e0e3583b9af..beaec32a8776 100644 --- a/src/modules/differential_drive/CMakeLists.txt +++ b/src/modules/rover_differential/CMakeLists.txt @@ -31,22 +31,19 @@ # ############################################################################ -add_subdirectory(DifferentialDriveControl) -add_subdirectory(DifferentialDriveGuidance) -add_subdirectory(DifferentialDriveKinematics) +add_subdirectory(RoverDifferentialGuidance) px4_add_module( - MODULE modules__differential_drive - MAIN differential_drive + MODULE modules__rover_differential + MAIN rover_differential SRCS - DifferentialDrive.cpp - DifferentialDrive.hpp + RoverDifferential.cpp + RoverDifferential.hpp DEPENDS - DifferentialDriveControl - DifferentialDriveGuidance - DifferentialDriveKinematics + RoverDifferentialGuidance px4_work_queue modules__control_allocator # for parameter CA_R_REV + pure_pursuit MODULE_CONFIG module.yaml ) diff --git a/src/modules/rover_differential/Kconfig b/src/modules/rover_differential/Kconfig new file mode 100644 index 000000000000..840e2cdbf98f --- /dev/null +++ b/src/modules/rover_differential/Kconfig @@ -0,0 +1,6 @@ +menuconfig MODULES_ROVER_DIFFERENTIAL + bool "rover_differential" + default n + depends on MODULES_CONTROL_ALLOCATOR + ---help--- + Enable support for control of differential rovers diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp new file mode 100644 index 000000000000..ab89392a0ec8 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -0,0 +1,256 @@ +/**************************************************************************** + * + * Copyright (c) 2023-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 "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); +} + +bool RoverDifferential::init() +{ + ScheduleOnInterval(10_ms); // 100 Hz + return true; +} + +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() +{ + if (should_exit()) { + ScheduleClear(); + exit_and_cleanup(); + 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(); + } + + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status{}; + _vehicle_status_sub.copy(&vehicle_status); + _nav_state = vehicle_status.nav_state; + } + + 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(); + + } + + _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); + } + + _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); + 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; + 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); + +} + +matrix::Vector2f RoverDifferential::computeMotorCommands(float forward_speed, const float speed_diff) +{ + 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; + } + + // Calculate the left and right wheel speeds + return Vector2f(forward_speed - speed_diff, + forward_speed + speed_diff); +} + +int RoverDifferential::task_spawn(int argc, char *argv[]) +{ + RoverDifferential *instance = new RoverDifferential(); + + if (instance) { + _object.store(instance); + _task_id = task_id_is_work_queue; + + if (instance->init()) { + return PX4_OK; + } + + } else { + PX4_ERR("alloc failed"); + } + + delete instance; + _object.store(nullptr); + _task_id = -1; + + return PX4_ERROR; +} + +int RoverDifferential::custom_command(int argc, char *argv[]) +{ + return print_usage("unk_timestampn command"); +} + +int RoverDifferential::print_usage(const char *reason) +{ + if (reason) { + PX4_ERR("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +Rover Differential controller. +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("rover_differential", "controller"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + return 0; +} + +extern "C" __EXPORT int rover_differential_main(int argc, char *argv[]) +{ + return RoverDifferential::main(argc, argv); +} diff --git a/src/modules/differential_drive/DifferentialDrive.hpp b/src/modules/rover_differential/RoverDifferential.hpp similarity index 53% rename from src/modules/differential_drive/DifferentialDrive.hpp rename to src/modules/rover_differential/RoverDifferential.hpp index 255bb0c52607..3dafe99b0566 100644 --- a/src/modules/differential_drive/DifferentialDrive.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -33,31 +33,41 @@ #pragma once +// PX4 includes #include #include #include #include #include + +// uORB includes #include +#include #include -#include #include #include -#include #include +#include +#include +#include +#include +#include + +// Standard libraries +#include +#include -#include "DifferentialDriveControl/DifferentialDriveControl.hpp" -#include "DifferentialDriveGuidance/DifferentialDriveGuidance.hpp" -#include "DifferentialDriveKinematics/DifferentialDriveKinematics.hpp" +// Local includes +#include "RoverDifferentialGuidance/RoverDifferentialGuidance.hpp" using namespace time_literals; -class DifferentialDrive : public ModuleBase, public ModuleParams, +class RoverDifferential : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { public: - DifferentialDrive(); - ~DifferentialDrive() override = default; + RoverDifferential(); + ~RoverDifferential() override = default; /** @see ModuleBase */ static int task_spawn(int argc, char *argv[]); @@ -70,36 +80,57 @@ class DifferentialDrive : 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; + + // uORB Subscriptions uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - + uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; - uORB::Publication _differential_drive_setpoint_pub{ORB_ID(differential_drive_setpoint)}; - bool _manual_driving = false; - bool _mission_driving = false; - bool _acro_driving = false; - hrt_abstime _time_stamp_last{0}; /**< time stamp when task was last updated */ + // uORB Publications + uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _rover_differential_status_pub{ORB_ID(rover_differential_status)}; + + // Instances + RoverDifferentialGuidance _rover_differential_guidance{this}; - DifferentialDriveGuidance _differential_drive_guidance{this}; - DifferentialDriveControl _differential_drive_control{this}; - DifferentialDriveKinematics _differential_drive_kinematics{this}; + // Variables + float _vehicle_body_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; - float _max_speed{0.f}; - float _max_angular_velocity{0.f}; + // 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_rdd_ang_velocity_scale, - (ParamFloat) _param_rdd_speed_scale, - (ParamFloat) _param_rdd_wheel_base, - (ParamFloat) _param_rdd_wheel_speed, - (ParamFloat) _param_rdd_wheel_radius, - (ParamFloat) _param_com_spoolup_time + (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 ) }; diff --git a/src/modules/differential_drive/DifferentialDriveGuidance/CMakeLists.txt b/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt similarity index 89% rename from src/modules/differential_drive/DifferentialDriveGuidance/CMakeLists.txt rename to src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt index fa833c50ae42..0fd7b68c394e 100644 --- a/src/modules/differential_drive/DifferentialDriveGuidance/CMakeLists.txt +++ b/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt @@ -31,8 +31,9 @@ # ############################################################################ -px4_add_library(DifferentialDriveGuidance - DifferentialDriveGuidance.cpp +px4_add_library(RoverDifferentialGuidance + RoverDifferentialGuidance.cpp ) -target_include_directories(DifferentialDriveGuidance PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) +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 new file mode 100644 index 000000000000..efad52e7b874 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp @@ -0,0 +1,247 @@ +/**************************************************************************** + * + * Copyright (c) 2023-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 "RoverDifferentialGuidance.hpp" + +#include + +using namespace matrix; +using namespace time_literals; + +RoverDifferentialGuidance::RoverDifferentialGuidance(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _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) +{ + // 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); + } + + if (_local_position_sub.updated()) { + vehicle_local_position_s local_position{}; + _local_position_sub.copy(&local_position); + + 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; + } + + // State machine + if (!mission_finished && distance_to_next_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; + } + + } else { // Mission finished or delay command + _currentState = GuidanceState::STOPPED; + } + + // Guidance logic + 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()); + } + + 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 + } + + break; + + case GuidanceState::STOPPED: + default: + desired_speed = 0.f; + desired_yaw_rate = 0.f; + break; + + } + + // Closed loop speed control + float throttle{0.f}; + + if (fabsf(desired_speed) < FLT_EPSILON) { + pid_reset_integral(&_pid_throttle); + + } else { + throttle = pid_calculate(&_pid_throttle, desired_speed, actual_speed, 0, + dt); + + 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); + } + } + + // 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; +} + +void RoverDifferentialGuidance::updateWaypoints() +{ + position_setpoint_triplet_s position_setpoint_triplet{}; + _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); + + // Global waypoint coordinates + 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); + + } else { + _curr_wp = Vector2d(0, 0); + } + + 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); + + } else { + _prev_wp = _curr_pos; + } + + 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); + + } else { + _next_wp = _home_position; + } + + // 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)); + +} diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp new file mode 100644 index 000000000000..29a131f8d8e2 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp @@ -0,0 +1,163 @@ +/**************************************************************************** + * + * Copyright (c) 2023-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 +#include + +// uORB includes +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Standard libraries +#include +#include +#include +#include +#include +#include + +using namespace matrix; + +/** + * @brief Enum class for the different states of guidance. + */ +enum class GuidanceState { + SPOT_TURNING, // The vehicle is currently turning on the spot. + DRIVING, // The vehicle is currently driving. + STOPPED // The vehicle is stopped. +}; + +/** + * @brief Class for differential rover guidance. + */ +class RoverDifferentialGuidance : public ModuleParams +{ +public: + /** + * @brief Constructor for RoverDifferentialGuidance. + * @param parent The parent ModuleParams object. + */ + 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. + * @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(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + // uORB subscriptions + uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; + uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; + uORB::Subscription _mission_result_sub{ORB_ID(mission_result)}; + uORB::Subscription _local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _home_position_sub{ORB_ID(home_position)}; + + // uORB publications + 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. + PurePursuit _pure_pursuit{this}; // Pure pursuit library + hrt_abstime _timestamp{0}; + float _max_yaw_rate{0.f}; + + + // Waypoints + Vector2d _curr_pos{}; + Vector2f _curr_pos_ned{}; + Vector2d _prev_wp{}; + Vector2f _prev_wp_ned{}; + Vector2d _curr_wp{}; + Vector2f _curr_wp_ned{}; + Vector2d _next_wp{}; + Vector2d _home_position{}; + + // Controllers + PID_t _pid_heading; // The PID controller for the heading + PID_t _pid_throttle; // The PID controller for velocity + + // 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/differential_drive/module.yaml b/src/modules/rover_differential/module.yaml similarity index 55% rename from src/modules/differential_drive/module.yaml rename to src/modules/rover_differential/module.yaml index 50ab9bb837ca..b6819305bc5f 100644 --- a/src/modules/differential_drive/module.yaml +++ b/src/modules/rover_differential/module.yaml @@ -1,11 +1,12 @@ -module_name: Differential Drive +module_name: Rover Differential parameters: - - group: Rover Differential Drive + - group: Rover Differential definitions: - RDD_WHEEL_BASE: + + RD_WHEEL_TRACK: description: - short: Wheel base + short: Wheel track long: Distance from the center of the right wheel to the center of the left wheel type: float unit: m @@ -14,55 +15,41 @@ parameters: increment: 0.001 decimal: 3 default: 0.5 - RDD_WHEEL_RADIUS: - description: - short: Wheel radius - long: Size of the wheel, half the diameter of the wheel - type: float - unit: m - min: 0.001 - max: 100 - increment: 0.001 - decimal: 3 - default: 0.1 - RDD_SPEED_SCALE: - description: - short: Manual speed scale - type: float - min: 0 - max: 1 - increment: 0.01 - decimal: 2 - default: 1 - RDD_ANG_SCALE: + + RD_MAN_YAW_SCALE: description: - short: Manual angular velocity scale + short: Manual yaw rate scale + long: | + In manual mode the setpoint for the yaw rate received from the rc remote + is scaled by this value. type: float - min: 0 + min: 0.01 max: 1 increment: 0.01 decimal: 2 default: 1 - RDD_WHEEL_SPEED: + + RD_HEADING_P: description: - short: Maximum wheel speed + short: Proportional gain for heading controller type: float - unit: rad/s min: 0 max: 100 increment: 0.01 decimal: 2 - default: 0.3 - RDD_P_HEADING: + default: 1 + + RD_HEADING_I: description: - short: Proportional gain for heading controller + short: Integral gain for heading controller type: float min: 0 max: 100 increment: 0.01 decimal: 2 - default: 1 - RDD_P_SPEED: + default: 0.1 + + RD_SPEED_P: description: short: Proportional gain for speed controller type: float @@ -71,7 +58,8 @@ parameters: increment: 0.01 decimal: 2 default: 1 - RDD_I_SPEED: + + RD_SPEED_I: description: short: Integral gain for ground speed controller type: float @@ -80,7 +68,8 @@ parameters: increment: 0.01 decimal: 2 default: 0 - RDD_P_ANG_VEL: + + RD_YAW_RATE_P: description: short: Proportional gain for angular velocity controller type: float @@ -89,7 +78,8 @@ parameters: increment: 0.01 decimal: 2 default: 1 - RDD_I_ANG_VEL: + + RD_YAW_RATE_I: description: short: Integral gain for angular velocity controller type: float @@ -98,7 +88,8 @@ parameters: increment: 0.01 decimal: 2 default: 0 - RDD_MAX_JERK: + + RD_MAX_JERK: description: short: Maximum jerk long: Limit for forwards acc/deceleration change. @@ -109,7 +100,8 @@ parameters: increment: 0.01 decimal: 2 default: 0.5 - RDD_MAX_ACCEL: + + RD_MAX_ACCEL: description: short: Maximum acceleration long: Maximum acceleration is used to limit the acceleration of the rover @@ -120,3 +112,61 @@ parameters: increment: 0.01 decimal: 2 default: 0.5 + + RD_MAX_SPEED: + description: + short: Maximum speed the rover can drive + long: This parameter is used to map desired speeds to normalized motor commands. + type: float + unit: m/s + min: 0 + max: 100 + increment: 0.01 + decimal: 2 + default: 7 + + RD_MAX_YAW_RATE: + description: + 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 + unit: deg/s + min: 0.01 + max: 1000 + increment: 0.01 + decimal: 2 + default: 90 + + RD_MISS_SPD_DEF: + description: + short: Default rover speed during a mission + type: float + unit: m/s + min: 0 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + + RD_TRANS_TRN_DRV: + description: + short: Heading error threshhold to switch from spot turning to driving + type: float + unit: rad + min: 0.001 + max: 180 + increment: 0.01 + decimal: 3 + default: 0.0872665 + + RD_TRANS_DRV_TRN: + description: + short: Heading error threshhold to switch from driving to spot turning + type: float + unit: rad + min: 0.001 + max: 180 + increment: 0.01 + decimal: 3 + default: 0.174533 diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index 67b1e9456cee..e9e67cff25ed 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -130,9 +130,6 @@ subscriptions: - topic: /fmu/in/vehicle_rates_setpoint type: px4_msgs::msg::VehicleRatesSetpoint - - topic: /fmu/in/differential_drive_setpoint - type: px4_msgs::msg::DifferentialDriveSetpoint - - topic: /fmu/in/vehicle_visual_odometry type: px4_msgs::msg::VehicleOdometry From 28a0de63c5787c10b366aeb0371c5bfe710d0ca7 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Wed, 7 Aug 2024 11:12:52 +0200 Subject: [PATCH 575/652] Orbit Yaw Vehicle Parameter (#23358) --- msg/OrbitStatus.msg | 1 + msg/VehicleCommand.msg | 8 ++++++++ .../tasks/Orbit/FlightTaskOrbit.cpp | 11 ++++++++++- .../tasks/Orbit/FlightTaskOrbit.hpp | 2 ++ .../tasks/Orbit/flight_task_orbit_params.c | 14 +++++++++++++- 5 files changed, 34 insertions(+), 2 deletions(-) diff --git a/msg/OrbitStatus.msg b/msg/OrbitStatus.msg index a04265db46c8..531fa4145306 100644 --- a/msg/OrbitStatus.msg +++ b/msg/OrbitStatus.msg @@ -4,6 +4,7 @@ uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 +uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 uint64 timestamp # time since system start (microseconds) float32 radius # Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. [m] diff --git a/msg/VehicleCommand.msg b/msg/VehicleCommand.msg index 0c1ce85d5fa8..8df0ca56b0ac 100644 --- a/msg/VehicleCommand.msg +++ b/msg/VehicleCommand.msg @@ -158,6 +158,14 @@ uint8 SPEED_TYPE_GROUNDSPEED = 1 uint8 SPEED_TYPE_CLIMB_SPEED = 2 uint8 SPEED_TYPE_DESCEND_SPEED = 3 +# used as param3 in CMD_DO_ORBIT +uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0 +uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 +uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 +uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 +uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 +uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 + # used as param1 in ARM_DISARM command int8 ARMING_ACTION_DISARM = 0 int8 ARMING_ACTION_ARM = 1 diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index f639e492493d..18adf4d3eb80 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -90,7 +90,14 @@ bool FlightTaskOrbit::applyCommandParameters(const vehicle_command_s &command, b // commanded heading behaviour if (PX4_ISFINITE(command.param3)) { - _yaw_behaviour = command.param3; + if (static_cast(command.param3 + .5f) == vehicle_command_s::ORBIT_YAW_BEHAVIOUR_UNCHANGED) { + if (!_currently_orbiting) { // only change the yaw behaviour if we are not actively orbiting + _yaw_behaviour = _param_mc_orbit_yaw_mod.get(); + } + + } else { + _yaw_behaviour = command.param3; + } } // save current yaw estimate for ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING @@ -165,6 +172,7 @@ void FlightTaskOrbit::_sanitizeParams(float &radius, float &velocity) const bool FlightTaskOrbit::activate(const trajectory_setpoint_s &last_setpoint) { bool ret = FlightTaskManualAltitude::activate(last_setpoint); + _currently_orbiting = false; _orbit_radius = _radius_min; _orbit_velocity = 1.f; _center = _position; @@ -199,6 +207,7 @@ bool FlightTaskOrbit::activate(const trajectory_setpoint_s &last_setpoint) bool FlightTaskOrbit::update() { bool ret = true; + _currently_orbiting = true; _updateTrajectoryBoundaries(); _adjustParametersByStick(); diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp index 187a47de4119..2c55bbc15ba7 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp @@ -124,6 +124,7 @@ class FlightTaskOrbit : public FlightTaskManualAltitudeSmoothVel /** yaw behaviour during the orbit flight according to MAVLink's ORBIT_YAW_BEHAVIOUR enum */ int _yaw_behaviour = orbit_status_s::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER; bool _started_clockwise{true}; + bool _currently_orbiting{false}; float _initial_heading = 0.f; /**< the heading of the drone when the orbit command was issued */ SlewRateYaw _slew_rate_yaw; @@ -132,6 +133,7 @@ class FlightTaskOrbit : public FlightTaskManualAltitudeSmoothVel DEFINE_PARAMETERS( (ParamFloat) _param_mc_orbit_rad_max, + (ParamInt) _param_mc_orbit_yaw_mod, (ParamFloat) _param_mpc_xy_cruise, /**< cruise speed for circle approach */ (ParamFloat) _param_mpc_yawrauto_max, (ParamFloat) _param_mpc_xy_traj_p, diff --git a/src/modules/flight_mode_manager/tasks/Orbit/flight_task_orbit_params.c b/src/modules/flight_mode_manager/tasks/Orbit/flight_task_orbit_params.c index 3e655c80e2ed..c8f66eb9f15d 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/flight_task_orbit_params.c +++ b/src/modules/flight_mode_manager/tasks/Orbit/flight_task_orbit_params.c @@ -39,6 +39,18 @@ * @max 10000.0 * @increment 0.5 * @decimal 1 - * @group FlightTaskOrbit + * @group Flight Task Orbit */ PARAM_DEFINE_FLOAT(MC_ORBIT_RAD_MAX, 1000.0f); + +/** + * Yaw behaviour during orbit flight. + * + * @value 0 Front to Circle Center + * @value 1 Hold Initial Heading + * @value 2 Uncontrolled + * @value 3 Hold Front Tangent to Circle + * @value 4 RC Controlled + * @group Flight Task Orbit + */ +PARAM_DEFINE_INT32(MC_ORBIT_YAW_MOD, 0); From c8ff5909b56224d24fb65e07f90d7ac0ab7ad4f7 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Wed, 7 Aug 2024 15:16:41 +0200 Subject: [PATCH 576/652] rover: restructure airframes (#23506) --- .../50000_generic_rover_differential | 12 ++++++ ..._r1_rover => 50001_aion_robotics_r1_rover} | 3 -- ..._generic => 51000_generic_rover_ackermann} | 2 +- .../51001_axial_scx10_2_trail_honcho | 37 +++++++++++++++++++ ...d_vehicle => 59000_generic_ground_vehicle} | 2 +- ...robot_gpx => 59001_nxpcup_car_dfrobot_gpx} | 2 +- .../init.d/airframes/CMakeLists.txt | 19 ++++++---- .../init.d/rc.rover_ackermann_apps | 4 +- .../init.d/rc.rover_ackermann_defaults | 12 +++--- .../init.d/rc.rover_differential_apps | 4 +- .../init.d/rc.rover_differential_defaults | 13 ++++--- 11 files changed, 80 insertions(+), 30 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/airframes/50000_generic_rover_differential rename ROMFS/px4fmu_common/init.d/airframes/{50003_aion_robotics_r1_rover => 50001_aion_robotics_r1_rover} (85%) rename ROMFS/px4fmu_common/init.d/airframes/{50010_ackermann_rover_generic => 51000_generic_rover_ackermann} (83%) create mode 100644 ROMFS/px4fmu_common/init.d/airframes/51001_axial_scx10_2_trail_honcho rename ROMFS/px4fmu_common/init.d/airframes/{50000_generic_ground_vehicle => 59000_generic_ground_vehicle} (96%) rename ROMFS/px4fmu_common/init.d/airframes/{50004_nxpcup_car_dfrobot_gpx => 59001_nxpcup_car_dfrobot_gpx} (97%) diff --git a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_rover_differential b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_rover_differential new file mode 100644 index 000000000000..8c490d497be2 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_rover_differential @@ -0,0 +1,12 @@ +#!/bin/sh +# +# @name Generic Rover Differential +# +# @type Rover +# @class Rover +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# + +. ${R}etc/init.d/rc.rover_differential_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover similarity index 85% rename from ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover rename to ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover index 20a16428b2ed..c06b158cf857 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover @@ -15,9 +15,6 @@ param set-default BAT1_N_CELLS 4 -param set-default EKF2_GBIAS_INIT 0.01 -param set-default EKF2_ANGERR_INIT 0.01 - # Set geometry & output configration param set-default RBCLW_ADDRESS 128 param set-default RBCLW_FUNC1 101 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50010_ackermann_rover_generic b/ROMFS/px4fmu_common/init.d/airframes/51000_generic_rover_ackermann similarity index 83% rename from ROMFS/px4fmu_common/init.d/airframes/50010_ackermann_rover_generic rename to ROMFS/px4fmu_common/init.d/airframes/51000_generic_rover_ackermann index 66b3dc0cabba..43620a50ddcd 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50010_ackermann_rover_generic +++ b/ROMFS/px4fmu_common/init.d/airframes/51000_generic_rover_ackermann @@ -1,6 +1,6 @@ #!/bin/sh # -# @name Generic ackermann rover +# @name Generic Rover Ackermann # # @type Rover # @class Rover diff --git a/ROMFS/px4fmu_common/init.d/airframes/51001_axial_scx10_2_trail_honcho b/ROMFS/px4fmu_common/init.d/airframes/51001_axial_scx10_2_trail_honcho new file mode 100644 index 000000000000..6f50c7f4a1e0 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/51001_axial_scx10_2_trail_honcho @@ -0,0 +1,37 @@ +#!/bin/sh +# +# @name Axial SCX10 2 Trail Honcho +# +# @url https://www.axialadventure.com/product/1-10-scx10-ii-trail-honcho-4wd-rock-crawler-brushed-rtr/AXID9059.html +# +# @type Rover +# @class Rover +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# + +. ${R}etc/init.d/rc.rover_ackermann_defaults + +param set-default BAT1_N_CELLS 3 + +# Rover parameters +param set-default NAV_ACC_RAD 0.5 +param set-default RA_ACC_RAD_GAIN 2 +param set-default RA_ACC_RAD_MAX 3 +param set-default RA_MAX_ACCEL 0.5 +param set-default RA_MAX_JERK 10 +param set-default RA_MAX_SPEED 2.7 +param set-default RA_MAX_STR_ANG 0.5236 +param set-default RA_MAX_STR_RATE 270 +param set-default RA_MISS_VEL_DEF 2.7 +param set-default RA_MISS_VEL_GAIN 3.5 +param set-default RA_MISS_VEL_MIN 1 +param set-default RA_SPEED_I 0.1 +param set-default RA_SPEED_P 0.5 +param set-default RA_WHEEL_BASE 0.321 + +# Pure pursuit parameters +param set-default PP_LOOKAHD_GAIN 1 +param set-default PP_LOOKAHD_MAX 10 +param set-default PP_LOOKAHD_MIN 1.5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle b/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle similarity index 96% rename from ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle rename to ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle index 5ae6b09f4a8d..a773c1158d44 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle +++ b/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle @@ -1,6 +1,6 @@ #!/bin/sh # -# @name Generic Ground Vehicle (Ackermann) +# @name Generic Ground Vehicle (Deprecated) # # @type Rover # @class Rover diff --git a/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx b/ROMFS/px4fmu_common/init.d/airframes/59001_nxpcup_car_dfrobot_gpx similarity index 97% rename from ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx rename to ROMFS/px4fmu_common/init.d/airframes/59001_nxpcup_car_dfrobot_gpx index 67620ddc0375..9f08553d970f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx +++ b/ROMFS/px4fmu_common/init.d/airframes/59001_nxpcup_car_dfrobot_gpx @@ -1,6 +1,6 @@ #!/bin/sh # -# @name NXP Cup car: DF Robot GPX +# @name NXP Cup car: DF Robot GPX (Deprecated) # # @type Rover diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index c6bae3566a1d..634eb3e1b882 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -136,22 +136,27 @@ if(CONFIG_MODULES_VTOL_ATT_CONTROL) ) endif() -if(CONFIG_MODULES_ROVER_POS_CONTROL) +if(CONFIG_MODULES_ROVER_DIFFERENTIAL) px4_add_romfs_files( - 50000_generic_ground_vehicle - 50004_nxpcup_car_dfrobot_gpx + # [50000, 50999] Differential rovers + 50000_generic_rover_differential + 50001_aion_robotics_r1_rover ) endif() -if(CONFIG_MODULES_ROVER_DIFFERENTIAL) +if(CONFIG_MODULES_ROVER_ACKERMANN) px4_add_romfs_files( - 50003_aion_robotics_r1_rover + # [51000, 51999] Ackermann rovers + 51000_generic_rover_ackermann + 51001_axial_scx10_2_trail_honcho ) endif() -if(CONFIG_MODULES_ROVER_ACKERMANN) +if(CONFIG_MODULES_ROVER_POS_CONTROL) px4_add_romfs_files( - 50010_ackermann_rover_generic + # [59000, 59999] Rover position control (deprecated) + 59000_generic_ground_vehicle + 59001_nxpcup_car_dfrobot_gpx ) endif() diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps index 5273d6aec068..181233babe26 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps @@ -1,7 +1,7 @@ #!/bin/sh -# Standard apps for a ackermann drive rover. +# Standard apps for an ackermann rover. -# Start rover ackermann drive controller. +# Start rover ackermann module. rover_ackermann start # Start Land Detector. diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults index 27cf144a329a..fe0ae7aa9bb8 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults @@ -2,12 +2,10 @@ # Ackermann rover parameters. set VEHICLE_TYPE rover_ackermann -param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER -param set-default CA_AIRFRAME 5 # Rover (Ackermann) -param set-default CA_R_REV 1 # Motor is assumed to be reversible -param set-default EKF2_MAG_TYPE 1 # make sure magnetometer is fused even when not flying +param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER +param set-default CA_AIRFRAME 5 # Rover (Ackermann) +param set-default CA_R_REV 1 # Motor is assumed to be reversible +param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying +param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius param set-default EKF2_GBIAS_INIT 0.01 param set-default EKF2_ANGERR_INIT 0.01 -param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius -param set-default NAV_RCL_ACT 6 # Disarm on manual control loss -param set-default COM_FAIL_ACT_T 1 # Delay before failsafe after rc loss diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps index 4acbe8301404..e1a7ecd9ccd2 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps @@ -1,7 +1,7 @@ #!/bin/sh -# Standard apps for a differential drive rover. +# Standard apps for a differential rover. -# Start rover differential drive controller. +# Start rover differential module. rover_differential start # Start Land Detector. diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults index 4cddd44f89e3..7c29ba364f3e 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults @@ -2,9 +2,10 @@ # Differential rover parameters. set VEHICLE_TYPE rover_differential - -param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER -param set-default CA_AIRFRAME 6 # Rover (Differential) -param set-default CA_R_REV 3 # Right and left motors reversible -param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius -param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying +param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER +param set-default CA_AIRFRAME 6 # Rover (Differential) +param set-default CA_R_REV 3 # Right and left motors reversible +param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying +param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius +param set-default EKF2_GBIAS_INIT 0.01 +param set-default EKF2_ANGERR_INIT 0.01 From 588eedb8cbc3d0c777dc433972ba87befe40c6ea Mon Sep 17 00:00:00 2001 From: Peter van der Perk <57130844+PetervdPerk-NXP@users.noreply.github.com> Date: Wed, 7 Aug 2024 15:24:07 +0200 Subject: [PATCH 577/652] px4: sitl fix filepath regression (#23457) --- boards/px4/sitl/default.px4board | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index 784be31db67a..ac228113d5d8 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -1,7 +1,7 @@ CONFIG_PLATFORM_POSIX=y CONFIG_BOARD_TESTING=y CONFIG_BOARD_ETHERNET=y -CONFIG_BOARD_ROOT_PATH="./" +CONFIG_BOARD_ROOT_PATH="." CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_OSD_MSP_OSD=y From 876730a9beefe721c6b723144909d33b699f75d2 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 7 Aug 2024 15:38:55 +0200 Subject: [PATCH 578/652] FW Position Controller: enable flaps during hand/catapult launch (#23460) Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index f636b0e013fd..9571c2986591 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1532,8 +1532,6 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _att_sp.pitch_body = _runway_takeoff.getPitch(get_tecs_pitch()); _att_sp.thrust_body[0] = _runway_takeoff.getThrottle(_param_fw_thr_idle.get(), get_tecs_thrust()); - _flaps_setpoint = _param_fw_flaps_to_scl.get(); - // retract ladning gear once passed the climbout state if (_runway_takeoff.getState() > RunwayTakeoffState::CLIMBOUT) { _new_landing_gear_position = landing_gear_s::GEAR_UP; @@ -1634,6 +1632,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _launch_detection_status_pub.publish(launch_detection_status); } + _flaps_setpoint = _param_fw_flaps_to_scl.get(); _att_sp.roll_body = constrainRollNearGround(_att_sp.roll_body, _current_altitude, _takeoff_ground_alt); if (!_vehicle_status.in_transition_to_fw) { From 176f09b48b49c55eaa91c08cf4b293cf82a60dd1 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Wed, 7 Aug 2024 13:56:31 +0200 Subject: [PATCH 579/652] gz_bridge: add rover world to cmake --- src/modules/simulation/gz_bridge/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/simulation/gz_bridge/CMakeLists.txt b/src/modules/simulation/gz_bridge/CMakeLists.txt index 003a712282f9..c7d36e36a5ad 100644 --- a/src/modules/simulation/gz_bridge/CMakeLists.txt +++ b/src/modules/simulation/gz_bridge/CMakeLists.txt @@ -93,6 +93,7 @@ if(gz-transport_FOUND) windy baylands lawn + rover ) # find corresponding airframes From b488e45e73288f96d54c08cc2778ecc71ec06b63 Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Wed, 7 Aug 2024 12:39:04 +0000 Subject: [PATCH 580/652] Update submodule sitl_gazebo-classic to latest Wed Aug 7 12:39:04 UTC 2024 - sitl_gazebo-classic in PX4/Firmware (28a0de63c5787c10b366aeb0371c5bfe710d0ca7): https://github.com/PX4/PX4-SITL_gazebo-classic/commit/67431d233f0f08de647f0eb11239816f9c8bd6c6 - sitl_gazebo-classic current upstream: https://github.com/PX4/PX4-SITL_gazebo-classic/commit/67af3c3a6da493bdc0a0b9de28b01a2a98d38659 - Changes: https://github.com/PX4/PX4-SITL_gazebo-classic/compare/67431d233f0f08de647f0eb11239816f9c8bd6c6...67af3c3a6da493bdc0a0b9de28b01a2a98d38659 67af3c3 2024-07-18 Silvan Fuhrer - model/lidar: incrase range to 50m (#1049) --- Tools/simulation/gazebo-classic/sitl_gazebo-classic | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/simulation/gazebo-classic/sitl_gazebo-classic b/Tools/simulation/gazebo-classic/sitl_gazebo-classic index 67431d233f0f..67af3c3a6da4 160000 --- a/Tools/simulation/gazebo-classic/sitl_gazebo-classic +++ b/Tools/simulation/gazebo-classic/sitl_gazebo-classic @@ -1 +1 @@ -Subproject commit 67431d233f0f08de647f0eb11239816f9c8bd6c6 +Subproject commit 67af3c3a6da493bdc0a0b9de28b01a2a98d38659 From a39a3e2099c493dbbbfdd08d43a92af6a40b964f Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Wed, 7 Aug 2024 12:39:06 +0000 Subject: [PATCH 581/652] Update submodule gz to latest Wed Aug 7 12:39:06 UTC 2024 - gz in PX4/Firmware (411a328e325e5109a453cf84d0c65393be86bfef): https://github.com/PX4/PX4-gazebo-models/commit/312cd002ff9602644efef58eef93e447c10dcbe8 - gz current upstream: https://github.com/PX4/PX4-gazebo-models/commit/536305adee09b9ace391b16107e625cf7c6db7e7 - Changes: https://github.com/PX4/PX4-gazebo-models/compare/312cd002ff9602644efef58eef93e447c10dcbe8...536305adee09b9ace391b16107e625cf7c6db7e7 536305a 2024-08-07 Claudio Chies - add world for collision prevention (#52) 36f49cb 2024-07-29 Stefano Colli - Add x500 with gimbal model (#47) 4ddfc13 2024-07-24 Jacob Dahl - Downward mono cam + aruco tag (#48) --- Tools/simulation/gz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/simulation/gz b/Tools/simulation/gz index 312cd002ff96..536305adee09 160000 --- a/Tools/simulation/gz +++ b/Tools/simulation/gz @@ -1 +1 @@ -Subproject commit 312cd002ff9602644efef58eef93e447c10dcbe8 +Subproject commit 536305adee09b9ace391b16107e625cf7c6db7e7 From 086c044f471bf6d79c4072481838f50f2ea08dfd Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Wed, 7 Aug 2024 07:26:12 -0800 Subject: [PATCH 582/652] mavlink: log handler rewrite for improved efficiency (#23421) --- src/modules/mavlink/mavlink_log_handler.cpp | 768 +++++++++----------- src/modules/mavlink/mavlink_log_handler.h | 118 +-- 2 files changed, 418 insertions(+), 468 deletions(-) diff --git a/src/modules/mavlink/mavlink_log_handler.cpp b/src/modules/mavlink/mavlink_log_handler.cpp index a75daf90bad7..1afa32382b19 100644 --- a/src/modules/mavlink/mavlink_log_handler.cpp +++ b/src/modules/mavlink/mavlink_log_handler.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2014-2021 PX4 Development Team. All rights reserved. + * Copyright (c) 2014-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 @@ -31,558 +31,498 @@ * ****************************************************************************/ -/// @file mavlink_log_handler.h -/// @author px4dev, Gus Grubba - #include "mavlink_log_handler.h" #include "mavlink_main.h" +#include #include -#include -#include - -#define MOUNTPOINT PX4_STORAGEDIR -static const char *kLogRoot = MOUNTPOINT "/log"; -static const char *kLogData = MOUNTPOINT "/logdata.txt"; -static const char *kTmpData = MOUNTPOINT "/$log$.txt"; +static constexpr int MAX_BYTES_BURST = 256 * 1024; +static const char *kLogListFilePath = PX4_STORAGEDIR "/logdata.txt"; +static const char *kLogListFilePathTemp = PX4_STORAGEDIR "/$log$.txt"; +static const char *kLogDir = PX4_STORAGEDIR "/log"; #ifdef __PX4_NUTTX #define PX4LOG_REGULAR_FILE DTYPE_FILE #define PX4LOG_DIRECTORY DTYPE_DIRECTORY +#define PX4_MAX_FILEPATH CONFIG_PATH_MAX #else +#ifndef PATH_MAX +#define PATH_MAX 1024 // maximum on macOS +#endif #define PX4LOG_REGULAR_FILE DT_REG #define PX4LOG_DIRECTORY DT_DIR +#define PX4_MAX_FILEPATH PATH_MAX #endif -//#define MAVLINK_LOG_HANDLER_VERBOSE - -#ifdef MAVLINK_LOG_HANDLER_VERBOSE -#define PX4LOG_WARN(fmt, ...) warnx(fmt, ##__VA_ARGS__) -#else -#define PX4LOG_WARN(fmt, ...) -#endif +MavlinkLogHandler::MavlinkLogHandler(Mavlink &mavlink) + : _mavlink(mavlink) +{} -//------------------------------------------------------------------- -static bool -stat_file(const char *file, time_t *date = nullptr, uint32_t *size = nullptr) +MavlinkLogHandler::~MavlinkLogHandler() { - struct stat st; - - if (stat(file, &st) == 0) { - if (date) { *date = st.st_mtime; } - - if (size) { *size = st.st_size; } + perf_free(_create_file_elapsed); + perf_free(_listing_elapsed); - return true; + if (_current_entry.fp) { + fclose(_current_entry.fp); } - return false; + unlink(kLogListFilePath); + unlink(kLogListFilePathTemp); } -//------------------------------------------------------------------- -MavlinkLogHandler::MavlinkLogHandler(Mavlink &mavlink) - : _mavlink(mavlink) +void MavlinkLogHandler::send() { + switch (_state) { + case LogHandlerState::Idle: { + state_idle(); + break; + } -} -MavlinkLogHandler::~MavlinkLogHandler() -{ - _close_and_unlink_files(); + case LogHandlerState::Listing: { + state_listing(); + break; + } + + case LogHandlerState::SendingData: { + state_sending_data(); + break; + } + } } -//------------------------------------------------------------------- -void -MavlinkLogHandler::handle_message(const mavlink_message_t *msg) +void MavlinkLogHandler::handle_message(const mavlink_message_t *msg) { switch (msg->msgid) { case MAVLINK_MSG_ID_LOG_REQUEST_LIST: - _log_request_list(msg); + handle_log_request_list(msg); break; case MAVLINK_MSG_ID_LOG_REQUEST_DATA: - _log_request_data(msg); + handle_log_request_data(msg); break; - case MAVLINK_MSG_ID_LOG_ERASE: - _log_request_erase(msg); + case MAVLINK_MSG_ID_LOG_REQUEST_END: + handle_log_request_end(msg); break; - case MAVLINK_MSG_ID_LOG_REQUEST_END: - _log_request_end(msg); + case MAVLINK_MSG_ID_LOG_ERASE: + handle_log_erase(msg); break; } } -//------------------------------------------------------------------- -void -MavlinkLogHandler::send() +void MavlinkLogHandler::state_idle() { - //-- An arbitrary count of max bytes in one go (one of the two below but never both) -#define MAX_BYTES_SEND 256 * 1024 - size_t count = 0; - - //-- Log Entries - while (_current_status == LogHandlerState::Listing - && _mavlink.get_free_tx_buf() > MAVLINK_MSG_ID_LOG_ENTRY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES - && count < MAX_BYTES_SEND) { - count += _log_send_listing(); - } - - //-- Log Data - while (_current_status == LogHandlerState::SendingData - && _mavlink.get_free_tx_buf() > MAVLINK_MSG_ID_LOG_DATA_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES - && count < MAX_BYTES_SEND) { - count += _log_send_data(); + if (_current_entry.fp && _file_send_finished) { + fclose(_current_entry.fp); + _current_entry.fp = nullptr; + + _current_entry.id = 0xffff; + _current_entry.time_utc = 0; + _current_entry.size_bytes = 0; + _current_entry.filepath[0] = 0; + _current_entry.offset = 0; + + _entry_request.id = 0xffff; + _entry_request.start_offset = 0; + _entry_request.byte_count = 0; } } -//------------------------------------------------------------------- -void -MavlinkLogHandler::_log_request_list(const mavlink_message_t *msg) +void MavlinkLogHandler::state_listing() { - mavlink_log_request_list_t request; - mavlink_msg_log_request_list_decode(msg, &request); + static constexpr uint32_t MAVLINK_PACKET_SIZE = MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_LOG_ENTRY_LEN; - //-- Check for re-requests (data loss) or new request - if (_current_status != LogHandlerState::Inactive) { - //-- Is this a new request? - if (request.start == 0) { - _current_status = LogHandlerState::Inactive; - _close_and_unlink_files(); - - } else { - _current_status = LogHandlerState::Idle; - - } + if (_mavlink.get_free_tx_buf() <= MAVLINK_PACKET_SIZE) { + return; } - if (_current_status == LogHandlerState::Inactive) { - //-- Prepare new request - - _reset_list_helper(); - _init_list_helper(); - _current_status = LogHandlerState::Idle; - } + DIR *dp = opendir(kLogDir); - if (_log_count) { - //-- Define (and clamp) range - _next_entry = request.start < _log_count ? request.start : - _log_count - 1; - _last_entry = request.end < _log_count ? request.end : - _log_count - 1; + if (!dp) { + PX4_DEBUG("No logs available"); + return; } - PX4LOG_WARN("\nMavlinkLogHandler::_log_request_list: start: %d last: %d count: %d", - _next_entry, - _last_entry, - _log_count); - //-- Enable streaming - _current_status = LogHandlerState::Listing; -} + FILE *fp = fopen(kLogListFilePath, "r"); -//------------------------------------------------------------------- -void -MavlinkLogHandler::_log_request_data(const mavlink_message_t *msg) -{ - //-- If we haven't listed, we can't do much - if (_current_status == LogHandlerState::Inactive) { - PX4LOG_WARN("MavlinkLogHandler::_log_request_data Log request with no list requested."); + if (!fp) { + PX4_DEBUG("Failed to open log list file"); + closedir(dp); return; } - mavlink_log_request_data_t request; - mavlink_msg_log_request_data_decode(msg, &request); + fseek(fp, _list_request.file_index, SEEK_SET); - //-- Does the requested log exist? - if (request.id >= _log_count) { - PX4LOG_WARN("MavlinkLogHandler::_log_request_data Requested log %" PRIu16 " but we only have %u.", request.id, - _log_count); - return; - } + size_t bytes_sent = 0; - //-- If we were sending log entries, stop it - _current_status = LogHandlerState::Idle; + char line[PX4_MAX_FILEPATH]; - if (_current_log_index != request.id) { - //-- Init send log dataset - _current_log_filename[0] = 0; - _current_log_index = request.id; - uint32_t time_utc = 0; + perf_begin(_listing_elapsed); - if (!_get_entry(_current_log_index, _current_log_size, time_utc, - _current_log_filename, sizeof(_current_log_filename))) { - PX4LOG_WARN("LogListHelper::get_entry failed."); - return; + while (fgets(line, sizeof(line), fp)) { + + if (_list_request.current_id < _list_request.first_id) { + _list_request.current_id++; + continue; } - _open_for_transmit(); - } + // We can send! + uint32_t size_bytes = 0; + uint32_t time_utc = 0; + char filepath[PX4_MAX_FILEPATH]; - _current_log_data_offset = request.ofs; + // If parsed lined successfully, send the entry + if (sscanf(line, "%" PRIu32 " %" PRIu32 " %s", &time_utc, &size_bytes, filepath) != 3) { + PX4_DEBUG("sscanf failed"); + continue; + } - if (_current_log_data_offset >= _current_log_size) { - _current_log_data_remaining = 0; + send_log_entry(time_utc, size_bytes); + bytes_sent += sizeof(mavlink_log_entry_t); + _list_request.current_id++; - } else { - _current_log_data_remaining = _current_log_size - request.ofs; + // Yield if we've exceed mavlink burst or buffer limit + if (_mavlink.get_free_tx_buf() <= MAVLINK_PACKET_SIZE || bytes_sent >= MAX_BYTES_BURST) { + _list_request.file_index = ftell(fp); + fclose(fp); + closedir(dp); + perf_end(_listing_elapsed); + return; + } } - if (_current_log_data_remaining > request.count) { - _current_log_data_remaining = request.count; - } + perf_end(_listing_elapsed); - //-- Enable streaming - _current_status = LogHandlerState::SendingData; -} + fclose(fp); + closedir(dp); -//------------------------------------------------------------------- -void -MavlinkLogHandler::_log_request_erase(const mavlink_message_t * /*msg*/) -{ - /* - mavlink_log_erase_t request; - mavlink_msg_log_erase_decode(msg, &request); - */ - _current_status = LogHandlerState::Inactive; - _close_and_unlink_files(); - - //-- Delete all logs - _delete_all(kLogRoot); + _list_request.current_id = 0; + _list_request.file_index = 0; + _state = LogHandlerState::Idle; } -//------------------------------------------------------------------- -void -MavlinkLogHandler::_log_request_end(const mavlink_message_t * /*msg*/) +void MavlinkLogHandler::state_sending_data() { - PX4LOG_WARN("MavlinkLogHandler::_log_request_end"); + static constexpr uint32_t MAVLINK_PACKET_SIZE = MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_LOG_DATA_LEN; + size_t bytes_sent = 0; - _current_status = LogHandlerState::Inactive; - _close_and_unlink_files(); -} + while (_mavlink.get_free_tx_buf() > MAVLINK_PACKET_SIZE && bytes_sent < MAX_BYTES_BURST) { -//------------------------------------------------------------------- -size_t -MavlinkLogHandler::_log_send_listing() -{ - mavlink_log_entry_t response; - uint32_t size, date; - _get_entry(_next_entry, size, date); - response.size = size; - response.time_utc = date; - response.id = _next_entry; - response.num_logs = _log_count; - response.last_log_num = _last_entry; - mavlink_msg_log_entry_send_struct(_mavlink.get_channel(), &response); - - //-- If we're done listing, flag it. - if (_next_entry >= _last_entry) { - _current_status = LogHandlerState::Idle; - - } else { - _next_entry++; - } + // Only seek if we need to + long int offset = _current_entry.offset - ftell(_current_entry.fp); - PX4LOG_WARN("MavlinkLogHandler::_log_send_listing id: %" PRIu16 " count: %" PRIu16 " last: %" PRIu16 " size: %" PRIu32 - " date: %" PRIu32 " status: %" PRIu32, - response.id, - response.num_logs, - response.last_log_num, - response.size, - response.time_utc, - (uint32_t)_current_status); - return sizeof(response); -} + if (offset && fseek(_current_entry.fp, offset, SEEK_CUR)) { + fclose(_current_entry.fp); + _current_entry.fp = nullptr; + PX4_DEBUG("seek error"); + _state = LogHandlerState::Idle; + } -//------------------------------------------------------------------- -size_t -MavlinkLogHandler::_log_send_data() -{ - mavlink_log_data_t response; - memset(&response, 0, sizeof(response)); - uint32_t len = _current_log_data_remaining; + // Prepare mavlink message + mavlink_log_data_t msg; - if (len > sizeof(response.data)) { - len = sizeof(response.data); - } + if (_current_entry.offset >= _current_entry.size_bytes) { + PX4_DEBUG("Entry offset equal to file size"); + _state = LogHandlerState::Idle; + return; + } - size_t read_size = _get_log_data(len, response.data); - response.ofs = _current_log_data_offset; - response.id = _current_log_index; - response.count = read_size; - mavlink_msg_log_data_send_struct(_mavlink.get_channel(), &response); - _current_log_data_offset += read_size; - _current_log_data_remaining -= read_size; + size_t bytes_to_read = _current_entry.size_bytes - _current_entry.offset; - if (read_size < sizeof(response.data) || _current_log_data_remaining == 0) { - _current_status = LogHandlerState::Idle; - } + if (bytes_to_read > sizeof(msg.data)) { + bytes_to_read = sizeof(msg.data); + } - return sizeof(response); -} + msg.count = fread(msg.data, 1, bytes_to_read, _current_entry.fp); + msg.id = _current_entry.id; + msg.ofs = _current_entry.offset; -//------------------------------------------------------------------- -void MavlinkLogHandler::_close_and_unlink_files() -{ - if (_current_log_filep) { - ::fclose(_current_log_filep); - _reset_list_helper(); - } + mavlink_msg_log_data_send_struct(_mavlink.get_channel(), &msg); + + bytes_sent += MAVLINK_PACKET_SIZE; + _current_entry.offset += msg.count; + + bool chunk_finished = _current_entry.offset >= (_entry_request.byte_count + _entry_request.start_offset); + _file_send_finished = _current_entry.offset >= _current_entry.size_bytes; - // Remove log data files (if any) - unlink(kLogData); - unlink(kTmpData); + if (chunk_finished || _file_send_finished) { + _state = LogHandlerState::Idle; + return; + } + } } -//------------------------------------------------------------------- -bool -MavlinkLogHandler::_get_entry(int idx, uint32_t &size, uint32_t &date, char *filename, int filename_len) +void MavlinkLogHandler::handle_log_request_list(const mavlink_message_t *msg) { - //-- Find log file in log list file created during init() - size = 0; - date = 0; - bool result = false; - //-- Open list of log files - FILE *f = ::fopen(kLogData, "r"); - - if (f) { - //--- Find requested entry - char line[160]; - int count = 0; - - while (fgets(line, sizeof(line), f)) { - //-- Found our "index" - if (count++ == idx) { - char file[160]; - - if (sscanf(line, "%" PRIu32 " %" PRIu32 " %s", &date, &size, file) == 3) { - if (filename && filename_len > 0) { - strncpy(filename, file, filename_len); - filename[filename_len - 1] = 0; // ensure null-termination - } - - result = true; - break; - } - } - } + mavlink_log_request_list_t request; + mavlink_msg_log_request_list_decode(msg, &request); - fclose(f); + if (!create_log_list_file()) { + return; } - return result; + _list_request.first_id = request.start; + _list_request.last_id = request.end == 0xffff ? _num_logs : request.end; + _list_request.current_id = 0; + _list_request.file_index = 0; + _logs_listed = true; + _state = LogHandlerState::Listing; } -//------------------------------------------------------------------- -bool -MavlinkLogHandler::_open_for_transmit() +void MavlinkLogHandler::handle_log_request_data(const mavlink_message_t *msg) { - if (_current_log_filep) { - ::fclose(_current_log_filep); - _current_log_filep = nullptr; + if (!_logs_listed) { + PX4_DEBUG("Logs not yet listed"); + _state = LogHandlerState::Idle; + return; } - _current_log_filep = ::fopen(_current_log_filename, "rb"); + mavlink_log_request_data_t request; + mavlink_msg_log_request_data_decode(msg, &request); - if (!_current_log_filep) { - PX4LOG_WARN("MavlinkLogHandler::open_for_transmit Could not open %s", _current_log_filename); - return false; + if (request.id >= _num_logs) { + PX4_DEBUG("Requested log %" PRIu16 " but we only have %u", request.id, _num_logs); + _state = LogHandlerState::Idle; + return; } - return true; -} + // Handle switching to new request ID + if (request.id != _current_entry.id) { + // Close the old file + if (_current_entry.fp) { + fclose(_current_entry.fp); + _current_entry.fp = nullptr; + } -//------------------------------------------------------------------- -size_t -MavlinkLogHandler::_get_log_data(uint8_t len, uint8_t *buffer) -{ - if (!_current_log_filename[0]) { - return 0; - } + LogEntry entry = {}; - if (!_current_log_filep) { - PX4LOG_WARN("MavlinkLogHandler::get_log_data file not open %s", _current_log_filename); - return 0; - } + if (!log_entry_from_id(request.id, &entry)) { + PX4_DEBUG("Log file ID %u does not exist", request.id); + _state = LogHandlerState::Idle; + return; + } - long int offset = _current_log_data_offset - ftell(_current_log_filep); + entry.fp = fopen(entry.filepath, "rb"); + entry.offset = request.ofs; - if (offset && fseek(_current_log_filep, offset, SEEK_CUR)) { - fclose(_current_log_filep); - _current_log_filep = nullptr; - PX4LOG_WARN("MavlinkLogHandler::get_log_data Seek error in %s", _current_log_filename); - return 0; + if (!entry.fp) { + PX4_DEBUG("Failed to open file %s", entry.filepath); + return; + } + + _current_entry = entry; } - size_t result = fread(buffer, 1, len, _current_log_filep); - return result; -} + // Stop if offset request is larger than file + if (request.ofs >= _current_entry.size_bytes) { + PX4_DEBUG("Request offset %" PRIu32 "greater than file size %" PRIu32, request.ofs, + _current_entry.size_bytes); + _state = LogHandlerState::Idle; + return; + } + _entry_request.id = request.id; + _entry_request.start_offset = request.ofs; + _entry_request.byte_count = request.count; + // Set the offset of the current entry to the requested offset + _current_entry.offset = _entry_request.start_offset; + _file_send_finished = false; + _state = LogHandlerState::SendingData; +} -void -MavlinkLogHandler::_reset_list_helper() +void MavlinkLogHandler::handle_log_request_end(const mavlink_message_t *msg) { - _next_entry = 0; - _last_entry = 0; - _log_count = 0; - _current_log_index = UINT16_MAX; - _current_log_size = 0; - _current_log_data_offset = 0; - _current_log_data_remaining = 0; - _current_log_filep = nullptr; + _state = LogHandlerState::Idle; } -void -MavlinkLogHandler::_init_list_helper() +void MavlinkLogHandler::handle_log_erase(const mavlink_message_t *msg) { - /* + if (_current_entry.fp) { + fclose(_current_entry.fp); + _current_entry.fp = nullptr; + } + + _state = LogHandlerState::Idle; + unlink(kLogListFilePath); + unlink(kLogListFilePathTemp); - When this helper is created, it scans the log directory - and collects all log files found into one file for easy, - subsequent access. - */ + delete_all_logs(kLogDir); +} - _current_log_filename[0] = 0; +bool MavlinkLogHandler::create_log_list_file() +{ + perf_begin(_create_file_elapsed); - // Remove old log data file (if any) - unlink(kLogData); - // Open log directory - DIR *dp = opendir(kLogRoot); + // clean up old file + unlink(kLogListFilePath); + _num_logs = 0; - if (dp == nullptr) { - // No log directory. Nothing to do. - return; + DIR *dp = opendir(kLogDir); + + if (!dp) { + PX4_DEBUG("No logs available"); + return false; } - // Create work file - FILE *f = ::fopen(kTmpData, "w"); + FILE *temp_fp = fopen(kLogListFilePathTemp, "w"); - if (!f) { - PX4LOG_WARN("MavlinkLogHandler::init Error creating %s", kTmpData); + if (!temp_fp) { + PX4_DEBUG("Failed to create temp file"); closedir(dp); - return; + return false; } - // Scan directory and collect log files struct dirent *result = nullptr; - while ((result = readdir(dp))) { - if (result->d_type == PX4LOG_DIRECTORY) { - time_t tt = 0; - char log_path[128]; - int ret = snprintf(log_path, sizeof(log_path), "%s/%s", kLogRoot, result->d_name); - bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_path)); + // Iterate over the log/ directory which contains subdirectories formatted: yyyy-mm-dd + while (1) { + result = readdir(dp); - if (path_is_ok) { - if (_get_session_date(log_path, result->d_name, tt)) { - _scan_logs(f, log_path, tt); - } - } + if (!result) { + // Reached end of directory + break; + } + + if (result->d_type != PX4LOG_DIRECTORY) { + // Skip stray files + continue; + } + + // Skip the '.' and '..' entries + if (strcmp(result->d_name, ".") == 0 || strcmp(result->d_name, "..") == 0) { + continue; + } + + // Open up the sub directory + char dirpath[PX4_MAX_FILEPATH]; + int ret = snprintf(dirpath, sizeof(dirpath), "%s/%s", kLogDir, result->d_name); + + bool path_is_ok = (ret > 0) && (ret < (int)sizeof(dirpath)); + + if (!path_is_ok) { + PX4_DEBUG("Log subdir path error: %s", dirpath); + continue; } + + // Iterate over files inside the subdir and write them to the file + write_entries_to_file(temp_fp, dirpath); } + fclose(temp_fp); closedir(dp); - fclose(f); // Rename temp file to data file - if (rename(kTmpData, kLogData)) { - PX4LOG_WARN("MavlinkLogHandler::init Error renaming %s", kTmpData); - _log_count = 0; + if (rename(kLogListFilePathTemp, kLogListFilePath)) { + PX4_DEBUG("Failed to rename temp file"); + return false; } + + perf_end(_create_file_elapsed); + + return true; } -//------------------------------------------------------------------- -bool -MavlinkLogHandler::_get_session_date(const char *path, const char *dir, time_t &date) +void MavlinkLogHandler::write_entries_to_file(FILE *fp, const char *dir) { - if (strlen(dir) > 4) { - // Always try to get file time first - if (stat_file(path, &date)) { - // Try to prevent taking date if it's around 1970 (use the logic below instead) - if (date > 60 * 60 * 24) { - return true; - } + DIR *dp = opendir(dir); + struct dirent *result = nullptr; + + while (1) { + result = readdir(dp); + + if (!result) { + // Reached end of directory + break; } - // Convert "sess000" to 00:00 Jan 1 1970 (day per session) - if (strncmp(dir, "sess", 4) == 0) { - unsigned u; + if (result->d_type != PX4LOG_REGULAR_FILE) { + // Skip non files + continue; + } - if (sscanf(&dir[4], "%u", &u) == 1) { - date = u * 60 * 60 * 24; - return true; - } + char filepath[PX4_MAX_FILEPATH]; + int ret = snprintf(filepath, sizeof(filepath), "%s/%s", dir, result->d_name); + bool path_is_ok = (ret > 0) && (ret < (int)sizeof(filepath)); + + if (!path_is_ok) { + PX4_DEBUG("Log subdir path error: %s", filepath); + continue; + } + + struct stat filestat; + + if (stat(filepath, &filestat) != 0) { + PX4_DEBUG("stat() failed: %s", filepath); + continue; } + + // Write to file using format: + // [ time ] [ size_bytes ] [ filepath ] + fprintf(fp, "%u %u %s\n", unsigned(filestat.st_mtime), unsigned(filestat.st_size), filepath); + _num_logs++; } - return false; + closedir(dp); } -//------------------------------------------------------------------- -void -MavlinkLogHandler::_scan_logs(FILE *f, const char *dir, time_t &date) +void MavlinkLogHandler::send_log_entry(uint32_t time_utc, uint32_t size_bytes) { - DIR *dp = opendir(dir); + mavlink_log_entry_t msg; + msg.time_utc = time_utc; + msg.size = size_bytes; + msg.id = _list_request.current_id; + msg.num_logs = _num_logs; + msg.last_log_num = _list_request.last_id; + mavlink_msg_log_entry_send_struct(_mavlink.get_channel(), &msg); +} - if (dp) { - struct dirent *result = nullptr; - - while ((result = readdir(dp))) { - if (result->d_type == PX4LOG_REGULAR_FILE) { - time_t ldate = date; - uint32_t size = 0; - char log_file_path[128]; - int ret = snprintf(log_file_path, sizeof(log_file_path), "%s/%s", dir, result->d_name); - bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_file_path)); - - if (path_is_ok) { - if (_get_log_time_size(log_file_path, result->d_name, ldate, size)) { - //-- Write result->out to list file - fprintf(f, "%u %u %s\n", (unsigned)ldate, (unsigned)size, log_file_path); - _log_count++; - } - } - } - } +bool MavlinkLogHandler::log_entry_from_id(uint16_t log_id, LogEntry *entry) +{ + DIR *dp = opendir(kLogDir); + + if (!dp) { + PX4_INFO("No logs available"); + return false; + } + + FILE *fp = fopen(kLogListFilePath, "r"); + if (!fp) { + PX4_DEBUG("Failed to open %s", kLogListFilePath); closedir(dp); + return false; } -} -//------------------------------------------------------------------- -bool -MavlinkLogHandler::_get_log_time_size(const char *path, const char *file, time_t &date, uint32_t &size) -{ - if (file && file[0]) { - if (strstr(file, ".px4log") || strstr(file, ".ulg")) { - // Always try to get file time first - if (stat_file(path, &date, &size)) { - // Try to prevent taking date if it's around 1970 (use the logic below instead) - if (date > 60 * 60 * 24) { - return true; - } - } + bool found_entry = false; + uint16_t current_id = 0; + char line[PX4_MAX_FILEPATH]; - // Convert "log000" to 00:00 (minute per flight in session) - if (strncmp(file, "log", 3) == 0) { - unsigned u; + while (fgets(line, sizeof(line), fp)) { - if (sscanf(&file[3], "%u", &u) == 1) { - date += (u * 60); + if (current_id != log_id) { + current_id++; + continue; + } - if (stat_file(path, nullptr, &size)) { - return true; - } - } - } + if (sscanf(line, "%" PRIu32 " %" PRIu32 " %s", &(entry->time_utc), &(entry->size_bytes), entry->filepath) != 3) { + PX4_DEBUG("sscanf failed"); + continue; } + + entry->id = log_id; + found_entry = true; + break; } - return false; + fclose(fp); + closedir(dp); + + return found_entry; } -//------------------------------------------------------------------- -void -MavlinkLogHandler::_delete_all(const char *dir) +void MavlinkLogHandler::delete_all_logs(const char *dir) { //-- Open log directory DIR *dp = opendir(dir); @@ -600,27 +540,27 @@ MavlinkLogHandler::_delete_all(const char *dir) } if (result->d_type == PX4LOG_DIRECTORY && result->d_name[0] != '.') { - char log_path[128]; - int ret = snprintf(log_path, sizeof(log_path), "%s/%s", dir, result->d_name); - bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_path)); + char filepath[PX4_MAX_FILEPATH]; + int ret = snprintf(filepath, sizeof(filepath), "%s/%s", dir, result->d_name); + bool path_is_ok = (ret > 0) && (ret < (int)sizeof(filepath)); if (path_is_ok) { - _delete_all(log_path); //Recursive call. TODO: consider add protection + delete_all_logs(filepath); - if (rmdir(log_path)) { - PX4LOG_WARN("MavlinkLogHandler::delete_all Error removing %s", log_path); + if (rmdir(filepath)) { + PX4_DEBUG("Error removing %s", filepath); } } } if (result->d_type == PX4LOG_REGULAR_FILE) { - char log_path[128]; - int ret = snprintf(log_path, sizeof(log_path), "%s/%s", dir, result->d_name); - bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_path)); + char filepath[PX4_MAX_FILEPATH]; + int ret = snprintf(filepath, sizeof(filepath), "%s/%s", dir, result->d_name); + bool path_is_ok = (ret > 0) && (ret < (int)sizeof(filepath)); if (path_is_ok) { - if (unlink(log_path)) { - PX4LOG_WARN("MavlinkLogHandler::delete_all Error deleting %s", log_path); + if (unlink(filepath)) { + PX4_DEBUG("Error unlinking %s", filepath); } } } diff --git a/src/modules/mavlink/mavlink_log_handler.h b/src/modules/mavlink/mavlink_log_handler.h index 965c26712f1c..eb521a61ee4f 100644 --- a/src/modules/mavlink/mavlink_log_handler.h +++ b/src/modules/mavlink/mavlink_log_handler.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2014, 2020 PX4 Development Team. All rights reserved. + * Copyright (c) 2014-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 @@ -33,76 +33,86 @@ #pragma once -/// @file mavlink_log_handler.h -/// @author px4dev, Gus Grubba - -#include -#include -#include -#include -#include -#include - +#include #include "mavlink_bridge_header.h" class Mavlink; -// MAVLink LOG_* Message Handler class MavlinkLogHandler { public: MavlinkLogHandler(Mavlink &mavlink); ~MavlinkLogHandler(); - // Handle possible LOG message + void send(); void handle_message(const mavlink_message_t *msg); - /** - * Handle sending of messages. Call this regularly at a fixed frequency. - * @param t current time - */ - void send(); +private: + struct LogEntry { + uint16_t id{0xffff}; + uint32_t time_utc{}; + uint32_t size_bytes{}; + FILE *fp{nullptr}; + char filepath[60]; + uint32_t offset{}; + }; - unsigned get_size(); + struct LogEntryRequest { + uint16_t id{0xffff}; + uint32_t start_offset{}; + uint32_t byte_count{}; + }; + + struct LogListRequest { + uint16_t first_id{0}; + uint16_t last_id{0}; + uint16_t current_id{0}; + int file_index{0}; + }; -private: enum class LogHandlerState { - Inactive, //There is no active action of log handler - Idle, //The log handler is not sending list/data, but list has been sent - Listing, //File list is being send - SendingData //File Data is being send + Idle, + Listing, + SendingData }; - void _log_message(const mavlink_message_t *msg); - void _log_request_list(const mavlink_message_t *msg); - void _log_request_data(const mavlink_message_t *msg); - void _log_request_erase(const mavlink_message_t *msg); - void _log_request_end(const mavlink_message_t *msg); - - void _reset_list_helper(); - void _init_list_helper(); - bool _get_session_date(const char *path, const char *dir, time_t &date); - void _scan_logs(FILE *f, const char *dir, time_t &date); - bool _get_log_time_size(const char *path, const char *file, time_t &date, uint32_t &size); - static void _delete_all(const char *dir); - bool _get_entry(int idx, uint32_t &size, uint32_t &date, char *filename = 0, int filename_len = 0); - bool _open_for_transmit(); - size_t _get_log_data(uint8_t len, uint8_t *buffer); - void _close_and_unlink_files(); - - size_t _log_send_listing(); - size_t _log_send_data(); - - LogHandlerState _current_status{LogHandlerState::Inactive}; + + // mavlink message handlers + void handle_log_request_list(const mavlink_message_t *msg); + void handle_log_request_data(const mavlink_message_t *msg); + void handle_log_request_end(const mavlink_message_t *msg); + void handle_log_erase(const mavlink_message_t *msg); + + // state functions + void state_idle(); + void state_listing(); + void state_sending_data(); + + // Log request list + bool create_log_list_file(); + void write_entries_to_file(FILE *f, const char *dir); + void send_log_entry(uint32_t size, uint32_t time_utc); + + // Log request data + bool log_entry_from_id(uint16_t log_id, LogEntry *entry); + + // Log erase + void delete_all_logs(const char *dir); + + +private: + LogHandlerState _state{LogHandlerState::Idle}; Mavlink &_mavlink; - int _next_entry{0}; - int _last_entry{0}; - int _log_count{0}; + // Log list + LogListRequest _list_request{}; + int _num_logs{0}; + bool _logs_listed{false}; + + // Log data + LogEntry _current_entry{}; + LogEntryRequest _entry_request{}; + bool _file_send_finished{}; - uint16_t _current_log_index{UINT16_MAX}; - uint32_t _current_log_size{0}; - uint32_t _current_log_data_offset{0}; - uint32_t _current_log_data_remaining{0}; - FILE *_current_log_filep{nullptr}; - char _current_log_filename[128]; //TODO: consider to allocate on runtime + perf_counter_t _create_file_elapsed{perf_alloc(PC_ELAPSED, MODULE_NAME": create file")}; + perf_counter_t _listing_elapsed{perf_alloc(PC_ELAPSED, MODULE_NAME": listing")}; }; From 2d99ae18ad2a6645305130fa659e9bb911de1306 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 8 Aug 2024 03:41:50 +1200 Subject: [PATCH 583/652] stm32h7: Reset USART clock selection (#23498) This resets the USARTs' clock source selection to the default, in case it has been changed by the bootloader. This is required if booting from the ArduPilot bootloader which happens to reset the clock selection to PLL. Without this fix, UARTs (including the console) is garbled, so presumably at an invalid baudrate. --- boards/cubepilot/cubeorange/nuttx-config/include/board.h | 6 ++++++ .../cubepilot/cubeorangeplus/nuttx-config/include/board.h | 6 ++++++ boards/px4/fmu-v6c/nuttx-config/include/board.h | 6 ++++++ boards/px4/fmu-v6x/nuttx-config/include/board.h | 6 ++++++ platforms/nuttx/NuttX/nuttx | 2 +- 5 files changed, 25 insertions(+), 1 deletion(-) diff --git a/boards/cubepilot/cubeorange/nuttx-config/include/board.h b/boards/cubepilot/cubeorange/nuttx-config/include/board.h index 5827b1bc81d1..62605f98d13a 100644 --- a/boards/cubepilot/cubeorange/nuttx-config/include/board.h +++ b/boards/cubepilot/cubeorange/nuttx-config/include/board.h @@ -194,6 +194,12 @@ #define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */ +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* FLASH wait states */ #define BOARD_FLASH_WAITSTATES 2 diff --git a/boards/cubepilot/cubeorangeplus/nuttx-config/include/board.h b/boards/cubepilot/cubeorangeplus/nuttx-config/include/board.h index d650c6169118..babaf587e450 100644 --- a/boards/cubepilot/cubeorangeplus/nuttx-config/include/board.h +++ b/boards/cubepilot/cubeorangeplus/nuttx-config/include/board.h @@ -195,6 +195,12 @@ #define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */ +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* FLASH wait states */ #define BOARD_FLASH_WAITSTATES 2 diff --git a/boards/px4/fmu-v6c/nuttx-config/include/board.h b/boards/px4/fmu-v6c/nuttx-config/include/board.h index 1951031cb825..4b4b128cf2ba 100644 --- a/boards/px4/fmu-v6c/nuttx-config/include/board.h +++ b/boards/px4/fmu-v6c/nuttx-config/include/board.h @@ -246,6 +246,12 @@ #define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* ADC 1 2 3 clock source */ #define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 diff --git a/boards/px4/fmu-v6x/nuttx-config/include/board.h b/boards/px4/fmu-v6x/nuttx-config/include/board.h index d6b2925b795c..7907eafad194 100644 --- a/boards/px4/fmu-v6x/nuttx-config/include/board.h +++ b/boards/px4/fmu-v6x/nuttx-config/include/board.h @@ -250,6 +250,12 @@ #define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* FDCAN 1 2 clock source */ #define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index d3b85f3e545d..5d74bc138955 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit d3b85f3e545de3692c100143f4a9ae67762ce679 +Subproject commit 5d74bc138955e6f010a38e0f87f34e9a9019aecc From a8d54c7fae573852a1c7b81d6bf4ae5f0b7bfce8 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 7 Aug 2024 14:31:32 +0200 Subject: [PATCH 584/652] mixer_module: Reset RC passthrough functions to disarmed value when no stick input --- .../functions/FunctionManualRC.hpp | 38 ++++++++++++------- 1 file changed, 24 insertions(+), 14 deletions(-) diff --git a/src/lib/mixer_module/functions/FunctionManualRC.hpp b/src/lib/mixer_module/functions/FunctionManualRC.hpp index 38f7d096a94e..171c28a81750 100644 --- a/src/lib/mixer_module/functions/FunctionManualRC.hpp +++ b/src/lib/mixer_module/functions/FunctionManualRC.hpp @@ -45,9 +45,7 @@ class FunctionManualRC : public FunctionProviderBase public: FunctionManualRC() { - for (int i = 0; i < num_data_points; ++i) { - _data[i] = NAN; - } + resetAllToDisarmedValue(); } static FunctionProviderBase *allocate(const Context &context) { return new FunctionManualRC(); } @@ -57,17 +55,22 @@ class FunctionManualRC : public FunctionProviderBase manual_control_setpoint_s manual_control_setpoint; if (_topic.update(&manual_control_setpoint)) { - _data[0] = manual_control_setpoint.roll; - _data[1] = manual_control_setpoint.pitch; - _data[2] = manual_control_setpoint.throttle; - _data[3] = manual_control_setpoint.yaw; - _data[4] = manual_control_setpoint.flaps; - _data[5] = manual_control_setpoint.aux1; - _data[6] = manual_control_setpoint.aux2; - _data[7] = manual_control_setpoint.aux3; - _data[8] = manual_control_setpoint.aux4; - _data[9] = manual_control_setpoint.aux5; - _data[10] = manual_control_setpoint.aux6; + if (manual_control_setpoint.valid) { + _data[0] = manual_control_setpoint.roll; + _data[1] = manual_control_setpoint.pitch; + _data[2] = manual_control_setpoint.throttle; + _data[3] = manual_control_setpoint.yaw; + _data[4] = manual_control_setpoint.flaps; + _data[5] = manual_control_setpoint.aux1; + _data[6] = manual_control_setpoint.aux2; + _data[7] = manual_control_setpoint.aux3; + _data[8] = manual_control_setpoint.aux4; + _data[9] = manual_control_setpoint.aux5; + _data[10] = manual_control_setpoint.aux6; + + } else { + resetAllToDisarmedValue(); + } } } @@ -76,6 +79,13 @@ class FunctionManualRC : public FunctionProviderBase private: static constexpr int num_data_points = 11; + void resetAllToDisarmedValue() + { + for (int i = 0; i < num_data_points; ++i) { + _data[i] = NAN; + } + } + static_assert(num_data_points == (int)OutputFunction::RC_AUXMax - (int)OutputFunction::RC_Roll + 1, "number of functions mismatch"); From e2f5debf777023aa15f79caea8cfce7c2371c76a Mon Sep 17 00:00:00 2001 From: Jeremy Zanzig Date: Fri, 10 May 2024 13:26:59 -0700 Subject: [PATCH 585/652] change pairing LED feedback to 20 fast flashes of white --- src/lib/button/ButtonPublisher.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/lib/button/ButtonPublisher.cpp b/src/lib/button/ButtonPublisher.cpp index b3b35a7b3af1..826e5ed49f9a 100644 --- a/src/lib/button/ButtonPublisher.cpp +++ b/src/lib/button/ButtonPublisher.cpp @@ -70,9 +70,9 @@ void ButtonPublisher::pairingButtonTriggerEvent() led_control_s led_control{}; led_control.led_mask = 0xff; led_control.mode = led_control_s::MODE_BLINK_FAST; - led_control.color = led_control_s::COLOR_GREEN; - led_control.num_blinks = 1; - led_control.priority = 0; + led_control.color = led_control_s::COLOR_WHITE; + led_control.num_blinks = 20; + led_control.priority = 2; led_control.timestamp = hrt_absolute_time(); _led_control_pub.publish(led_control); From b01c179eed3564066a43ff0f734730ffc9f4dfca Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 2 Aug 2024 16:17:45 +0200 Subject: [PATCH 586/652] NavigatorMissionItem.msg: remove instance_count This information is duplicate to mission_result/mission_id. Signed-off-by: Silvan Fuhrer --- msg/NavigatorMissionItem.msg | 2 -- src/modules/navigator/mission_base.cpp | 1 - src/modules/navigator/navigator.h | 2 -- 3 files changed, 5 deletions(-) diff --git a/msg/NavigatorMissionItem.msg b/msg/NavigatorMissionItem.msg index 64af762f75d8..a10aa4656d51 100644 --- a/msg/NavigatorMissionItem.msg +++ b/msg/NavigatorMissionItem.msg @@ -1,7 +1,5 @@ uint64 timestamp # time since system start (microseconds) -uint32 instance_count # Instance count of this mission. Increments monotonically whenever the mission is modified - uint16 sequence_current # Sequence of the current mission item uint16 nav_cmd diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index 0a9a76bd2b34..d41456ccce66 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -870,7 +870,6 @@ void MissionBase::publish_navigator_mission_item() { navigator_mission_item_s navigator_mission_item{}; - navigator_mission_item.instance_count = _navigator->mission_instance_count(); navigator_mission_item.sequence_current = _mission.current_seq; navigator_mission_item.nav_cmd = _mission_item.nav_cmd; navigator_mission_item.latitude = _mission_item.lat; diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 93f630dbf525..45c4f158b7c4 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -249,8 +249,6 @@ class Navigator : public ModuleBase, public ModuleParams orb_advert_t *get_mavlink_log_pub() { return &_mavlink_log_pub; } - int mission_instance_count() const { return _mission_result.mission_id; } - void set_mission_failure_heading_timeout(); bool get_mission_start_land_available() { return _mission.get_land_start_available(); } From 588c4a04c8154a9a94c04133f2eb11895c0029fb Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 6 Aug 2024 22:15:25 +0200 Subject: [PATCH 587/652] RTL direct: publish NavigatorMissionItem Signed-off-by: Silvan Fuhrer --- src/modules/navigator/rtl_direct.cpp | 31 ++++++++++++++++++++++++++++ src/modules/navigator/rtl_direct.h | 8 +++++++ 2 files changed, 39 insertions(+) diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index b028c7fb358f..52e853733eeb 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -337,6 +337,8 @@ void RtlDirect::set_rtl_item() _navigator->set_position_setpoint_triplet_updated(); } } + + publish_rtl_direct_navigator_mission_item(); // for logging } RtlDirect::RTLState RtlDirect::getActivationLandState() @@ -515,3 +517,32 @@ loiter_point_s RtlDirect::sanitizeLandApproach(loiter_point_s land_approach) con return sanitized_land_approach; } + +void RtlDirect::publish_rtl_direct_navigator_mission_item() +{ + navigator_mission_item_s navigator_mission_item{}; + + navigator_mission_item.sequence_current = static_cast(_rtl_state); + navigator_mission_item.nav_cmd = _mission_item.nav_cmd; + navigator_mission_item.latitude = _mission_item.lat; + navigator_mission_item.longitude = _mission_item.lon; + navigator_mission_item.altitude = _mission_item.altitude; + + navigator_mission_item.time_inside = get_time_inside(_mission_item); + navigator_mission_item.acceptance_radius = _mission_item.acceptance_radius; + navigator_mission_item.loiter_radius = _mission_item.loiter_radius; + navigator_mission_item.yaw = _mission_item.yaw; + + navigator_mission_item.frame = _mission_item.frame; + navigator_mission_item.frame = _mission_item.origin; + + navigator_mission_item.loiter_exit_xtrack = _mission_item.loiter_exit_xtrack; + navigator_mission_item.force_heading = _mission_item.force_heading; + navigator_mission_item.altitude_is_relative = _mission_item.altitude_is_relative; + navigator_mission_item.autocontinue = _mission_item.autocontinue; + navigator_mission_item.vtol_back_transition = _mission_item.vtol_back_transition; + + navigator_mission_item.timestamp = hrt_absolute_time(); + + _navigator_mission_item_pub.publish(navigator_mission_item); +} diff --git a/src/modules/navigator/rtl_direct.h b/src/modules/navigator/rtl_direct.h index 211b2779eae0..b1f6a75b81ae 100644 --- a/src/modules/navigator/rtl_direct.h +++ b/src/modules/navigator/rtl_direct.h @@ -47,6 +47,7 @@ #include #include #include +#include #include #include #include @@ -137,6 +138,12 @@ class RtlDirect : public MissionBlock, public ModuleParams */ void parameters_update(); + /** + * @brief Publish navigator mission item + * + */ + void publish_rtl_direct_navigator_mission_item(); + RTLState getActivationLandState(); void setLoiterPosition(); @@ -167,4 +174,5 @@ class RtlDirect : public MissionBlock, public ModuleParams uORB::SubscriptionData _land_detected_sub{ORB_ID(vehicle_land_detected)}; /**< vehicle land detected subscription */ uORB::SubscriptionData _vehicle_status_sub{ORB_ID(vehicle_status)}; /**< vehicle status subscription */ uORB::SubscriptionData _wind_sub{ORB_ID(wind)}; + uORB::Publication _navigator_mission_item_pub{ORB_ID::navigator_mission_item}; /**< Navigator mission item publication*/ }; From a737036633764b760d36828d16378dedbe0faed1 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 6 Aug 2024 23:38:38 +0200 Subject: [PATCH 588/652] RTLDirect: check for terrain collision in every state of RTL beside when landing Signed-off-by: Silvan Fuhrer --- src/modules/navigator/rtl_direct.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index 52e853733eeb..62a940f6c0cf 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -104,8 +104,9 @@ void RtlDirect::on_active() set_rtl_item(); } - if (_rtl_state == RTLState::LOITER_HOLD) { //TODO: rename _rtl_state to _rtl_state_next + if (_rtl_state != RTLState::IDLE) { //TODO: rename _rtl_state to _rtl_state_next (when in IDLE we're actually in LAND) //check for terrain collision and update altitude if needed + // note: it may trigger multiple times during a RTL, as every time the altitude set is reset updateAltToAvoidTerrainCollisionAndRepublishTriplet(_mission_item); } From 0381e148225ab8ef2380090319be9ebd4ca5608a Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 8 Aug 2024 13:51:00 +0200 Subject: [PATCH 589/652] FlightTaskOrbit: Avoid sending NAN altitude in status telemetry while it's changed by stick --- .../flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index 18adf4d3eb80..144c6c7ba158 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -140,9 +140,11 @@ bool FlightTaskOrbit::sendTelemetry() orbit_status.yaw_behaviour = _yaw_behaviour; if (_geo_projection.isInitialized()) { + // While chainging altitude by stick _position_setpoint(2) is not set (NAN) + float local_altitude = PX4_ISFINITE(_position_setpoint(2)) ? _position_setpoint(2) : _position(2); // local -> global _geo_projection.reproject(_center(0), _center(1), orbit_status.x, orbit_status.y); - orbit_status.z = _global_local_alt0 - _position_setpoint(2); + orbit_status.z = _global_local_alt0 - local_altitude; } else { return false; // don't send the message if the transformation failed From a91aa40a3d7d3cc9ba6a5bbe40b35237b69aacb3 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Thu, 8 Aug 2024 17:09:36 +0200 Subject: [PATCH 590/652] battery: only reset soc filter with valid voltage measurement (#23513) --- src/lib/battery/battery.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index 4d4715a0d529..5b41dde3b846 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -108,10 +108,6 @@ void Battery::updateCurrent(const float current_a) void Battery::updateBatteryStatus(const hrt_abstime ×tamp) { - if (!_battery_initialized && _internal_resistance_initialized && _params.n_cells > 0) { - resetInternalResistanceEstimation(_voltage_v, _current_a); - } - // Require minimum voltage otherwise override connected status if (_voltage_v < LITHIUM_BATTERY_RECOGNITION_VOLTAGE) { _connected = false; @@ -121,9 +117,13 @@ void Battery::updateBatteryStatus(const hrt_abstime ×tamp) _last_unconnected_timestamp = timestamp; } - // wait with initializing filters to avoid relying on a voltage sample from the rising edge + // Wait with initializing filters to avoid relying on a voltage sample from the rising edge _battery_initialized = _connected && (timestamp > _last_unconnected_timestamp + 2_s); + if (_connected && !_battery_initialized && _internal_resistance_initialized && _params.n_cells > 0) { + resetInternalResistanceEstimation(_voltage_v, _current_a); + } + sumDischarged(timestamp, _current_a); _state_of_charge_volt_based = calculateStateOfChargeVoltageBased(_voltage_v, _current_a); From cd231d0eed6a58f059dae995c360fbdd78ec1a98 Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Thu, 8 Aug 2024 15:08:33 +0200 Subject: [PATCH 591/652] fmuv6x: Add GPIO expander to check overcurrent pins --- boards/px4/fmu-v6x/default.px4board | 1 + boards/px4/fmu-v6x/init/rc.board_defaults | 11 +++++++++++ boards/px4/fmu-v6x/nuttx-config/nsh/defconfig | 1 + boards/px4/fmu-v6x/src/CMakeLists.txt | 5 +++-- boards/px4/fmu-v6x/src/board_config.h | 5 +++++ boards/px4/fmu-v6x/src/{init.c => init.cpp} | 10 +++++++++- 6 files changed, 30 insertions(+), 3 deletions(-) rename boards/px4/fmu-v6x/src/{init.c => init.cpp} (98%) diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 7b9488933fb4..7c4bf0b6f6cb 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -18,6 +18,7 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPIO_MCP23009=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index cb1eb580a429..bdc99a68e7bd 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -27,3 +27,14 @@ else fi safety_button start + +# GPIO Expander driver on external I2C3 +if ver hwbasecmp 009 +then + # No USB + mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10 +fi +if ver hwbasecmp 00a 008 +then + mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10 +fi diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index ec6b1c7e2b0e..f0a8d6ae8653 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -91,6 +91,7 @@ CONFIG_DEBUG_SYMBOLS=y CONFIG_DEBUG_TCBINFO=y CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_GPIO=y CONFIG_DEV_PIPE_MAXSIZE=1024 CONFIG_DEV_PIPE_SIZE=70 CONFIG_DEV_URANDOM=y diff --git a/boards/px4/fmu-v6x/src/CMakeLists.txt b/boards/px4/fmu-v6x/src/CMakeLists.txt index a120ebe33623..39ec808e1e9a 100644 --- a/boards/px4/fmu-v6x/src/CMakeLists.txt +++ b/boards/px4/fmu-v6x/src/CMakeLists.txt @@ -34,7 +34,7 @@ if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") add_compile_definitions(BOOTLOADER) add_library(drivers_board bootloader_main.c - init.c + init.cpp usb.c timer_config.cpp ) @@ -52,7 +52,7 @@ else() add_library(drivers_board can.c i2c.cpp - init.c + init.cpp led.c mtd.cpp sdio.c @@ -71,5 +71,6 @@ else() nuttx_arch # sdio nuttx_drivers # sdio px4_layer + platform_gpio_mcp23009 ) endif() diff --git a/boards/px4/fmu-v6x/src/board_config.h b/boards/px4/fmu-v6x/src/board_config.h index 7cad5497ed2b..7c98f9490207 100644 --- a/boards/px4/fmu-v6x/src/board_config.h +++ b/boards/px4/fmu-v6x/src/board_config.h @@ -270,6 +270,11 @@ #define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) #define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) +/* MCP23009 GPIO expander */ +#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4" +#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5" + + /* Spare GPIO */ #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) diff --git a/boards/px4/fmu-v6x/src/init.c b/boards/px4/fmu-v6x/src/init.cpp similarity index 98% rename from boards/px4/fmu-v6x/src/init.c rename to boards/px4/fmu-v6x/src/init.cpp index cd6714af1664..8901bd1766f3 100644 --- a/boards/px4/fmu-v6x/src/init.c +++ b/boards/px4/fmu-v6x/src/init.cpp @@ -74,6 +74,7 @@ #include #include #include +#include /**************************************************************************** * Pre-Processor Definitions @@ -159,7 +160,7 @@ __EXPORT void board_on_reset(int status) * ************************************************************************************/ -__EXPORT void +extern "C" __EXPORT void stm32_boardinitialize(void) { board_on_reset(-1); /* Reset PWM first thing */ @@ -280,6 +281,13 @@ __EXPORT int board_app_initialize(uintptr_t arg) # endif /* CONFIG_MMCSD */ + ret = mcp23009_register_gpios(3, 0x25); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + #endif /* !defined(BOOTLOADER) */ return OK; From 1af295f1a91b8e95fd31a3a3915dd8ebd01972ea Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Mon, 5 Aug 2024 15:46:41 +0200 Subject: [PATCH 592/652] ackermann: refactor main files --- .../rover_ackermann/RoverAckermann.cpp | 146 ++++++++++-------- .../rover_ackermann/RoverAckermann.hpp | 25 ++- 2 files changed, 105 insertions(+), 66 deletions(-) diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index b5468880587c..5409e40d841a 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -73,32 +73,15 @@ void RoverAckermann::Run() return; } - // uORB subscriber updates - if (_parameter_update_sub.updated()) { - updateParams(); - } - - if (_vehicle_status_sub.updated()) { - vehicle_status_s vehicle_status; - _vehicle_status_sub.copy(&vehicle_status); - _nav_state = vehicle_status.nav_state; - _armed = vehicle_status.arming_state == 2; - } - - if (_local_position_sub.updated()) { - vehicle_local_position_s local_position{}; - _local_position_sub.copy(&local_position); - const Vector3f rover_velocity = {local_position.vx, local_position.vy, local_position.vz}; - _actual_speed = rover_velocity.norm(); - } + updateSubscriptions(); // Timestamps hrt_abstime timestamp_prev = _timestamp; _timestamp = hrt_absolute_time(); const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + // Generate motor setpoints if (_armed) { - // Navigation modes switch (_nav_state) { case vehicle_status_s::NAVIGATION_STATE_MANUAL: { manual_control_setpoint_s manual_control_setpoint{}; @@ -118,62 +101,97 @@ void RoverAckermann::Run() default: // Unimplemented nav states will stop the rover _motor_setpoint.steering = 0.f; _motor_setpoint.throttle = 0.f; + _throttle_with_accel_limit.setForcedValue(0.f); + _steering_with_rate_limit.setForcedValue(0.f); break; } - // Sanitize actuator commands - if (!PX4_ISFINITE(_motor_setpoint.steering)) { - _motor_setpoint.steering = 0.f; - } + } else { // Reset on disarm + _motor_setpoint.steering = 0.f; + _motor_setpoint.throttle = 0.f; + _throttle_with_accel_limit.setForcedValue(0.f); + _steering_with_rate_limit.setForcedValue(0.f); + } - if (!PX4_ISFINITE(_motor_setpoint.throttle)) { - _motor_setpoint.throttle = 0.f; - } + publishMotorSetpoints(applySlewRates(_motor_setpoint, dt)); +} - // Acceleration slew rate - if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_speed.get() > FLT_EPSILON - && fabsf(_motor_setpoint.throttle) > fabsf(_throttle_with_accel_limit.getState())) { - _throttle_with_accel_limit.update(_motor_setpoint.throttle, dt); +void RoverAckermann::updateSubscriptions() +{ + if (_parameter_update_sub.updated()) { + updateParams(); + } - } else { - _throttle_with_accel_limit.setForcedValue(_motor_setpoint.throttle); - } + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status; + _vehicle_status_sub.copy(&vehicle_status); + _nav_state = vehicle_status.nav_state; + _armed = vehicle_status.arming_state == 2; + } - // Steering slew rate - if (_param_ra_max_steering_rate.get() > FLT_EPSILON && _param_ra_max_steer_angle.get() > FLT_EPSILON) { - _steering_with_rate_limit.update(_motor_setpoint.steering, dt); + if (_local_position_sub.updated()) { + vehicle_local_position_s local_position{}; + _local_position_sub.copy(&local_position); + const Vector3f rover_velocity = {local_position.vx, local_position.vy, local_position.vz}; + _actual_speed = rover_velocity.norm(); + } +} +motor_setpoint_struct RoverAckermann::applySlewRates(motor_setpoint_struct motor_setpoint, const float dt) +{ + // Sanitize actuator commands + if (!PX4_ISFINITE(motor_setpoint.steering)) { + motor_setpoint.steering = 0.f; + } - } else { - _steering_with_rate_limit.setForcedValue(_motor_setpoint.steering); - } + if (!PX4_ISFINITE(motor_setpoint.throttle)) { + motor_setpoint.throttle = 0.f; + } - // Publish rover ackermann status (logging) - rover_ackermann_status_s rover_ackermann_status{}; - rover_ackermann_status.timestamp = _timestamp; - rover_ackermann_status.throttle_setpoint = _motor_setpoint.throttle; - rover_ackermann_status.steering_setpoint = _motor_setpoint.steering; - rover_ackermann_status.actual_speed = _actual_speed; - _rover_ackermann_status_pub.publish(rover_ackermann_status); - - // Publish to motor - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); - actuator_motors.control[0] = math::constrain(_throttle_with_accel_limit.getState(), -1.f, 1.f); - actuator_motors.timestamp = _timestamp; - _actuator_motors_pub.publish(actuator_motors); - - // Publish to servo - actuator_servos_s actuator_servos{}; - actuator_servos.control[0] = math::constrain(_steering_with_rate_limit.getState(), -1.f, 1.f); - actuator_servos.timestamp = _timestamp; - _actuator_servos_pub.publish(actuator_servos); + // Acceleration slew rate + if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_speed.get() > FLT_EPSILON + && fabsf(motor_setpoint.throttle) > fabsf(_throttle_with_accel_limit.getState())) { + _throttle_with_accel_limit.update(motor_setpoint.throttle, dt); - } else { // Reset on disarm - _motor_setpoint.steering = 0.f; - _motor_setpoint.throttle = 0.f; - _throttle_with_accel_limit.setForcedValue(0.f); - _steering_with_rate_limit.setForcedValue(0.f); + } else { + _throttle_with_accel_limit.setForcedValue(motor_setpoint.throttle); + } + + // Steering slew rate + if (_param_ra_max_steering_rate.get() > FLT_EPSILON && _param_ra_max_steer_angle.get() > FLT_EPSILON) { + _steering_with_rate_limit.update(motor_setpoint.steering, dt); + + } else { + _steering_with_rate_limit.setForcedValue(motor_setpoint.steering); } + + motor_setpoint_struct motor_setpoint_temp{}; + motor_setpoint_temp.steering = math::constrain(_steering_with_rate_limit.getState(), -1.f, 1.f); + motor_setpoint_temp.throttle = math::constrain(_throttle_with_accel_limit.getState(), -1.f, 1.f); + return motor_setpoint_temp; +} + +void RoverAckermann::publishMotorSetpoints(motor_setpoint_struct motor_setpoint_with_slew_rates) +{ + // Publish rover Ackermann status (logging) + rover_ackermann_status_s rover_ackermann_status{}; + rover_ackermann_status.timestamp = _timestamp; + rover_ackermann_status.throttle_setpoint = _motor_setpoint.throttle; + rover_ackermann_status.steering_setpoint = _motor_setpoint.steering; + rover_ackermann_status.actual_speed = _actual_speed; + _rover_ackermann_status_pub.publish(rover_ackermann_status); + + // Publish to motor + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + actuator_motors.control[0] = motor_setpoint_with_slew_rates.throttle; + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + + // Publish to servo + actuator_servos_s actuator_servos{}; + actuator_servos.control[0] = motor_setpoint_with_slew_rates.steering; + actuator_servos.timestamp = _timestamp; + _actuator_servos_pub.publish(actuator_servos); } int RoverAckermann::task_spawn(int argc, char *argv[]) diff --git a/src/modules/rover_ackermann/RoverAckermann.hpp b/src/modules/rover_ackermann/RoverAckermann.hpp index cea9300a1b3d..3617b5b80ba6 100644 --- a/src/modules/rover_ackermann/RoverAckermann.hpp +++ b/src/modules/rover_ackermann/RoverAckermann.hpp @@ -59,6 +59,7 @@ // Local includes #include "RoverAckermannGuidance/RoverAckermannGuidance.hpp" +using motor_setpoint_struct = RoverAckermannGuidance::motor_setpoint; using namespace time_literals; @@ -83,12 +84,32 @@ class RoverAckermann : public ModuleBase, public ModuleParams, bool init(); + protected: void updateParams() override; private: void Run() override; + /** + * @brief Update uORB subscriptions. + */ + void updateSubscriptions(); + + /** + * @brief Apply slew rates to motor setpoints. + * @param motor_setpoint Normalized steering and throttle setpoints. + * @param dt Time since last update [s]. + * @return Motor setpoint with applied slew rates. + */ + motor_setpoint_struct applySlewRates(motor_setpoint_struct motor_setpoint, float dt); + + /** + * @brief Publish motor setpoints to ActuatorMotors/ActuatorServos and logging values to RoverAckermannStatus. + * @param motor_setpoint_with_slew_rate Normalized motor_setpoint with applied slew rates. + */ + void publishMotorSetpoints(motor_setpoint_struct motor_setpoint_with_slew_rates); + // uORB subscriptions uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; @@ -100,12 +121,12 @@ class RoverAckermann : public ModuleBase, public ModuleParams, uORB::Publication _actuator_servos_pub{ORB_ID(actuator_servos)}; uORB::Publication _rover_ackermann_status_pub{ORB_ID(rover_ackermann_status)}; - // Instances + // Class instances RoverAckermannGuidance _ackermann_guidance{this}; // Variables int _nav_state{0}; - RoverAckermannGuidance::motor_setpoint _motor_setpoint; + motor_setpoint_struct _motor_setpoint; hrt_abstime _timestamp{0}; float _actual_speed{0.f}; SlewRate _steering_with_rate_limit{0.f}; From 1a7717b5d99d1f32dedd746dcb9bb961b0d8b047 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Mon, 5 Aug 2024 15:46:55 +0200 Subject: [PATCH 593/652] ackermann: refactor guidance files --- .../RoverAckermannGuidance.cpp | 276 +++++++++--------- .../RoverAckermannGuidance.hpp | 120 +++++--- 2 files changed, 230 insertions(+), 166 deletions(-) diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index ade89f6c7e18..1acaebb6386f 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -58,13 +58,54 @@ void RoverAckermannGuidance::updateParams() RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(const int nav_state) { - // Initializations - float desired_speed{0.f}; - float vehicle_yaw{0.f}; - float actual_speed{0.f}; - bool mission_finished{false}; + updateSubscriptions(); - // uORB subscriber updates + // Catch return to launch + if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { + _mission_finished = _distance_to_next_wp < _acceptance_radius; + } + + // Guidance logic + if (_mission_finished) { // Mission is finished + _desired_steering = 0.f; + _desired_speed = 0.f; + + } else if (_distance_to_curr_wp < _acceptance_radius) { // Catch delay command + _desired_speed = 0.f; + + } else { // Regular guidance algorithm + _desired_speed = calcDesiredSpeed(_param_ra_miss_vel_def.get(), _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); + + _desired_steering = calcDesiredSteering(_pure_pursuit, _curr_wp_ned, _prev_wp_ned, _curr_pos_ned, + _param_ra_wheel_base.get(), _desired_speed, _vehicle_yaw, _param_ra_max_steer_angle.get()); + + } + + // Calculate throttle setpoint + hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + const float throttle = calcThrottleSetpoint(_pid_throttle, _desired_speed, _actual_speed, _param_ra_max_speed.get(), + dt); + + // Publish ackermann controller status (logging) + _rover_ackermann_guidance_status.timestamp = _timestamp; + _rover_ackermann_guidance_status.desired_speed = _desired_speed; + _rover_ackermann_guidance_status.pid_throttle_integral = _pid_throttle.integral; + _rover_ackermann_guidance_status_pub.publish(_rover_ackermann_guidance_status); + + // Return motor setpoints + motor_setpoint motor_setpoint_temp; + motor_setpoint_temp.steering = math::interpolate(_desired_steering, -_param_ra_max_steer_angle.get(), + _param_ra_max_steer_angle.get(), -1.f, 1.f); // Normalize steering setpoint + motor_setpoint_temp.throttle = throttle; + return motor_setpoint_temp; +} + +void RoverAckermannGuidance::updateSubscriptions() +{ if (_vehicle_global_position_sub.updated()) { vehicle_global_position_s vehicle_global_position{}; _vehicle_global_position_sub.copy(&vehicle_global_position); @@ -82,7 +123,7 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c _curr_pos_ned = Vector2f(local_position.x, local_position.y); const Vector3f rover_velocity = {local_position.vx, local_position.vy, local_position.vz}; - actual_speed = rover_velocity.norm(); + _actual_speed = rover_velocity.norm(); } if (_home_position_sub.updated()) { @@ -92,158 +133,63 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c } if (_position_setpoint_triplet_sub.updated()) { - updateWaypoints(); + updateWaypointsAndAcceptanceRadius(); } if (_vehicle_attitude_sub.updated()) { vehicle_attitude_s vehicle_attitude{}; _vehicle_attitude_sub.copy(&vehicle_attitude); matrix::Quatf vehicle_attitude_quaternion = Quatf(vehicle_attitude.q); - vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); + _vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); } if (_mission_result_sub.updated()) { mission_result_s mission_result{}; _mission_result_sub.copy(&mission_result); - mission_finished = mission_result.finished; - } - - if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL - && get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), _next_wp(0), - _next_wp(1)) < _acceptance_radius) { // Return to launch - mission_finished = true; - } - - // Guidance logic - if (mission_finished) { - _desired_steering = 0.f; - - } else { - const float distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - _prev_wp(0), - _prev_wp(1)); - const float distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - _curr_wp(0), - _curr_wp(1)); - - if (distance_to_curr_wp < _acceptance_radius) { // Catch delay command - desired_speed = 0.f; - - } else { - // Calculate desired speed - if (_param_ra_miss_vel_min.get() > 0.f && _param_ra_miss_vel_min.get() < _param_ra_miss_vel_def.get() - && _param_ra_miss_vel_gain.get() > FLT_EPSILON) { // Cornering slow down effect - if (distance_to_prev_wp <= _prev_acceptance_radius && _prev_acceptance_radius > FLT_EPSILON) { - const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acceptance_radius; - desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); - - } else if (distance_to_curr_wp <= _acceptance_radius && _acceptance_radius > FLT_EPSILON) { - const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; - desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); - - } else { // Straight line speed - if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_jerk.get() > FLT_EPSILON - && _acceptance_radius > FLT_EPSILON) { - float max_velocity{0.f}; - - if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { - max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), - _param_ra_max_accel.get(), distance_to_curr_wp, 0.f); - - } else { - const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius; - max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(), - _param_ra_max_accel.get(), distance_to_curr_wp - _acceptance_radius, cornering_speed); - } - - desired_speed = math::constrain(max_velocity, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get()); - - } else { - desired_speed = _param_ra_miss_vel_def.get(); - } - } - - } else { - desired_speed = _param_ra_miss_vel_def.get(); - } - - // Calculate desired steering - _desired_steering = calcDesiredSteering(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, _param_ra_wheel_base.get(), - desired_speed, vehicle_yaw); - _desired_steering = math::constrain(_desired_steering, -_param_ra_max_steer_angle.get(), - _param_ra_max_steer_angle.get()); - } - } - - // Throttle PID - hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - float throttle = 0.f; - - if (desired_speed < FLT_EPSILON) { - pid_reset_integral(&_pid_throttle); - - } else { - throttle = pid_calculate(&_pid_throttle, desired_speed, actual_speed, 0, - dt); - } - - if (_param_ra_max_speed.get() > 0.f) { // Feed-forward term - throttle += math::interpolate(desired_speed, - 0.f, _param_ra_max_speed.get(), - 0.f, 1.f); + _mission_finished = mission_result.finished; } - - // Publish ackermann controller status (logging) - _rover_ackermann_guidance_status.timestamp = _timestamp; - _rover_ackermann_guidance_status.desired_speed = desired_speed; - _rover_ackermann_guidance_status.pid_throttle_integral = _pid_throttle.integral; - _rover_ackermann_guidance_status_pub.publish(_rover_ackermann_guidance_status); - - // Return motor setpoints - motor_setpoint motor_setpoint_temp; - motor_setpoint_temp.steering = math::interpolate(_desired_steering, -_param_ra_max_steer_angle.get(), - _param_ra_max_steer_angle.get(), - -1.f, 1.f); - motor_setpoint_temp.throttle = math::constrain(throttle, 0.f, 1.f); - return motor_setpoint_temp; } -void RoverAckermannGuidance::updateWaypoints() +void RoverAckermannGuidance::updateWaypointsAndAcceptanceRadius() { position_setpoint_triplet_s position_setpoint_triplet{}; _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 + 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); - } else { - _curr_wp = Vector2d(0, 0); } 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); - } else { - _prev_wp = _curr_pos; } 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); - } else { - _next_wp = _home_position; // Enables corner slow down with RTL } + // 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; @@ -287,24 +233,90 @@ float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_ned return acceptance_radius; } -float RoverAckermannGuidance::calcDesiredSteering(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, - const Vector2f &curr_pos_ned, const float wheel_base, const float desired_speed, const float vehicle_yaw) +float RoverAckermannGuidance::calcDesiredSpeed(const float miss_vel_def, const float miss_vel_min, + const float miss_vel_gain, const float distance_to_prev_wp, const float distance_to_curr_wp, const float acc_rad, + const float prev_acc_rad, const float max_accel, const float max_jerk, const int nav_state) +{ + // Catch improper values + if (miss_vel_min < 0.f || miss_vel_min > miss_vel_def || miss_vel_gain < FLT_EPSILON) { + return miss_vel_def; + } + + // Cornering slow down effect + if (distance_to_prev_wp <= prev_acc_rad && prev_acc_rad > FLT_EPSILON) { + const float cornering_speed = miss_vel_gain / prev_acc_rad; + return math::constrain(cornering_speed, miss_vel_min, miss_vel_def); + + } else if (distance_to_curr_wp <= acc_rad && acc_rad > FLT_EPSILON) { + const float cornering_speed = miss_vel_gain / acc_rad; + return math::constrain(cornering_speed, miss_vel_min, miss_vel_def); + + } + + // Straight line speed + if (max_accel > FLT_EPSILON && max_jerk > FLT_EPSILON && acc_rad > FLT_EPSILON) { + float max_velocity{0.f}; + + if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { + max_velocity = math::trajectory::computeMaxSpeedFromDistance(max_jerk, + max_accel, distance_to_curr_wp, 0.f); + + } else { + const float cornering_speed = miss_vel_gain / acc_rad; + max_velocity = math::trajectory::computeMaxSpeedFromDistance(max_jerk, + max_accel, distance_to_curr_wp - acc_rad, cornering_speed); + } + + return math::constrain(max_velocity, miss_vel_min, miss_vel_def); + + } else { + return miss_vel_def; + } + +} + +float RoverAckermannGuidance::calcDesiredSteering(PurePursuit &pure_pursuit, const Vector2f &curr_wp_ned, + const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, const float wheel_base, const float desired_speed, + const float vehicle_yaw, const float max_steering) { - // Calculate desired steering to reach lookahead point - const float desired_heading = _pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, + const float desired_heading = pure_pursuit.calcDesiredHeading(curr_wp_ned, prev_wp_ned, curr_pos_ned, desired_speed); - const float lookahead_distance = _pure_pursuit.getLookaheadDistance(); + const float lookahead_distance = pure_pursuit.getLookaheadDistance(); const float heading_error = matrix::wrap_pi(desired_heading - vehicle_yaw); // For logging _rover_ackermann_guidance_status.lookahead_distance = lookahead_distance; _rover_ackermann_guidance_status.heading_error = (heading_error * 180.f) / (M_PI_F); + float desired_steering{0.f}; + if (math::abs_t(heading_error) <= M_PI_2_F) { - return atanf(2 * wheel_base * sinf(heading_error) / lookahead_distance); + desired_steering = atanf(2 * wheel_base * sinf(heading_error) / lookahead_distance); + } else { - return atanf(2 * wheel_base * (sign(heading_error) * 1.0f + sinf(heading_error - sign(heading_error) * M_PI_2_F)) / - lookahead_distance); + desired_steering = atanf(2 * wheel_base * (sign(heading_error) * 1.0f + sinf(heading_error - + sign(heading_error) * M_PI_2_F)) / lookahead_distance); + } + + return math::constrain(desired_steering, -max_steering, max_steering); + +} + +float RoverAckermannGuidance::calcThrottleSetpoint(PID_t &pid_throttle, const float desired_speed, + const float actual_speed, const float max_speed, const float dt) +{ + float throttle = 0.f; + + if (desired_speed < FLT_EPSILON) { + pid_reset_integral(&pid_throttle); + + } else { + throttle = pid_calculate(&pid_throttle, desired_speed, actual_speed, 0, dt); + } + + if (_param_ra_max_speed.get() > 0.f) { // Feed-forward term + throttle += math::interpolate(desired_speed, 0.f, max_speed, 0.f, 1.f); } + return math::constrain(throttle, 0.f, 1.f); } diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index 592083556f13..23f63ed9280e 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -73,58 +73,106 @@ class RoverAckermannGuidance : public ModuleParams RoverAckermannGuidance(ModuleParams *parent); ~RoverAckermannGuidance() = default; + /** + * @brief Struct for steering and throttle setpoints. + * @param steering Steering setpoint. + * @param throttle Throttle setpoint. + */ struct motor_setpoint { float steering{0.f}; float throttle{0.f}; }; /** - * @brief Compute guidance for ackermann rover and return motor_setpoint for throttle and steering. - * @param nav_state Vehicle navigation state + * @brief Calculate motor setpoints based on the mission plan. + * @param nav_state Vehicle navigation state. + * @return Motor setpoints for throttle and steering. */ motor_setpoint computeGuidance(int nav_state); +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + /** + * @brief Update uORB subscriptions + */ + void updateSubscriptions(); + /** - * @brief Update global/NED waypoint coordinates and acceptance radius + * @brief Update global/NED waypoint coordinates and acceptance radius. */ - void updateWaypoints(); + void updateWaypointsAndAcceptanceRadius(); /** - * @brief Returns and publishes the acceptance radius for current waypoint based on the angle between a line segment - * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of - * the vehicle. - * @param curr_wp_ned Current waypoint in NED frame. - * @param prev_wp_ned Previous waypoint in NED frame. - * @param next_wp_ned Next waypoint in NED frame. - * @param default_acceptance_radius Default acceptance radius for waypoints. - * @param acceptance_radius_gain Scaling of the geometric optimal acceptance radius for the rover to cut corners. - * @param acceptance_radius_max Maximum value for the acceptance radius. - * @param wheel_base Rover wheelbase. - * @param max_steer_angle Rover maximum steer angle. + * @brief Publish the acceptance radius for current waypoint based on the angle between a line segment + * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of the vehicle. + * @param curr_wp_ned Current waypoint in NED frame [m]. + * @param prev_wp_ned Previous waypoint in NED frame [m]. + * @param next_wp_ned Next waypoint in NED frame [m]. + * @param default_acceptance_radius Default acceptance radius for waypoints [m]. + * @param acceptance_radius_gain Tuning parameter that scales the geometric optimal acceptance radius for the corner cutting [-]. + * @param acceptance_radius_max Maximum value for the acceptance radius [m]. + * @param wheel_base Rover wheelbase [m]. + * @param max_steer_angle Rover maximum steer angle [rad]. + * @return Updated acceptance radius [m]. */ float updateAcceptanceRadius(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &next_wp_ned, float default_acceptance_radius, float acceptance_radius_gain, float acceptance_radius_max, float wheel_base, float max_steer_angle); + /** - * @brief Calculate and return desired steering input - * @param curr_wp_ned Current waypoint in NED frame. - * @param prev_wp_ned Previous waypoint in NED frame. - * @param curr_pos_ned Current position of the vehicle in NED frame. - * @param wheel_base Rover wheelbase. - * @param desired_speed Desired speed for the rover. - * @param vehicle_yaw Current yaw of the rover. + * @brief Calculate the desired speed setpoint. During cornering the speed is calculated as the inverse + * of the acceptance radius multiplied with a tuning factor. On straight lines it is based on a velocity trajectory + * such that the rover will arrive at the next corner with the desired cornering speed under consideration of the + * maximum acceleration and jerk. + * @param miss_vel_def Default desired velocity for the rover during mission [m/s]. + * @param miss_vel_min Minimum desired velocity for the rover during mission [m/s]. + * @param miss_vel_gain Tuning parameter for the slow down effect during cornering [-]. + * @param distance_to_prev_wp Distance to the previous waypoint [m]. + * @param distance_to_curr_wp Distance to the current waypoint [m]. + * @param acc_rad Acceptance radius of the current waypoint [m]. + * @param prev_acc_rad Acceptance radius of the previous waypoint [m]. + * @param max_accel Maximum allowed acceleration for the rover [m/s^2]. + * @param max_jerk Maximum allowed jerk for the rover [m/s^3]. + * @param nav_state Current nav_state of the rover. + * @return Speed setpoint for the rover [m/s]. */ - float calcDesiredSteering(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, - float wheel_base, float desired_speed, float vehicle_yaw); + float calcDesiredSpeed(float miss_vel_def, float miss_vel_min, float miss_vel_gain, float distance_to_prev_wp, + float distance_to_curr_wp, float acc_rad, float prev_acc_rad, float max_accel, float max_jerk, int nav_state); -protected: /** - * @brief Update the parameters of the module. + * @brief Calculate desired steering angle. The desired steering is calulated as the steering that is required to + * reach the point calculated using the pure pursuit algorithm (see PurePursuit.hpp). + * @param pure_pursuit Pure pursuit class instance. + * @param curr_wp_ned Current waypoint in NED frame [m]. + * @param prev_wp_ned Previous waypoint in NED frame [m]. + * @param curr_pos_ned Current position of the vehicle in NED frame [m]. + * @param wheel_base Rover wheelbase [m]. + * @param desired_speed Desired speed for the rover [m/s]. + * @param vehicle_yaw Current yaw of the rover [rad]. + * @param max_steering Maximum steering angle of the rover [rad]. + * @return Steering setpoint for the rover [rad]. */ - void updateParams() override; + float calcDesiredSteering(PurePursuit &pure_pursuit, const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, + const Vector2f &curr_pos_ned, float wheel_base, float desired_speed, float vehicle_yaw, float max_steering); + + /** + * @brief Calculate the throttle setpoint. Calculated with a PID controller using the difference between + * the desired/actual speed and a feedforward term based on the full throttle speed. + * @param pid_throttle Reference to PID instance. + * @param desired_speed Reference speed for the rover [m/s]. + * @param actual_speed Actual speed of the rover [m/s]. + * @param max_speed Rover speed at full throttle [m/s]. + * @param dt Time interval since last update [s]. + * @return Normalized throttle setpoint [0, 1]. + */ + float calcThrottleSetpoint(PID_t &pid_throttle, float desired_speed, float actual_speed, float max_speed, float dt); -private: // uORB subscriptions uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; @@ -138,27 +186,31 @@ class RoverAckermannGuidance : public ModuleParams uORB::Publication _position_controller_status_pub{ORB_ID(position_controller_status)}; rover_ackermann_guidance_status_s _rover_ackermann_guidance_status{}; - - MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates. + // Class instances + MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates PurePursuit _pure_pursuit{this}; // Pure pursuit library // Rover variables + float _desired_steering{0.f}; + float _vehicle_yaw{0.f}; + float _desired_speed{0.f}; + float _actual_speed{0.f}; Vector2d _curr_pos{}; Vector2f _curr_pos_ned{}; PID_t _pid_throttle; hrt_abstime _timestamp{0}; - float _desired_steering{0.f}; // Waypoint variables - Vector2d _curr_wp{}; - Vector2d _next_wp{}; - Vector2d _prev_wp{}; Vector2d _home_position{}; Vector2f _curr_wp_ned{}; Vector2f _prev_wp_ned{}; Vector2f _next_wp_ned{}; + 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}; + bool _mission_finished{false}; // Parameters DEFINE_PARAMETERS( From a294e011ab1aac3fc3a2239c33eaa1326b914dab Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Mon, 5 Aug 2024 15:47:14 +0200 Subject: [PATCH 594/652] purePursuit: fix commenting error --- src/lib/pure_pursuit/PurePursuit.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/lib/pure_pursuit/PurePursuit.hpp b/src/lib/pure_pursuit/PurePursuit.hpp index 66b9b8ce7cfe..9de498c2e1b1 100644 --- a/src/lib/pure_pursuit/PurePursuit.hpp +++ b/src/lib/pure_pursuit/PurePursuit.hpp @@ -95,9 +95,9 @@ class PurePursuit : public ModuleParams * @param prev_wp_ned North/East coordinates of previous waypoint in NED frame [m]. * @param curr_pos_ned North/East coordinates of current position of the vehicle in NED frame [m]. * @param vehicle_speed Vehicle speed [m/s]. - * @param RA_LOOKAHD_GAIN Tuning parameter [-] - * @param RA_LOOKAHD_MAX Maximum lookahead distance [m] - * @param RA_LOOKAHD_MIN Minimum lookahead distance [m] + * @param PP_LOOKAHD_GAIN Tuning parameter [-] + * @param PP_LOOKAHD_MAX Maximum lookahead distance [m] + * @param PP_LOOKAHD_MIN Minimum lookahead distance [m] */ float calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned, float vehicle_speed); From 718d308d918e8fc99176d8dba86e05ee36757e27 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 8 Aug 2024 12:06:06 +1000 Subject: [PATCH 595/652] parameter markdown - correct reboot in tables --- src/lib/parameters/px4params/markdownout.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/parameters/px4params/markdownout.py b/src/lib/parameters/px4params/markdownout.py index 34e6f9e38666..182324f6711d 100644 --- a/src/lib/parameters/px4params/markdownout.py +++ b/src/lib/parameters/px4params/markdownout.py @@ -81,7 +81,7 @@ def __init__(self, groups): if bitmask_list: result += bitmask_output # Format the ranges as a table. - result += f"Reboot | minValue | maxValue | increment | default | unit\n--- | --- | --- | --- | --- | ---\n{reboot_required} | {min_val} | {max_val} | {increment} | {def_val} | {unit} \n\n" + result += f"Reboot | minValue | maxValue | increment | default | unit\n--- | --- | --- | --- | --- | ---\n{'✓' if reboot_required else ' ' } | {min_val} | {max_val} | {increment} | {def_val} | {unit} \n\n" self.output = result From 82be5cd44fb27df8d14c3eca2a833046509d8f5a Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 8 Aug 2024 12:38:06 +1000 Subject: [PATCH 596/652] Strip short description from long one --- src/lib/parameters/px4params/markdownout.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/lib/parameters/px4params/markdownout.py b/src/lib/parameters/px4params/markdownout.py index 182324f6711d..3666182568c5 100644 --- a/src/lib/parameters/px4params/markdownout.py +++ b/src/lib/parameters/px4params/markdownout.py @@ -26,12 +26,20 @@ def __init__(self, groups): for param in group.GetParams(): name = param.GetName() short_desc = param.GetFieldValue("short_desc") or '' + #short_desc = html.escape(short_desc) + + # Add fullstop to short_desc if not present if short_desc: if not short_desc.strip().endswith('.'): short_desc += "." - #short_desc = html.escape(short_desc) + long_desc = param.GetFieldValue("long_desc") or '' - #long_desc = html.escape(long_desc) + #long_desc = html.escape(long_desc) + + #Strip out short text from start of long text, if it ends in fullstop + if long_desc.startswith(short_desc): + long_desc = long_desc[len(short_desc):].lstrip() + min_val = param.GetFieldValue("min") or '' max_val = param.GetFieldValue("max") or '' increment = param.GetFieldValue("increment") or '' From 58a699e3cbb317ab2252b6cec512dff655e8fe21 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Fri, 9 Aug 2024 06:12:38 +1000 Subject: [PATCH 597/652] Strip out html escape comments --- src/lib/parameters/px4params/markdownout.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/lib/parameters/px4params/markdownout.py b/src/lib/parameters/px4params/markdownout.py index 3666182568c5..4c698fb5115a 100644 --- a/src/lib/parameters/px4params/markdownout.py +++ b/src/lib/parameters/px4params/markdownout.py @@ -26,7 +26,6 @@ def __init__(self, groups): for param in group.GetParams(): name = param.GetName() short_desc = param.GetFieldValue("short_desc") or '' - #short_desc = html.escape(short_desc) # Add fullstop to short_desc if not present if short_desc: @@ -34,7 +33,6 @@ def __init__(self, groups): short_desc += "." long_desc = param.GetFieldValue("long_desc") or '' - #long_desc = html.escape(long_desc) #Strip out short text from start of long text, if it ends in fullstop if long_desc.startswith(short_desc): From 6cf0bf5e19ca006cd434d29fa7e5279396087bc2 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 20 Sep 2023 15:14:36 +0200 Subject: [PATCH 598/652] Support MAVLink extension MANUAL_CONTROL.aux Note that in uORB we don't currently know if the aux fields are specifically valid or not so we can also not set the corresponding bits in the field. --- src/modules/mavlink/mavlink_receiver.cpp | 13 +++++++ .../mavlink/streams/MANUAL_CONTROL.hpp | 38 +++++++++++++++++-- 2 files changed, 47 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 06fb97c8a65f..e7c679295fa2 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2110,6 +2110,19 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) manual_control_setpoint.yaw = mavlink_manual_control.r / 1000.f; // Pass along the button states manual_control_setpoint.buttons = mavlink_manual_control.buttons; + + if (mavlink_manual_control.enabled_extensions & (1u << 2)) { manual_control_setpoint.aux1 = mavlink_manual_control.aux1 / 1000.0f; } + + if (mavlink_manual_control.enabled_extensions & (1u << 3)) { manual_control_setpoint.aux2 = mavlink_manual_control.aux2 / 1000.0f; } + + if (mavlink_manual_control.enabled_extensions & (1u << 4)) { manual_control_setpoint.aux3 = mavlink_manual_control.aux3 / 1000.0f; } + + if (mavlink_manual_control.enabled_extensions & (1u << 5)) { manual_control_setpoint.aux4 = mavlink_manual_control.aux4 / 1000.0f; } + + if (mavlink_manual_control.enabled_extensions & (1u << 6)) { manual_control_setpoint.aux5 = mavlink_manual_control.aux5 / 1000.0f; } + + if (mavlink_manual_control.enabled_extensions & (1u << 7)) { manual_control_setpoint.aux6 = mavlink_manual_control.aux6 / 1000.0f; } + manual_control_setpoint.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink.get_instance_id(); manual_control_setpoint.timestamp = manual_control_setpoint.timestamp_sample = hrt_absolute_time(); manual_control_setpoint.valid = true; diff --git a/src/modules/mavlink/streams/MANUAL_CONTROL.hpp b/src/modules/mavlink/streams/MANUAL_CONTROL.hpp index 8be68fdc3fad..3feabf124d68 100644 --- a/src/modules/mavlink/streams/MANUAL_CONTROL.hpp +++ b/src/modules/mavlink/streams/MANUAL_CONTROL.hpp @@ -68,10 +68,10 @@ class MavlinkStreamManualControl : public MavlinkStream mavlink_manual_control_t msg{}; msg.target = mavlink_system.sysid; - msg.x = manual_control_setpoint.pitch * 1000; - msg.y = manual_control_setpoint.roll * 1000; - msg.z = manual_control_setpoint.throttle * 1000; - msg.r = manual_control_setpoint.yaw * 1000; + msg.x = manual_control_setpoint.pitch * 1000.f; + msg.y = manual_control_setpoint.roll * 1000.f; + msg.z = manual_control_setpoint.throttle * 1000.f; + msg.r = manual_control_setpoint.yaw * 1000.f; manual_control_switches_s manual_control_switches{}; @@ -84,6 +84,36 @@ class MavlinkStreamManualControl : public MavlinkStream msg.buttons |= (manual_control_switches.kill_switch << (shift * 6)); } + if (PX4_ISFINITE(manual_control_setpoint.aux1)) { + msg.enabled_extensions |= (1u << 2); + msg.aux1 = manual_control_setpoint.aux1 * 1000.f; + } + + if (PX4_ISFINITE(manual_control_setpoint.aux2)) { + msg.enabled_extensions |= (1u << 3); + msg.aux2 = manual_control_setpoint.aux2 * 1000.f; + } + + if (PX4_ISFINITE(manual_control_setpoint.aux3)) { + msg.enabled_extensions |= (1u << 4); + msg.aux3 = manual_control_setpoint.aux3 * 1000.f; + } + + if (PX4_ISFINITE(manual_control_setpoint.aux4)) { + msg.enabled_extensions |= (1u << 5); + msg.aux4 = manual_control_setpoint.aux4 * 1000.f; + } + + if (PX4_ISFINITE(manual_control_setpoint.aux5)) { + msg.enabled_extensions |= (1u << 6); + msg.aux5 = manual_control_setpoint.aux5 * 1000.f; + } + + if (PX4_ISFINITE(manual_control_setpoint.aux6)) { + msg.enabled_extensions |= (1u << 7); + msg.aux6 = manual_control_setpoint.aux6 * 1000.f; + } + mavlink_msg_manual_control_send_struct(_mavlink->get_channel(), &msg); return true; From f04aa2494b39f851b883b1f53b132d7f2086c92f Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 31 Jul 2024 15:14:16 +0200 Subject: [PATCH 599/652] FW pos control: do not requre global pos in manual position control --- .../fw_pos_control/FixedwingPositionControl.cpp | 15 ++++++--------- .../fw_pos_control/FixedwingPositionControl.hpp | 2 +- 2 files changed, 7 insertions(+), 10 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 9571c2986591..daef50572dc9 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -2158,28 +2158,25 @@ FixedwingPositionControl::control_manual_position(const float control_interval, if (_yaw_lock_engaged) { - /* just switched back from non heading-hold to heading hold */ + Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; + if (!_hdg_hold_enabled) { + // just switched back from non heading-hold to heading hold _hdg_hold_enabled = true; _hdg_hold_yaw = _yaw; - _hdg_hold_position.lat = _current_latitude; - _hdg_hold_position.lon = _current_longitude; + _hdg_hold_position = curr_pos_local; } // if there's a reset-by-fusion, the ekf needs some time to converge, // therefore we go into track holiding for 2 seconds if (_local_pos.timestamp - _time_last_xy_reset < 2_s) { - _hdg_hold_position.lat = _current_latitude; - _hdg_hold_position.lon = _current_longitude; + _hdg_hold_position = curr_pos_local; } - Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; - Vector2f curr_wp_local = _global_local_proj_ref.project(_hdg_hold_position.lat, _hdg_hold_position.lon); - _npfg.setAirspeedNom(calibrated_airspeed_sp * _eas2tas); _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateLine(curr_wp_local, _hdg_hold_yaw, curr_pos_local, ground_speed, _wind_vel); + navigateLine(_hdg_hold_position, _hdg_hold_yaw, curr_pos_local, ground_speed, _wind_vel); _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); calibrated_airspeed_sp = _npfg.getAirspeedRef() / _eas2tas; diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index 77eb88eb6511..84300ae1b409 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -298,7 +298,7 @@ class FixedwingPositionControl final : public ModuleBase Date: Wed, 31 Jul 2024 15:15:56 +0200 Subject: [PATCH 600/652] commander: extend local position 'relaxed' validity Relaxed position is valid as long as a velocity aiding source is active (e.g.: optical flow or airspeed+sideslip) --- .../checks/estimatorCheck.cpp | 26 +++---------------- .../checks/estimatorCheck.hpp | 2 -- 2 files changed, 4 insertions(+), 24 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 2ede2baf6381..888835ba7ef6 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -533,19 +533,6 @@ void EstimatorChecks::checkEstimatorStatusFlags(const Context &context, Report & estimator_status_flags_s estimator_status_flags; if (_estimator_status_flags_sub.copy(&estimator_status_flags)) { - - bool dead_reckoning = estimator_status_flags.cs_wind_dead_reckoning - || estimator_status_flags.cs_inertial_dead_reckoning; - - if (!dead_reckoning) { - // position requirements (update if not dead reckoning) - bool gps = estimator_status_flags.cs_gps; - bool optical_flow = estimator_status_flags.cs_opt_flow; - bool vision_position = estimator_status_flags.cs_ev_pos; - - _position_reliant_on_optical_flow = !gps && optical_flow && !vision_position; - } - // Check for a magnetometer fault and notify the user if (estimator_status_flags.cs_mag_fault) { /* EVENT @@ -722,15 +709,6 @@ void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_f // Check if quality checking of position accuracy and consistency is to be performed const float lpos_eph_threshold = (_param_com_pos_fs_eph.get() < 0) ? INFINITY : _param_com_pos_fs_eph.get(); - float lpos_eph_threshold_relaxed = lpos_eph_threshold; - - // Set the allowable position uncertainty based on combination of flight and estimator state - // When we are in a operator demanded position control mode and are solely reliant on optical flow, - // do not check position error because it will gradually increase throughout flight and the operator will compensate for the drift - if (_position_reliant_on_optical_flow) { - lpos_eph_threshold_relaxed = INFINITY; - } - bool xy_valid = lpos.xy_valid && !_nav_test_failed; bool v_xy_valid = lpos.v_xy_valid && !_nav_test_failed; @@ -793,6 +771,10 @@ void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_f !checkPosVelValidity(now, xy_valid, lpos.eph, lpos_eph_threshold, lpos.timestamp, _last_lpos_fail_time_us, !failsafe_flags.local_position_invalid); + + // In some modes we assume that the operator will compensate for the drift so we do not need to check the position error + const float lpos_eph_threshold_relaxed = INFINITY; + failsafe_flags.local_position_invalid_relaxed = !checkPosVelValidity(now, xy_valid, lpos.eph, lpos_eph_threshold_relaxed, lpos.timestamp, _last_lpos_relaxed_fail_time_us, !failsafe_flags.local_position_invalid_relaxed); diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp index 6578776ee99d..4f61df88670f 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp @@ -100,8 +100,6 @@ class EstimatorChecks : public HealthAndArmingCheckBase bool _nav_test_passed{false}; ///< true if the post takeoff navigation test has passed bool _nav_test_failed{false}; ///< true if the post takeoff navigation test has failed - bool _position_reliant_on_optical_flow{false}; - bool _gps_was_fused{false}; bool _gnss_spoofed{false}; From 3f17f155058e264d75b9e1184417c4b1d5856a9c Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 31 Jul 2024 15:17:52 +0200 Subject: [PATCH 601/652] commander: allow FW manual pos control without global position --- src/modules/commander/ModeUtil/mode_requirements.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/modules/commander/ModeUtil/mode_requirements.cpp b/src/modules/commander/ModeUtil/mode_requirements.cpp index 0718804df282..32eb5b1e8116 100644 --- a/src/modules/commander/ModeUtil/mode_requirements.cpp +++ b/src/modules/commander/ModeUtil/mode_requirements.cpp @@ -82,11 +82,6 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags) setRequirement(vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW, flags.mode_req_local_position_relaxed); setRequirement(vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW, flags.mode_req_manual_control); - if (vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { - setRequirement(vehicle_status_s::NAVIGATION_STATE_POSCTL, flags.mode_req_global_position); - setRequirement(vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW, flags.mode_req_global_position); - } - // NAVIGATION_STATE_AUTO_MISSION setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_angular_velocity); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_attitude); From fdfe43471e60d2ff220a7e666bf77cc99d2b280c Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 9 Aug 2024 16:13:44 +0200 Subject: [PATCH 602/652] mavlink_receiver: limit access through instances with gimbal mode This adds explicit handling for the few things we want to allow through a MAVLink instance dedicated to a gimbal/(camera) payload as per the MAVLink gimbal mode configuration. --- src/modules/mavlink/mavlink_receiver.cpp | 39 +++++++++++++++++++++++- src/modules/mavlink/mavlink_receiver.h | 1 + 2 files changed, 39 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index e7c679295fa2..8e03e8bd40bc 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -406,6 +406,34 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) _mavlink.handle_message(msg); } +void MavlinkReceiver::handle_messages_in_gimbal_mode(mavlink_message_t &msg) +{ + switch (msg.msgid) { + case MAVLINK_MSG_ID_HEARTBEAT: + handle_message_heartbeat(&msg); + break; + + case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE: + handle_message_gimbal_manager_set_attitude(&msg); + break; + + case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL: + handle_message_gimbal_manager_set_manual_control(&msg); + break; + + case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION: + handle_message_gimbal_device_information(&msg); + break; + + case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS: + handle_message_gimbal_device_attitude_status(&msg); + break; + } + + // Message forwarding + _mavlink.handle_message(&msg); +} + bool MavlinkReceiver::evaluate_target_ok(int command, int target_system, int target_component) { @@ -3176,7 +3204,16 @@ MavlinkReceiver::run() _mavlink.set_proto_version(2); } - handle_message(&msg); + switch (_mavlink.get_mode()) { + case Mavlink::MAVLINK_MODE::MAVLINK_MODE_GIMBAL: + handle_messages_in_gimbal_mode(msg); + break; + + default: + handle_message(&msg); + break; + } + _mavlink.set_has_received_messages(true); // Received first message, unlock wait to transmit '-w' command-line flag update_rx_stats(msg); diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 9f2882e84835..b95bdca59a72 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -155,6 +155,7 @@ class MavlinkReceiver : public ModuleParams float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f); void handle_message(mavlink_message_t *msg); + void handle_messages_in_gimbal_mode(mavlink_message_t &msg); void handle_message_adsb_vehicle(mavlink_message_t *msg); void handle_message_att_pos_mocap(mavlink_message_t *msg); From f4f93118e6ea00fc2a848fc2ce6319eeecf48af8 Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Thu, 8 Aug 2024 02:39:54 +0000 Subject: [PATCH 603/652] mRo boards: Fix for USART clock selection --- boards/mro/ctrl-zero-classic/nuttx-config/include/board.h | 6 ++++++ boards/mro/ctrl-zero-h7-oem/nuttx-config/include/board.h | 6 ++++++ boards/mro/ctrl-zero-h7/nuttx-config/include/board.h | 6 ++++++ boards/mro/pixracerpro/nuttx-config/include/board.h | 6 ++++++ 4 files changed, 24 insertions(+) diff --git a/boards/mro/ctrl-zero-classic/nuttx-config/include/board.h b/boards/mro/ctrl-zero-classic/nuttx-config/include/board.h index 52206cccd00f..ea2147442699 100644 --- a/boards/mro/ctrl-zero-classic/nuttx-config/include/board.h +++ b/boards/mro/ctrl-zero-classic/nuttx-config/include/board.h @@ -197,6 +197,12 @@ #define STM32_FDCANCLK STM32_HSE_FREQUENCY +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* FLASH wait states */ #define BOARD_FLASH_WAITSTATES 2 diff --git a/boards/mro/ctrl-zero-h7-oem/nuttx-config/include/board.h b/boards/mro/ctrl-zero-h7-oem/nuttx-config/include/board.h index d5ffa2c5848e..14a6a28d2b88 100644 --- a/boards/mro/ctrl-zero-h7-oem/nuttx-config/include/board.h +++ b/boards/mro/ctrl-zero-h7-oem/nuttx-config/include/board.h @@ -197,6 +197,12 @@ #define STM32_FDCANCLK STM32_HSE_FREQUENCY +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* FLASH wait states */ #define BOARD_FLASH_WAITSTATES 2 diff --git a/boards/mro/ctrl-zero-h7/nuttx-config/include/board.h b/boards/mro/ctrl-zero-h7/nuttx-config/include/board.h index cdbd3dd3e629..4a20575d70ae 100644 --- a/boards/mro/ctrl-zero-h7/nuttx-config/include/board.h +++ b/boards/mro/ctrl-zero-h7/nuttx-config/include/board.h @@ -196,6 +196,12 @@ #define STM32_FDCANCLK STM32_HSE_FREQUENCY +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* FLASH wait states */ #define BOARD_FLASH_WAITSTATES 2 diff --git a/boards/mro/pixracerpro/nuttx-config/include/board.h b/boards/mro/pixracerpro/nuttx-config/include/board.h index 5edda931dc10..96b2ed2022fb 100644 --- a/boards/mro/pixracerpro/nuttx-config/include/board.h +++ b/boards/mro/pixracerpro/nuttx-config/include/board.h @@ -196,6 +196,12 @@ #define STM32_FDCANCLK STM32_HSE_FREQUENCY +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + /* FLASH wait states */ #define BOARD_FLASH_WAITSTATES 2 From 1211aad9b043bf747ceefc9c6b5e8ad47acf3a08 Mon Sep 17 00:00:00 2001 From: Sergei Date: Fri, 9 Aug 2024 09:37:20 -0500 Subject: [PATCH 604/652] Reasonable defaults for Lawnmower SITL --- .../init.d-posix/airframes/4011_gz_lawnmower | 27 ++++++++++++++----- src/modules/rover_differential/module.yaml | 4 +-- 2 files changed, 23 insertions(+), 8 deletions(-) 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 01fc515c4370..c0d91e222365 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower @@ -15,14 +15,29 @@ param set-default SIM_GZ_EN 1 # Gazebo bridge param set-default SENS_EN_GPSSIM 1 param set-default SENS_EN_BAROSIM 0 param set-default SENS_EN_MAGSIM 1 -param set-default SENS_EN_ARSPDSIM 1 +param set-default SENS_EN_ARSPDSIM 0 # We can arm and drive in manual mode when it slides and GPS check fails: param set-default COM_ARM_WO_GPS 1 -# Set Differential Drive Kinematics Library parameters: -param set RD_WHEEL_BASE 0.9 -param set RD_WHEEL_RADIUS 0.22 -param set RD_WHEEL_SPEED 10.0 # Maximum wheel speed rad/s, approx 8 km/h +# Rover parameters +param set-default RD_WHEEL_TRACK 0.9 +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 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_MAX_YAW_RATE 30 +param set-default RD_MISS_SPD_DEF 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 30 +param set-default PP_LOOKAHD_MIN 2 +param set-default PP_LOOKAHD_GAIN 1 # Actuator mapping - set SITL motors/servos output parameters: @@ -36,7 +51,7 @@ param set-default SIM_GZ_WH_FUNC1 101 # right wheel param set-default SIM_GZ_WH_FUNC2 102 # left wheel #param set-default SIM_GZ_WH_MIN2 0 #param set-default SIM_GZ_WH_MAX2 200 -#aram set-default SIM_GZ_WH_DIS2 100 +#param set-default SIM_GZ_WH_DIS2 100 #param set-default SIM_GZ_WH_FAIL2 100 param set-default SIM_GZ_WH_REV 0 # no need to reverse any wheels diff --git a/src/modules/rover_differential/module.yaml b/src/modules/rover_differential/module.yaml index b6819305bc5f..be0a76c60e9b 100644 --- a/src/modules/rover_differential/module.yaml +++ b/src/modules/rover_differential/module.yaml @@ -155,7 +155,7 @@ parameters: type: float unit: rad min: 0.001 - max: 180 + max: 3.14159 increment: 0.01 decimal: 3 default: 0.0872665 @@ -166,7 +166,7 @@ parameters: type: float unit: rad min: 0.001 - max: 180 + max: 3.14159 increment: 0.01 decimal: 3 default: 0.174533 From 64056fc7bbafc701f6ac3f84c1a63902525ff4f3 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 5 Aug 2024 16:55:36 +0200 Subject: [PATCH 605/652] SYS_STATUS: fill correct attitude, horizontal position flags --- src/modules/mavlink/streams/SYS_STATUS.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/streams/SYS_STATUS.hpp b/src/modules/mavlink/streams/SYS_STATUS.hpp index 272947b1ad77..c875eaceaae9 100644 --- a/src/modules/mavlink/streams/SYS_STATUS.hpp +++ b/src/modules/mavlink/streams/SYS_STATUS.hpp @@ -150,7 +150,11 @@ class MavlinkStreamSysStatus : public MavlinkStream fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_3D_MAG, health_component_t::magnetometer, msg); fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_GPS, health_component_t::gps, msg); fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_RC_RECEIVER, health_component_t::remote_control, msg); - fillOutComponent(health_report, MAV_SYS_STATUS_AHRS, health_component_t::local_position_estimate, msg); + fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, health_component_t::attitude_estimate, + msg); + fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL, health_component_t::local_position_estimate, + msg); + fillOutComponent(health_report, MAV_SYS_STATUS_AHRS, health_component_t::attitude_estimate, msg); fillOutComponent(health_report, MAV_SYS_STATUS_LOGGING, health_component_t::logging, msg); fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, health_component_t::absolute_pressure, msg); fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, health_component_t::differential_pressure, From 478875c00615a2a287dd2ec9f9907597613b3669 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 12 Aug 2024 14:01:52 +0200 Subject: [PATCH 606/652] ekf tools: compare gyro integral with attitude estimate --- .../python/tuning_tools/gyro_integration.py | 158 ++++++++++++++++++ 1 file changed, 158 insertions(+) create mode 100644 src/modules/ekf2/EKF/python/tuning_tools/gyro_integration.py diff --git a/src/modules/ekf2/EKF/python/tuning_tools/gyro_integration.py b/src/modules/ekf2/EKF/python/tuning_tools/gyro_integration.py new file mode 100644 index 000000000000..457c1eb8e9bd --- /dev/null +++ b/src/modules/ekf2/EKF/python/tuning_tools/gyro_integration.py @@ -0,0 +1,158 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +""" + Copyright (c) 2024 PX4 Development Team + 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. +""" + +import matplotlib.pylab as plt +from pyulog import ULog +from pyulog.px4 import PX4ULog +import numpy as np +import sym +import symforce.symbolic as sf + +def getAllData(logfile): + log = ULog(logfile) + + gyro = np.matrix([getData(log, 'sensor_combined', 'gyro_rad[0]'), + getData(log, 'sensor_combined', 'gyro_rad[1]'), + getData(log, 'sensor_combined', 'gyro_rad[2]')]) + t_gyro = getTimestampsSeconds(log, 'sensor_combined') + + t_gyro -= t_gyro[0] + + q = np.matrix([getData(log, 'vehicle_attitude', 'q[0]'), + getData(log, 'vehicle_attitude', 'q[1]'), + getData(log, 'vehicle_attitude', 'q[2]'), + getData(log, 'vehicle_attitude', 'q[3]')]) + t_q = getTimestampsSeconds(log, 'vehicle_attitude') + t_q -= t_q[0] + + return (t_gyro, gyro, t_q, q) + +def getData(log, topic_name, variable_name, instance=0): + variable_data = np.array([]) + for elem in log.data_list: + if elem.name == topic_name: + if instance == elem.multi_id: + variable_data = elem.data[variable_name] + break + + return variable_data + +def us2s(time_us): + return time_us * 1e-6 + +def getTimestampsSeconds(log, topic_name, instance=0): + return us2s(getData(log, topic_name, 'timestamp', instance)) + +def integrateAngularRate(t, angular_rate, rot_init=sym.Rot3()): + R = rot_init + roll = [] + pitch = [] + yaw = [] + t_prev = 0 + + for i in range(len(t)): + dt = t[i] - t_prev + R = R * sym.Rot3.from_tangent(angular_rate[:, i] * dt) + att = R.to_yaw_pitch_roll() + yaw = np.append(yaw, att[0]) + pitch = np.append(pitch, att[1]) + roll = np.append(roll, att[2]) + + t_prev = t[i] + + return (roll, pitch, yaw) + +def quat2RollPitchYaw(t, q): + roll = [] + pitch = [] + yaw = [] + + for i in range(len(t)): + vect = sf.V3(float(q[1, i]), float(q[2, i]), float(q[3, i])) + quat = sf.Quaternion(w=q[0, i], xyz=vect) + R = sf.Rot3(quat) + att = R.to_yaw_pitch_roll() + yaw = np.append(yaw, float(att[0].evalf())) + pitch = np.append(pitch, float(att[1].evalf())) + roll = np.append(roll, float(att[2].evalf())) + + return (roll, pitch, yaw) + + +def run(logfile): + (t, gyro, t_q, q) = getAllData(logfile) + + (roll, pitch, yaw) = quat2RollPitchYaw(t_q, q) + (roll_raw, pitch_raw, yaw_raw) = integrateAngularRate(t, gyro, rot_init=sym.Rot3.from_yaw_pitch_roll(yaw[0], pitch[0], roll[0])) + + # Plot data + plt.figure(1) + plt.suptitle(logfile.split('/')[-1]) + + ax1 = plt.subplot(3, 1, 1) + ax1.plot(t_q, np.rad2deg(roll), '-') + ax1.plot(t, np.rad2deg(roll_raw), '--') + ax1.set_ylabel("roll (deg)") + ax1.legend(["estimated", "integrated"]) + ax1.grid() + + ax2 = plt.subplot(3, 1, 2, sharex=ax1) + ax2.plot(t_q, np.rad2deg(pitch)) + ax2.plot(t, np.rad2deg(pitch_raw), '--') + ax2.set_ylabel("pitch (deg)") + ax2.legend(["estimated", "integrated"]) + ax2.grid() + + ax3 = plt.subplot(3, 1, 3, sharex=ax1) + ax3.plot(t_q, np.rad2deg(yaw)) + ax3.plot(t, np.rad2deg(yaw_raw), '--') + ax3.set_xlabel("time (s)") + ax3.set_ylabel("yaw (deg)") + ax3.legend(["estimated", "integrated"]) + ax3.grid() + plt.show() + +if __name__ == '__main__': + import os + import argparse + + script_path = os.path.split(os.path.realpath(__file__))[0] + + parser = argparse.ArgumentParser( + description='Integrate angular velocity to attitude and compare it with attitude estimate') + + parser.add_argument('logfile', help='Full ulog file path, name and extension', type=str) + args = parser.parse_args() + + logfile = os.path.abspath(args.logfile) + + run(logfile) From af06bee8d0e4665a37787279d8237bad36a5526a Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 5 Aug 2024 09:58:24 +0200 Subject: [PATCH 607/652] update mavlink & adapt to pymavlink generator reporting failures by default --- src/modules/mavlink/CMakeLists.txt | 2 -- src/modules/mavlink/mavlink | 2 +- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index 3038a0f705cc..f42dd6fa9b7b 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -44,7 +44,6 @@ add_custom_command( COMMAND ${PYTHON_EXECUTABLE} ${MAVLINK_GIT_DIR}/pymavlink/tools/mavgen.py --lang C --wire-protocol 2.0 - --exit-code --output ${MAVLINK_LIBRARY_DIR} ${MAVLINK_GIT_DIR}/message_definitions/v1.0/${MAVLINK_DIALECT_UAVIONIX}.xml > ${CMAKE_CURRENT_BINARY_DIR}/mavgen_${MAVLINK_DIALECT_UAVIONIX}.log DEPENDS @@ -63,7 +62,6 @@ add_custom_command( COMMAND ${PYTHON_EXECUTABLE} ${MAVLINK_GIT_DIR}/pymavlink/tools/mavgen.py --lang C --wire-protocol 2.0 - --exit-code --output ${MAVLINK_LIBRARY_DIR} ${MAVLINK_GIT_DIR}/message_definitions/v1.0/${CONFIG_MAVLINK_DIALECT}.xml > ${CMAKE_CURRENT_BINARY_DIR}/mavgen_${CONFIG_MAVLINK_DIALECT}.log DEPENDS diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index d65952bacc02..bb52e30d2b92 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit d65952bacc02c4a5a1ed8249be73e6a66fa800ab +Subproject commit bb52e30d2b924d5a250f2400144d33012271a19d From c9343ca11d1dd8670cb15b04b7775254bb107913 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 9 Aug 2024 12:04:07 -0400 Subject: [PATCH 608/652] sitl_gazebo-classic update submodule to latest --- Tools/simulation/gazebo-classic/sitl_gazebo-classic | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/simulation/gazebo-classic/sitl_gazebo-classic b/Tools/simulation/gazebo-classic/sitl_gazebo-classic index 67af3c3a6da4..f1d11a612699 160000 --- a/Tools/simulation/gazebo-classic/sitl_gazebo-classic +++ b/Tools/simulation/gazebo-classic/sitl_gazebo-classic @@ -1 +1 @@ -Subproject commit 67af3c3a6da493bdc0a0b9de28b01a2a98d38659 +Subproject commit f1d11a6126990d487d4aa8ff68c23ff370516510 From e008ca24f1ecc1c7e41e2da555c366291145695e Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Mon, 12 Aug 2024 16:42:51 +0200 Subject: [PATCH 609/652] Remove euler angles from attitude setpoint (#23482) * Remove euler angles from attitude setpoint message * Remove usage of euler angles in attitude setpoint messages This commit removes the usage of euler angles in the vehicle_attitude_setpoint messages * Fix standard vtol --- msg/VehicleAttitudeSetpoint.msg | 4 - .../FixedwingAttitudeControl.cpp | 29 ++- .../FixedwingPositionControl.cpp | 227 ++++++++++++------ src/modules/mavlink/mavlink_receiver.cpp | 5 - src/modules/mavlink/streams/HIGH_LATENCY2.hpp | 4 +- .../mc_att_control/mc_att_control_main.cpp | 6 - .../PositionControl/ControlMath.cpp | 6 - .../PositionControl/ControlMathTest.cpp | 21 +- .../PositionControl/PositionControlTest.cpp | 20 +- .../RoverPositionControl.cpp | 8 +- .../uuv_att_control/uuv_att_control.cpp | 12 +- .../uuv_pos_control/uuv_pos_control.cpp | 5 +- src/modules/vtol_att_control/standard.cpp | 17 +- src/modules/vtol_att_control/tailsitter.cpp | 10 +- src/modules/vtol_att_control/tiltrotor.cpp | 11 +- src/modules/vtol_att_control/vtol_type.cpp | 6 +- 16 files changed, 234 insertions(+), 157 deletions(-) diff --git a/msg/VehicleAttitudeSetpoint.msg b/msg/VehicleAttitudeSetpoint.msg index f52025d2bb51..74a753023df5 100644 --- a/msg/VehicleAttitudeSetpoint.msg +++ b/msg/VehicleAttitudeSetpoint.msg @@ -1,9 +1,5 @@ uint64 timestamp # time since system start (microseconds) -float32 roll_body # body angle in NED frame (can be NaN for FW) -float32 pitch_body # body angle in NED frame (can be NaN for FW) -float32 yaw_body # body angle in NED frame (can be NaN for FW) - float32 yaw_sp_move_rate # rad/s (commanded by user) # For quaternion-based attitude control diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp index b08fc895ab9c..988853fdeaaf 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp @@ -96,17 +96,16 @@ FixedwingAttitudeControl::vehicle_manual_poll(const float yaw_body) // STABILIZED mode generate the attitude setpoint from manual user inputs - _att_sp.roll_body = _manual_control_setpoint.roll * radians(_param_fw_man_r_max.get()); + const float roll_body = _manual_control_setpoint.roll * radians(_param_fw_man_r_max.get()); - _att_sp.pitch_body = -_manual_control_setpoint.pitch * radians(_param_fw_man_p_max.get()) - + radians(_param_fw_psp_off.get()); - _att_sp.pitch_body = constrain(_att_sp.pitch_body, - -radians(_param_fw_man_p_max.get()), radians(_param_fw_man_p_max.get())); + float pitch_body = -_manual_control_setpoint.pitch * radians(_param_fw_man_p_max.get()) + + radians(_param_fw_psp_off.get()); + pitch_body = constrain(pitch_body, + -radians(_param_fw_man_p_max.get()), radians(_param_fw_man_p_max.get())); - _att_sp.yaw_body = yaw_body; // yaw is not controlled, so set setpoint to current yaw _att_sp.thrust_body[0] = (_manual_control_setpoint.throttle + 1.f) * .5f; - Quatf q(Eulerf(_att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body)); + const Quatf q(Eulerf(roll_body, pitch_body, yaw_body)); q.copyTo(_att_sp.q_d); _att_sp.reset_integral = false; @@ -325,16 +324,22 @@ void FixedwingAttitudeControl::Run() /* Run attitude controllers */ if (_vcontrol_mode.flag_control_attitude_enabled && _in_fw_or_transition_wo_tailsitter_transition) { - if (PX4_ISFINITE(_att_sp.roll_body) && PX4_ISFINITE(_att_sp.pitch_body)) { - _roll_ctrl.control_roll(_att_sp.roll_body, _yaw_ctrl.get_euler_rate_setpoint(), euler_angles.phi(), + const Eulerf setpoint(Quatf(_att_sp.q_d)); + const float roll_body = setpoint.phi(); + const float pitch_body = setpoint.theta(); + + if (PX4_ISFINITE(roll_body) && PX4_ISFINITE(pitch_body)) { + + _roll_ctrl.control_roll(roll_body, _yaw_ctrl.get_euler_rate_setpoint(), euler_angles.phi(), euler_angles.theta()); - _pitch_ctrl.control_pitch(_att_sp.pitch_body, _yaw_ctrl.get_euler_rate_setpoint(), euler_angles.phi(), + _pitch_ctrl.control_pitch(pitch_body, _yaw_ctrl.get_euler_rate_setpoint(), euler_angles.phi(), euler_angles.theta()); - _yaw_ctrl.control_yaw(_att_sp.roll_body, _pitch_ctrl.get_euler_rate_setpoint(), euler_angles.phi(), + _yaw_ctrl.control_yaw(roll_body, _pitch_ctrl.get_euler_rate_setpoint(), euler_angles.phi(), euler_angles.theta(), get_airspeed_constrained()); if (wheel_control) { - _wheel_ctrl.control_attitude(_att_sp.yaw_body, euler_angles.psi()); + Eulerf attitude_setpoint(Quatf(_att_sp.q_d)); + _wheel_ctrl.control_attitude(attitude_setpoint.psi(), euler_angles.psi()); } else { _wheel_ctrl.reset_integrator(); diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index daef50572dc9..4da7168255f9 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -451,9 +451,6 @@ FixedwingPositionControl::status_publish() { position_controller_status_s pos_ctrl_status = {}; - pos_ctrl_status.nav_roll = _att_sp.roll_body; - pos_ctrl_status.nav_pitch = _att_sp.pitch_body; - npfg_status_s npfg_status = {}; npfg_status.wind_est_valid = _wind_valid; @@ -791,8 +788,11 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) /* reset setpoints from other modes (auto) otherwise we won't * level out without new manual input */ - _att_sp.roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + const Eulerf current_setpoint(Quatf(_att_sp.q_d)); + const Quatf setpoint(Eulerf(roll_body, current_setpoint.theta(), yaw_body)); + setpoint.copyTo(_att_sp.q_d); } _control_mode_current = FW_POSCTRL_MODE_MANUAL_POSITION; @@ -877,11 +877,16 @@ FixedwingPositionControl::control_auto(const float control_interval, const Vecto } switch (position_sp_type) { - case position_setpoint_s::SETPOINT_TYPE_IDLE: - _att_sp.thrust_body[0] = 0.0f; - _att_sp.roll_body = 0.0f; - _att_sp.pitch_body = radians(_param_fw_psp_off.get()); - break; + case position_setpoint_s::SETPOINT_TYPE_IDLE: { + _att_sp.thrust_body[0] = 0.0f; + const float roll_body = 0.0f; + const float pitch_body = radians(_param_fw_psp_off.get()); + const float yaw_body = 0.0f; + + const Quatf setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + setpoint.copyTo(_att_sp.q_d); + break; + } case position_setpoint_s::SETPOINT_TYPE_POSITION: control_auto_position(control_interval, curr_pos, ground_speed, pos_sp_prev, current_sp); @@ -927,9 +932,6 @@ FixedwingPositionControl::control_auto(const float control_interval, const Vecto _att_sp.thrust_body[0] = (_landed) ? min(_param_fw_thr_idle.get(), 1.f) : get_tecs_thrust(); } - /* Copy thrust and pitch values from tecs */ - _att_sp.pitch_body = get_tecs_pitch(); - if (!_vehicle_status.in_transition_to_fw) { publishLocalPositionSetpoint(current_sp); } @@ -950,8 +952,8 @@ FixedwingPositionControl::control_auto_fixed_bank_alt_hold(const float control_i _param_sinkrate_target.get(), _param_climbrate_target.get()); - _att_sp.roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle - _att_sp.yaw_body = 0.f; + const float roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle + const float yaw_body = 0.f; if (_landed) { _att_sp.thrust_body[0] = _param_fw_thr_min.get(); @@ -960,7 +962,9 @@ FixedwingPositionControl::control_auto_fixed_bank_alt_hold(const float control_i _att_sp.thrust_body[0] = min(get_tecs_thrust(), _param_fw_thr_max.get()); } - _att_sp.pitch_body = get_tecs_pitch(); + const float pitch_body = get_tecs_pitch(); + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } @@ -983,11 +987,13 @@ FixedwingPositionControl::control_auto_descend(const float control_interval) false, descend_rate); - _att_sp.roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle - _att_sp.yaw_body = 0.f; + const float roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle + const float yaw_body = 0.f; _att_sp.thrust_body[0] = (_landed) ? _param_fw_thr_min.get() : min(get_tecs_thrust(), _param_fw_thr_max.get()); - _att_sp.pitch_body = get_tecs_pitch(); + const float pitch_body = get_tecs_pitch(); + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } uint8_t @@ -1109,10 +1115,10 @@ FixedwingPositionControl::control_auto_position(const float control_interval, co navigateWaypoint(curr_wp_local, curr_pos_local, ground_speed, _wind_vel); } - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw tecs_update_pitch_throttle(control_interval, position_sp_alt, @@ -1123,6 +1129,9 @@ FixedwingPositionControl::control_auto_position(const float control_interval, co tecs_fw_thr_max, _param_sinkrate_target.get(), _param_climbrate_target.get()); + const float pitch_body = get_tecs_pitch(); + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } void @@ -1158,10 +1167,10 @@ FixedwingPositionControl::control_auto_velocity(const float control_interval, co _npfg.setAirspeedNom(target_airspeed * _eas2tas); _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); navigateBearing(curr_pos_local, _target_bearing, ground_speed, _wind_vel); - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.yaw_body = _yaw; + float yaw_body = _yaw; tecs_update_pitch_throttle(control_interval, position_sp_alt, @@ -1174,6 +1183,10 @@ FixedwingPositionControl::control_auto_velocity(const float control_interval, co _param_climbrate_target.get(), false, pos_sp_curr.vz); + const float pitch_body = get_tecs_pitch(); + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } void @@ -1253,10 +1266,10 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons navigateLoiter(curr_wp_local, curr_pos_local, loiter_radius, pos_sp_curr.loiter_direction_counter_clockwise, ground_speed, _wind_vel); - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw float alt_sp = pos_sp_curr.alt; @@ -1267,7 +1280,7 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons } else { // continue straight until vehicle has sufficient altitude - _att_sp.roll_body = 0.0f; + roll_body = 0.0f; } _tecs.set_altitude_error_time_constant(_param_fw_thrtc_sc.get() * _param_fw_t_h_error_tc.get()); @@ -1282,6 +1295,11 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons tecs_fw_thr_max, _param_sinkrate_target.get(), _param_climbrate_target.get()); + + const float pitch_body = get_tecs_pitch(); + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } #ifdef CONFIG_FIGURE_OF_EIGHT @@ -1306,7 +1324,7 @@ FixedwingPositionControl::controlAutoFigureEight(const float control_interval, c // Apply control _figure_eight.updateSetpoint(curr_pos_local, ground_speed, params, target_airspeed); - _att_sp.roll_body = _figure_eight.getRollSetpoint(); + float roll_body = _figure_eight.getRollSetpoint(); target_airspeed = _figure_eight.getAirspeedSetpoint(); _target_bearing = _figure_eight.getTargetBearing(); _closest_point_on_path = _figure_eight.getClosestPoint(); @@ -1337,7 +1355,11 @@ FixedwingPositionControl::controlAutoFigureEight(const float control_interval, c _param_climbrate_target.get()); // Yaw - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + const float pitch_body = get_tecs_pitch(); + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } void FixedwingPositionControl::publishFigureEightStatus(const position_setpoint_s pos_sp) @@ -1392,10 +1414,10 @@ FixedwingPositionControl::control_auto_path(const float control_interval, const 0.0f; navigatePathTangent(curr_pos_local, curr_wp_local, velocity_2d.normalized(), ground_speed, _wind_vel, curvature); - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw tecs_update_pitch_throttle(control_interval, pos_sp_curr.alt, @@ -1408,7 +1430,10 @@ FixedwingPositionControl::control_auto_path(const float control_interval, const _param_climbrate_target.get()); _att_sp.thrust_body[0] = min(get_tecs_thrust(), tecs_fw_thr_max); - _att_sp.pitch_body = get_tecs_pitch(); + const float pitch_body = get_tecs_pitch(); + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } void @@ -1494,7 +1519,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); navigateLine(start_pos_local, takeoff_bearing, local_2D_position, ground_speed, _wind_vel); - _att_sp.roll_body = _runway_takeoff.getRoll(getCorrectedNpfgRollSetpoint()); + float roll_body = _runway_takeoff.getRoll(getCorrectedNpfgRollSetpoint()); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; @@ -1502,7 +1527,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo const float bearing = _npfg.getBearing(); // heading hold mode will override this bearing setpoint - _att_sp.yaw_body = _runway_takeoff.getYaw(bearing); + float yaw_body = _runway_takeoff.getYaw(bearing); // update tecs const float pitch_max = _runway_takeoff.getMaxPitch(math::radians(_param_fw_p_lim_max.get())); @@ -1529,9 +1554,16 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation - _att_sp.pitch_body = _runway_takeoff.getPitch(get_tecs_pitch()); + const float pitch_body = _runway_takeoff.getPitch(get_tecs_pitch()); _att_sp.thrust_body[0] = _runway_takeoff.getThrottle(_param_fw_thr_idle.get(), get_tecs_thrust()); + roll_body = constrainRollNearGround(roll_body, _current_altitude, _takeoff_ground_alt); + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); + + _flaps_setpoint = _param_fw_flaps_to_scl.get(); + // retract ladning gear once passed the climbout state if (_runway_takeoff.getState() > RunwayTakeoffState::CLIMBOUT) { _new_landing_gear_position = landing_gear_s::GEAR_UP; @@ -1588,7 +1620,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _npfg.setAirspeedNom(target_airspeed * _eas2tas); _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); navigateLine(launch_local_position, takeoff_bearing, local_2D_position, ground_speed, _wind_vel); - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; @@ -1613,17 +1645,27 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _att_sp.thrust_body[0] = get_tecs_thrust(); } - _att_sp.pitch_body = get_tecs_pitch(); - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float pitch_body = get_tecs_pitch(); + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + + roll_body = constrainRollNearGround(roll_body, _current_altitude, _takeoff_ground_alt); + + Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } else { /* Tell the attitude controller to stop integrating while we are waiting for the launch */ _att_sp.reset_integral = true; /* Set default roll and pitch setpoints during detection phase */ - _att_sp.roll_body = 0.0f; + float roll_body = 0.0f; + float yaw_body = _yaw; _att_sp.thrust_body[0] = _param_fw_thr_idle.get(); - _att_sp.pitch_body = radians(_takeoff_pitch_min.get()); + float pitch_body = radians(_takeoff_pitch_min.get()); + roll_body = constrainRollNearGround(roll_body, _current_altitude, _takeoff_ground_alt); + Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); + } launch_detection_status_s launch_detection_status; @@ -1633,7 +1675,6 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo } _flaps_setpoint = _param_fw_flaps_to_scl.get(); - _att_sp.roll_body = constrainRollNearGround(_att_sp.roll_body, _current_altitude, _takeoff_ground_alt); if (!_vehicle_status.in_transition_to_fw) { publishLocalPositionSetpoint(pos_sp_curr); @@ -1738,10 +1779,10 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); navigateLine(local_approach_entrance, local_land_point, local_position, ground_speed, _wind_vel); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); // use npfg's bearing to commanded course, controlled via yaw angle while on runway - _att_sp.yaw_body = _npfg.getBearing(); + float yaw_body = _npfg.getBearing(); /* longitudinal guidance */ @@ -1787,7 +1828,13 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, /* set the attitude and throttle commands */ // TECS has authority (though constrained) over pitch during flare, throttle is hard set to idle - _att_sp.pitch_body = get_tecs_pitch(); + float pitch_body = get_tecs_pitch(); + + roll_body = constrainRollNearGround(roll_body, _current_altitude, terrain_alt); + + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); // enable direct yaw control using rudder/wheel _att_sp.fw_control_yaw_wheel = true; @@ -1817,7 +1864,7 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); navigateLine(local_approach_entrance, local_land_point, local_position, ground_speed, _wind_vel); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); /* longitudinal guidance */ @@ -1839,10 +1886,15 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, /* set the attitude and throttle commands */ - _att_sp.pitch_body = get_tecs_pitch(); + float pitch_body = get_tecs_pitch(); + + roll_body = constrainRollNearGround(roll_body, _current_altitude, terrain_alt); // yaw is not controlled in nominal flight - _att_sp.yaw_body = _yaw; + float yaw_body = _yaw; + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); // enable direct yaw control using rudder/wheel _att_sp.fw_control_yaw_wheel = false; @@ -1852,8 +1904,6 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation - _att_sp.roll_body = constrainRollNearGround(_att_sp.roll_body, _current_altitude, terrain_alt); - _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); _spoilers_setpoint = _param_fw_spoilers_lnd.get(); @@ -1911,6 +1961,10 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, } // the terrain estimate (if enabled) is always used to determine the flaring altitude + float roll_body; + float yaw_body; + float pitch_body; + if ((_current_altitude < terrain_alt + flare_rel_alt) || _flare_states.flaring) { // flare and land with minimal speed @@ -1943,9 +1997,9 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, pos_sp_curr.loiter_direction_counter_clockwise, ground_speed, _wind_vel); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + roll_body = getCorrectedNpfgRollSetpoint(); - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw /* longitudinal guidance */ @@ -1990,7 +2044,7 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, /* set the attitude and throttle commands */ // TECS has authority (though constrained) over pitch during flare, throttle is hard set to idle - _att_sp.pitch_body = get_tecs_pitch(); + pitch_body = get_tecs_pitch(); // enable direct yaw control using rudder/wheel _att_sp.fw_control_yaw_wheel = true; @@ -2020,7 +2074,7 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, pos_sp_curr.loiter_direction_counter_clockwise, ground_speed, _wind_vel); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + roll_body = getCorrectedNpfgRollSetpoint(); /* longitudinal guidance */ @@ -2044,10 +2098,10 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, /* set the attitude and throttle commands */ - _att_sp.pitch_body = get_tecs_pitch(); + pitch_body = get_tecs_pitch(); // yaw is not controlled in nominal flight - _att_sp.yaw_body = _yaw; + yaw_body = _yaw; // enable direct yaw control using rudder/wheel _att_sp.fw_control_yaw_wheel = false; @@ -2057,7 +2111,11 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation - _att_sp.roll_body = constrainRollNearGround(_att_sp.roll_body, _current_altitude, terrain_alt); + roll_body = constrainRollNearGround(roll_body, _current_altitude, terrain_alt); + + Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); + _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); _spoilers_setpoint = _param_fw_spoilers_lnd.get(); @@ -2104,11 +2162,14 @@ FixedwingPositionControl::control_manual_altitude(const float control_interval, false, height_rate_sp); - _att_sp.roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw _att_sp.thrust_body[0] = min(get_tecs_thrust(), throttle_max); - _att_sp.pitch_body = get_tecs_pitch(); + const float pitch_body = get_tecs_pitch(); + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } void @@ -2137,6 +2198,11 @@ FixedwingPositionControl::control_manual_position(const float control_interval, _time_last_xy_reset = _local_pos.timestamp; } + Eulerf current_setpoint(Quatf(_att_sp.q_d)); + float yaw_body = current_setpoint.psi(); + float roll_body = current_setpoint.phi(); + float pitch_body = current_setpoint.theta(); + /* heading control */ // TODO: either make it course hold (easier) or a real heading hold (minus all the complexity here) if (fabsf(_manual_control_setpoint.roll) < HDG_HOLD_MAN_INPUT_THRESH && @@ -2177,10 +2243,10 @@ FixedwingPositionControl::control_manual_position(const float control_interval, _npfg.setAirspeedNom(calibrated_airspeed_sp * _eas2tas); _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); navigateLine(_hdg_hold_position, _hdg_hold_yaw, curr_pos_local, ground_speed, _wind_vel); - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + roll_body = getCorrectedNpfgRollSetpoint(); calibrated_airspeed_sp = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw } } @@ -2202,12 +2268,16 @@ FixedwingPositionControl::control_manual_position(const float control_interval, _hdg_hold_enabled = false; _yaw_lock_engaged = false; - _att_sp.roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); + yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw } _att_sp.thrust_body[0] = min(get_tecs_thrust(), throttle_max); - _att_sp.pitch_body = get_tecs_pitch(); + + pitch_body = get_tecs_pitch(); + + Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } void FixedwingPositionControl::control_backtransition(const float control_interval, const Vector2f &ground_speed, @@ -2230,10 +2300,10 @@ void FixedwingPositionControl::control_backtransition(const float control_interv navigateLine(_lpos_where_backtrans_started, curr_wp_local, curr_pos_local, ground_speed, _wind_vel); - _att_sp.roll_body = getCorrectedNpfgRollSetpoint(); + float roll_body = getCorrectedNpfgRollSetpoint(); target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - _att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw tecs_update_pitch_throttle(control_interval, pos_sp_curr.alt, @@ -2246,7 +2316,10 @@ void FixedwingPositionControl::control_backtransition(const float control_interv _param_climbrate_target.get()); _att_sp.thrust_body[0] = (_landed) ? _param_fw_thr_min.get() : min(get_tecs_thrust(), _param_fw_thr_max.get()); - _att_sp.pitch_body = get_tecs_pitch(); + const float pitch_body = get_tecs_pitch(); + + const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); + attitude_setpoint.copyTo(_att_sp.q_d); } float FixedwingPositionControl::get_tecs_pitch() @@ -2556,12 +2629,16 @@ FixedwingPositionControl::Run() if (_control_mode_current != FW_POSCTRL_MODE_OTHER) { + Eulerf attitude_setpoint(Quatf(_att_sp.q_d)); + float roll_body = attitude_setpoint.phi(); + float pitch_body = attitude_setpoint.theta(); + float yaw_body = attitude_setpoint.psi(); if (_control_mode.flag_control_manual_enabled) { - _att_sp.roll_body = constrain(_att_sp.roll_body, -radians(_param_fw_r_lim.get()), - radians(_param_fw_r_lim.get())); - _att_sp.pitch_body = constrain(_att_sp.pitch_body, radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get())); + roll_body = constrain(roll_body, -radians(_param_fw_r_lim.get()), + radians(_param_fw_r_lim.get())); + pitch_body = constrain(pitch_body, radians(_param_fw_p_lim_min.get()), + radians(_param_fw_p_lim_max.get())); } if (_control_mode.flag_control_position_enabled || @@ -2571,9 +2648,9 @@ FixedwingPositionControl::Run() _control_mode.flag_control_climb_rate_enabled) { // roll slew rate - _att_sp.roll_body = _roll_slew_rate.update(_att_sp.roll_body, control_interval); + roll_body = _roll_slew_rate.update(roll_body, control_interval); - const Quatf q(Eulerf(_att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body)); + const Quatf q(Eulerf(roll_body, pitch_body, yaw_body)); q.copyTo(_att_sp.q_d); _att_sp.timestamp = hrt_absolute_time(); @@ -3162,8 +3239,10 @@ float FixedwingPositionControl::getLoadFactor() { float load_factor_from_bank_angle = 1.0f; - if (PX4_ISFINITE(_att_sp.roll_body)) { - load_factor_from_bank_angle = 1.0f / math::max(cosf(_att_sp.roll_body), FLT_EPSILON); + float roll_body = Eulerf(Quatf(_att_sp.q_d)).phi(); + + if (PX4_ISFINITE(roll_body)) { + load_factor_from_bank_angle = 1.0f / math::max(cosf(roll_body), FLT_EPSILON); } return load_factor_from_bank_angle; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 8e03e8bd40bc..58d2c044ccd0 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1626,11 +1626,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) const matrix::Quatf q{attitude_target.q}; q.copyTo(attitude_setpoint.q_d); - matrix::Eulerf euler{q}; - attitude_setpoint.roll_body = euler.phi(); - attitude_setpoint.pitch_body = euler.theta(); - attitude_setpoint.yaw_body = euler.psi(); - // TODO: review use case attitude_setpoint.yaw_sp_move_rate = (type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE) ? (float)NAN : attitude_target.body_yaw_rate; diff --git a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp index 32d244b138da..6aca9f7d9837 100644 --- a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp +++ b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp @@ -264,7 +264,9 @@ class MavlinkStreamHighLatency2 : public MavlinkStream vehicle_attitude_setpoint_s attitude_sp; if (_attitude_sp_sub.update(&attitude_sp)) { - msg->target_heading = static_cast(math::degrees(matrix::wrap_2pi(attitude_sp.yaw_body)) * 0.5f); + + msg->target_heading = static_cast(math::degrees(matrix::wrap_2pi(matrix::Eulerf(matrix::Quatf( + attitude_sp.q_d)).psi())) * 0.5f); return true; } diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 39cb033e74dc..f6cc5db43d88 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -182,12 +182,6 @@ MulticopterAttitudeControl::generate_attitude_setpoint(const Quatf &q, float dt, q_sp.copyTo(attitude_setpoint.q_d); - // Transform to euler angles for logging only - const Eulerf euler_sp(q_sp); - attitude_setpoint.roll_body = euler_sp(0); - attitude_setpoint.pitch_body = euler_sp(1); - attitude_setpoint.yaw_body = euler_sp(2); - attitude_setpoint.thrust_body[2] = -throttle_curve(_manual_control_setpoint.throttle); attitude_setpoint.timestamp = hrt_absolute_time(); diff --git a/src/modules/mc_pos_control/PositionControl/ControlMath.cpp b/src/modules/mc_pos_control/PositionControl/ControlMath.cpp index b4eba96115cd..3d1b1268c2cc 100644 --- a/src/modules/mc_pos_control/PositionControl/ControlMath.cpp +++ b/src/modules/mc_pos_control/PositionControl/ControlMath.cpp @@ -111,12 +111,6 @@ void bodyzToAttitude(Vector3f body_z, const float yaw_sp, vehicle_attitude_setpo // copy quaternion setpoint to attitude setpoint topic const Quatf q_sp{R_sp}; q_sp.copyTo(att_sp.q_d); - - // calculate euler angles, for logging only, must not be used for control - const Eulerf euler{R_sp}; - att_sp.roll_body = euler.phi(); - att_sp.pitch_body = euler.theta(); - att_sp.yaw_body = euler.psi(); } Vector2f constrainXY(const Vector2f &v0, const Vector2f &v1, const float &max) diff --git a/src/modules/mc_pos_control/PositionControl/ControlMathTest.cpp b/src/modules/mc_pos_control/PositionControl/ControlMathTest.cpp index e9b6fba12fb4..ebb23d7ed14e 100644 --- a/src/modules/mc_pos_control/PositionControl/ControlMathTest.cpp +++ b/src/modules/mc_pos_control/PositionControl/ControlMathTest.cpp @@ -108,18 +108,20 @@ TEST(ControlMathTest, ThrottleAttitudeMapping) float yaw = 0.f; vehicle_attitude_setpoint_s att{}; thrustToAttitude(thr, yaw, att); - EXPECT_FLOAT_EQ(att.roll_body, 0.f); - EXPECT_FLOAT_EQ(att.pitch_body, 0.f); - EXPECT_FLOAT_EQ(att.yaw_body, 0.f); + EXPECT_FLOAT_EQ(att.q_d[0], 1.f); + EXPECT_FLOAT_EQ(att.q_d[1], 0.f); + EXPECT_FLOAT_EQ(att.q_d[2], 0.f); + EXPECT_FLOAT_EQ(att.q_d[3], 0.f); EXPECT_FLOAT_EQ(att.thrust_body[2], -1.f); /* expected: same as before but with 90 yaw * reason: only yaw changed */ yaw = M_PI_2_F; thrustToAttitude(thr, yaw, att); - EXPECT_FLOAT_EQ(att.roll_body, 0.f); - EXPECT_FLOAT_EQ(att.pitch_body, 0.f); - EXPECT_FLOAT_EQ(att.yaw_body, M_PI_2_F); + Eulerf euler_att(Quatf(att.q_d)); + EXPECT_FLOAT_EQ(euler_att.phi(), 0.f); + EXPECT_FLOAT_EQ(euler_att.theta(), 0.f); + EXPECT_FLOAT_EQ(euler_att.psi(), M_PI_2_F); EXPECT_FLOAT_EQ(att.thrust_body[2], -1.f); /* expected: same as before but roll 180 @@ -127,9 +129,10 @@ TEST(ControlMathTest, ThrottleAttitudeMapping) * order is: 1. roll, 2. pitch, 3. yaw */ thr = Vector3f(0.f, 0.f, 1.f); thrustToAttitude(thr, yaw, att); - EXPECT_FLOAT_EQ(att.roll_body, -M_PI_F); - EXPECT_FLOAT_EQ(att.pitch_body, 0.f); - EXPECT_FLOAT_EQ(att.yaw_body, M_PI_2_F); + Eulerf euler_att2(Quatf(att.q_d)); + EXPECT_FLOAT_EQ(std::abs(euler_att2.phi()), std::abs(M_PI_F)); + EXPECT_FLOAT_EQ(euler_att2.theta(), 0.f); + EXPECT_FLOAT_EQ(euler_att2.psi(), M_PI_2_F); EXPECT_FLOAT_EQ(att.thrust_body[2], -1.f); } diff --git a/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp b/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp index 0e5a60619a44..9c1e72b1a5c8 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp @@ -56,9 +56,10 @@ TEST(PositionControlTest, EmptySetpoint) vehicle_attitude_setpoint_s attitude{}; position_control.getAttitudeSetpoint(attitude); - EXPECT_FLOAT_EQ(attitude.roll_body, 0.f); - EXPECT_FLOAT_EQ(attitude.pitch_body, 0.f); - EXPECT_FLOAT_EQ(attitude.yaw_body, 0.f); + Eulerf euler_att(Quatf(attitude.q_d)); + EXPECT_FLOAT_EQ(euler_att.phi(), 0.f); + EXPECT_FLOAT_EQ(euler_att.theta(), 0.f); + EXPECT_FLOAT_EQ(euler_att.psi(), 0.f); EXPECT_FLOAT_EQ(attitude.yaw_sp_move_rate, 0.f); EXPECT_EQ(Quatf(attitude.q_d), Quatf(1.f, 0.f, 0.f, 0.f)); EXPECT_EQ(Vector3f(attitude.thrust_body), Vector3f(0.f, 0.f, 0.f)); @@ -184,7 +185,8 @@ TEST_F(PositionControlBasicTest, PositionControlMaxThrustLimit) EXPECT_FLOAT_EQ(_attitude.thrust_body[2], -MAXIMUM_THRUST); // Then the horizontal margin results in a tilt with the ratio of: horizontal margin / maximum thrust - EXPECT_FLOAT_EQ(_attitude.roll_body, asin((HORIZONTAL_THRUST_MARGIN / sqrt(2.f)) / MAXIMUM_THRUST)); + Eulerf euler_att(Quatf(_attitude.q_d)); + EXPECT_FLOAT_EQ(euler_att.phi(), asin((HORIZONTAL_THRUST_MARGIN / sqrt(2.f)) / MAXIMUM_THRUST)); // TODO: add this line back once attitude setpoint generation strategy does not align body yaw with heading all the time anymore // EXPECT_FLOAT_EQ(_attitude.pitch_body, -asin((HORIZONTAL_THRUST_MARGIN / sqrt(2.f)) / MAXIMUM_THRUST)); } @@ -198,9 +200,10 @@ TEST_F(PositionControlBasicTest, PositionControlMinThrustLimit) EXPECT_FLOAT_EQ(thrust.length(), 0.1f); EXPECT_FLOAT_EQ(_attitude.thrust_body[2], -0.1f); + Eulerf euler_att(Quatf(_attitude.q_d)); - EXPECT_FLOAT_EQ(_attitude.roll_body, 0.f); - EXPECT_FLOAT_EQ(_attitude.pitch_body, -1.f); + EXPECT_FLOAT_EQ(euler_att.phi(), 0.f); + EXPECT_FLOAT_EQ(euler_att.theta(), -1.f); } TEST_F(PositionControlBasicTest, FailsafeInput) @@ -377,6 +380,7 @@ TEST_F(PositionControlBasicTest, IntegratorWindupWithInvalidSetpoint) EXPECT_TRUE(runController()); // THEN: the integral did not wind up and produce unexpected deviation - EXPECT_FLOAT_EQ(_attitude.roll_body, 0.f); - EXPECT_FLOAT_EQ(_attitude.pitch_body, 0.f); + Eulerf euler_att(Quatf(_attitude.q_d)); + EXPECT_FLOAT_EQ(euler_att.phi(), 0.f); + EXPECT_FLOAT_EQ(euler_att.theta(), 0.f); } diff --git a/src/modules/rover_pos_control/RoverPositionControl.cpp b/src/modules/rover_pos_control/RoverPositionControl.cpp index 24909280e99c..928ce13c6edb 100644 --- a/src/modules/rover_pos_control/RoverPositionControl.cpp +++ b/src/modules/rover_pos_control/RoverPositionControl.cpp @@ -122,8 +122,8 @@ RoverPositionControl::manual_control_setpoint_poll() if (_control_mode.flag_control_attitude_enabled) { // STABILIZED mode generate the attitude setpoint from manual user inputs - _att_sp.roll_body = 0.0; - _att_sp.pitch_body = 0.0; + float roll_body = 0.0; + float pitch_body = 0.0; /* reset yaw setpoint to current position if needed */ if (_reset_yaw_sp) { @@ -137,10 +137,10 @@ RoverPositionControl::manual_control_setpoint_poll() _manual_yaw_sp = wrap_pi(_manual_yaw_sp + _att_sp.yaw_sp_move_rate * dt); } - _att_sp.yaw_body = _manual_yaw_sp; + float yaw_body = _manual_yaw_sp; _att_sp.thrust_body[0] = _manual_control_setpoint.throttle; - Quatf q(Eulerf(_att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body)); + const Quatf q(Eulerf(roll_body, pitch_body, yaw_body)); q.copyTo(_att_sp.q_d); _att_sp.timestamp = hrt_absolute_time(); diff --git a/src/modules/uuv_att_control/uuv_att_control.cpp b/src/modules/uuv_att_control/uuv_att_control.cpp index 58992ccb7803..52baccb8dde6 100644 --- a/src/modules/uuv_att_control/uuv_att_control.cpp +++ b/src/modules/uuv_att_control/uuv_att_control.cpp @@ -138,9 +138,10 @@ void UUVAttitudeControl::control_attitude_geo(const vehicle_attitude_s &attitude */ Eulerf euler_angles(matrix::Quatf(attitude.q)); - float roll_body = attitude_setpoint.roll_body; - float pitch_body = attitude_setpoint.pitch_body; - float yaw_body = attitude_setpoint.yaw_body; + const Eulerf setpoint_euler_angles(matrix::Quatf(attitude_setpoint.q_d)); + const float roll_body = setpoint_euler_angles(0); + const float pitch_body = setpoint_euler_angles(1); + const float yaw_body = setpoint_euler_angles(2); float roll_rate_desired = rates_setpoint.roll; float pitch_rate_desired = rates_setpoint.pitch; @@ -227,9 +228,8 @@ void UUVAttitudeControl::Run() _vehicle_rates_setpoint_sub.update(&_rates_setpoint); if (input_mode == 1) { // process manual data - _attitude_setpoint.roll_body = _param_direct_roll.get(); - _attitude_setpoint.pitch_body = _param_direct_pitch.get(); - _attitude_setpoint.yaw_body = _param_direct_yaw.get(); + Quatf attitude_setpoint(Eulerf(_param_direct_roll.get(), _param_direct_pitch.get(), _param_direct_yaw.get())); + attitude_setpoint.copyTo(_attitude_setpoint.q_d); _attitude_setpoint.thrust_body[0] = _param_direct_thrust.get(); _attitude_setpoint.thrust_body[1] = 0.f; _attitude_setpoint.thrust_body[2] = 0.f; diff --git a/src/modules/uuv_pos_control/uuv_pos_control.cpp b/src/modules/uuv_pos_control/uuv_pos_control.cpp index d402941b4a16..272ea56def8d 100644 --- a/src/modules/uuv_pos_control/uuv_pos_control.cpp +++ b/src/modules/uuv_pos_control/uuv_pos_control.cpp @@ -97,9 +97,8 @@ void UUVPOSControl::publish_attitude_setpoint(const float thrust_x, const float vehicle_attitude_setpoint_s vehicle_attitude_setpoint = {}; vehicle_attitude_setpoint.timestamp = hrt_absolute_time(); - vehicle_attitude_setpoint.roll_body = roll_des; - vehicle_attitude_setpoint.pitch_body = pitch_des; - vehicle_attitude_setpoint.yaw_body = yaw_des; + const Quatf attitude_setpoint(Eulerf(roll_des, pitch_des, yaw_des)); + attitude_setpoint.copyTo(vehicle_attitude_setpoint.q_d); vehicle_attitude_setpoint.thrust_body[0] = thrust_x; vehicle_attitude_setpoint.thrust_body[1] = thrust_y; diff --git a/src/modules/vtol_att_control/standard.cpp b/src/modules/vtol_att_control/standard.cpp index 84606aad4327..105ee1ee6efa 100644 --- a/src/modules/vtol_att_control/standard.cpp +++ b/src/modules/vtol_att_control/standard.cpp @@ -172,6 +172,11 @@ void Standard::update_transition_state() VtolType::update_transition_state(); + const Eulerf attitude_setpoint_euler(Quatf(_v_att_sp->q_d)); + float roll_body = attitude_setpoint_euler.phi(); + float pitch_body = attitude_setpoint_euler.theta(); + float yaw_body = attitude_setpoint_euler.psi(); + // we get attitude setpoint from a multirotor flighttask if climbrate is controlled. // in any other case the fixed wing attitude controller publishes attitude setpoint from manual stick input. if (_v_control_mode->flag_control_climb_rate_enabled) { @@ -181,7 +186,7 @@ void Standard::update_transition_state() } memcpy(_v_att_sp, _mc_virtual_att_sp, sizeof(vehicle_attitude_setpoint_s)); - _v_att_sp->roll_body = _fw_virtual_att_sp->roll_body; + roll_body = Eulerf(Quatf(_fw_virtual_att_sp->q_d)).phi(); } else { // we need a recent incoming (fw virtual) attitude setpoint, otherwise return (means the previous setpoint stays active) @@ -227,21 +232,19 @@ void Standard::update_transition_state() } // ramp up FW_PSP_OFF - _v_att_sp->pitch_body = math::radians(_param_fw_psp_off.get()) * (1.0f - mc_weight); - + pitch_body = math::radians(_param_fw_psp_off.get()) * (1.0f - mc_weight); _v_att_sp->thrust_body[0] = _pusher_throttle; - - const Quatf q_sp(Eulerf(_v_att_sp->roll_body, _v_att_sp->pitch_body, _v_att_sp->yaw_body)); + const Quatf q_sp(Eulerf(roll_body, pitch_body, yaw_body)); q_sp.copyTo(_v_att_sp->q_d); } else if (_vtol_mode == vtol_mode::TRANSITION_TO_MC) { if (_v_control_mode->flag_control_climb_rate_enabled) { // control backtransition deceleration using pitch. - _v_att_sp->pitch_body = update_and_get_backtransition_pitch_sp(); + pitch_body = update_and_get_backtransition_pitch_sp(); } - const Quatf q_sp(Eulerf(_v_att_sp->roll_body, _v_att_sp->pitch_body, _v_att_sp->yaw_body)); + const Quatf q_sp(Eulerf(roll_body, pitch_body, yaw_body)); q_sp.copyTo(_v_att_sp->q_d); _pusher_throttle = 0.0f; diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index af95a05083c3..eaacbe68d611 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -179,7 +179,8 @@ void Tailsitter::update_transition_state() // the yaw setpoint and zero roll since we want wings level transition. // If for some reason the fw attitude setpoint is not recent then don't use it and assume 0 pitch if (_fw_virtual_att_sp->timestamp > (now - 1_s)) { - _q_trans_start = Eulerf(0.f, _fw_virtual_att_sp->pitch_body, yaw_sp); + const float pitch_body = Eulerf(Quatf(_fw_virtual_att_sp->q_d)).theta(); + _q_trans_start = Eulerf(0.f, pitch_body, yaw_sp); } else { _q_trans_start = Eulerf(0.f, 0.f, yaw_sp); @@ -191,7 +192,8 @@ void Tailsitter::update_transition_state() } else if (_vtol_mode == vtol_mode::TRANSITION_FRONT_P1) { // initial attitude setpoint for the transition should be with wings level - _q_trans_start = Eulerf(0.f, _mc_virtual_att_sp->pitch_body, _mc_virtual_att_sp->yaw_body); + const Eulerf setpoint_euler(Quatf(_mc_virtual_att_sp->q_d)); + _q_trans_start = Eulerf(0.f, setpoint_euler.theta(), setpoint_euler.psi()); Vector3f x = Dcmf(Quatf(_v_att->q)) * Vector3f(1.f, 0.f, 0.f); _trans_rot_axis = -x.cross(Vector3f(0.f, 0.f, -1.f)); } @@ -238,10 +240,6 @@ void Tailsitter::update_transition_state() _v_att_sp->timestamp = hrt_absolute_time(); const Eulerf euler_sp(_q_trans_sp); - _v_att_sp->roll_body = euler_sp.phi(); - _v_att_sp->pitch_body = euler_sp.theta(); - _v_att_sp->yaw_body = euler_sp.psi(); - _q_trans_sp.copyTo(_v_att_sp->q_d); } diff --git a/src/modules/vtol_att_control/tiltrotor.cpp b/src/modules/vtol_att_control/tiltrotor.cpp index 0956e1003698..3a1904257993 100644 --- a/src/modules/vtol_att_control/tiltrotor.cpp +++ b/src/modules/vtol_att_control/tiltrotor.cpp @@ -203,6 +203,11 @@ void Tiltrotor::update_transition_state() const hrt_abstime now = hrt_absolute_time(); + const Eulerf attitude_setpoint_euler(Quatf(_v_att_sp->q_d)); + float roll_body = attitude_setpoint_euler.phi(); + float pitch_body = attitude_setpoint_euler.theta(); + float yaw_body = attitude_setpoint_euler.psi(); + // we get attitude setpoint from a multirotor flighttask if altitude is controlled. // in any other case the fixed wing attitude controller publishes attitude setpoint from manual stick input. if (_v_control_mode->flag_control_climb_rate_enabled) { @@ -212,7 +217,7 @@ void Tiltrotor::update_transition_state() } memcpy(_v_att_sp, _mc_virtual_att_sp, sizeof(vehicle_attitude_setpoint_s)); - _v_att_sp->roll_body = _fw_virtual_att_sp->roll_body; + roll_body = Eulerf(Quatf(_fw_virtual_att_sp->q_d)).phi(); _thrust_transition = -_mc_virtual_att_sp->thrust_body[2]; } else { @@ -290,7 +295,7 @@ void Tiltrotor::update_transition_state() // control backtransition deceleration using pitch. if (_v_control_mode->flag_control_climb_rate_enabled) { - _v_att_sp->pitch_body = update_and_get_backtransition_pitch_sp(); + pitch_body = update_and_get_backtransition_pitch_sp(); } if (_time_since_trans_start < BACKTRANS_THROTTLE_DOWNRAMP_DUR_S) { @@ -321,7 +326,7 @@ void Tiltrotor::update_transition_state() _v_att_sp->thrust_body[2] = -_thrust_transition; - const Quatf q_sp(Eulerf(_v_att_sp->roll_body, _v_att_sp->pitch_body, _v_att_sp->yaw_body)); + const Quatf q_sp(Eulerf(roll_body, pitch_body, yaw_body)); q_sp.copyTo(_v_att_sp->q_d); _mc_roll_weight = math::constrain(_mc_roll_weight, 0.0f, 1.0f); diff --git a/src/modules/vtol_att_control/vtol_type.cpp b/src/modules/vtol_att_control/vtol_type.cpp index e43dd7c912ad..458b3927fb9c 100644 --- a/src/modules/vtol_att_control/vtol_type.cpp +++ b/src/modules/vtol_att_control/vtol_type.cpp @@ -563,10 +563,10 @@ float VtolType::pusher_assist() tilt_new = R_yaw_correction * tilt_new; // now extract roll and pitch setpoints - _v_att_sp->pitch_body = atan2f(tilt_new(0), tilt_new(2)); - _v_att_sp->roll_body = -asinf(tilt_new(1)); + const float pitch_body = atan2f(tilt_new(0), tilt_new(2)); + const float roll_body = -asinf(tilt_new(1)); - const Quatf q_sp(Eulerf(_v_att_sp->roll_body, _v_att_sp->pitch_body, euler_sp(2))); + const Quatf q_sp(Eulerf(roll_body, pitch_body, euler_sp(2))); q_sp.copyTo(_v_att_sp->q_d); } From db8781e5311c876cb948fc2e10c0ec6d0ff96372 Mon Sep 17 00:00:00 2001 From: "murata,katsutoshi" Date: Tue, 13 Aug 2024 02:09:22 +0900 Subject: [PATCH 610/652] navigator: Align MAVLINK message level with EVENT message level (#23535) --- src/modules/navigator/geofence.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index 55917331a614..ea2c30a18eee 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -648,7 +648,7 @@ Geofence::loadFromFile(const char *filename) } else { mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Geofence: import error\t"); - events::send(events::ID("navigator_geofence_import_failed"), events::Log::Error, "Geofence: import error"); + events::send(events::ID("navigator_geofence_import_failed"), events::Log::Critical, "Geofence: import error"); } updateFence(); From afc360d637d4ce9eca67a01c1faef15c16d4ebc6 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 9 Aug 2024 14:18:39 +0200 Subject: [PATCH 611/652] FW Position control: do not invalidate airspeed from negative readings Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 4da7168255f9..9d126262fb17 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -212,8 +212,7 @@ FixedwingPositionControl::airspeed_poll() _eas2tas = 1.0f; //this is the default value, taken in case of invalid airspeed if (PX4_ISFINITE(airspeed_validated.calibrated_airspeed_m_s) - && PX4_ISFINITE(airspeed_validated.true_airspeed_m_s) - && (airspeed_validated.calibrated_airspeed_m_s > FLT_EPSILON)) { + && PX4_ISFINITE(airspeed_validated.true_airspeed_m_s)) { airspeed_valid = true; From acc0cd7e8ad915eaede3f7efaa58bbb831c12628 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 9 Aug 2024 14:22:33 +0200 Subject: [PATCH 612/652] FW Position Control: disable underspeed handling during auto takeoff Signed-off-by: Silvan Fuhrer --- src/modules/fw_pos_control/FixedwingPositionControl.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 9d126262fb17..5143a4da3899 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1549,7 +1549,8 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _param_fw_thr_min.get(), _param_fw_thr_max.get(), _param_sinkrate_target.get(), - _performance_model.getMaximumClimbRate(_air_density)); + _performance_model.getMaximumClimbRate(_air_density), + true); // disable underspeed handling _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation @@ -1634,7 +1635,8 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _param_fw_thr_min.get(), max_takeoff_throttle, _param_sinkrate_target.get(), - _performance_model.getMaximumClimbRate(_air_density)); + _performance_model.getMaximumClimbRate(_air_density), + true); // disable underspeed handling if (_launchDetector.getLaunchDetected() < launch_detection_status_s::STATE_FLYING) { // explicitly set idle throttle until motors are enabled From a0d22a4d212a87980a47524b5d5633cf6e918ace Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 12 Aug 2024 10:39:29 +0200 Subject: [PATCH 613/652] FW Position Control: make explicit when underspeed detection logic is en-/disabled Signed-off-by: Silvan Fuhrer --- .../FixedwingPositionControl.cpp | 31 +++++++++++++------ 1 file changed, 22 insertions(+), 9 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 5143a4da3899..7858fe2c1c5f 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -973,6 +973,7 @@ FixedwingPositionControl::control_auto_descend(const float control_interval) // Hard-code descend rate to 0.5m/s. This is a compromise to give the system to recover, // but not letting it drift too far away. const float descend_rate = -0.5f; + const bool disable_underspeed_handling = false; tecs_update_pitch_throttle(control_interval, _current_altitude, @@ -983,7 +984,7 @@ FixedwingPositionControl::control_auto_descend(const float control_interval) _param_fw_thr_max.get(), _param_sinkrate_target.get(), _param_climbrate_target.get(), - false, + disable_underspeed_handling, descend_rate); const float roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle @@ -1170,6 +1171,7 @@ FixedwingPositionControl::control_auto_velocity(const float control_interval, co target_airspeed = _npfg.getAirspeedRef() / _eas2tas; float yaw_body = _yaw; + const bool disable_underspeed_handling = false; tecs_update_pitch_throttle(control_interval, position_sp_alt, @@ -1180,7 +1182,7 @@ FixedwingPositionControl::control_auto_velocity(const float control_interval, co tecs_fw_thr_max, _param_sinkrate_target.get(), _param_climbrate_target.get(), - false, + disable_underspeed_handling, pos_sp_curr.vz); const float pitch_body = get_tecs_pitch(); @@ -1541,6 +1543,8 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _tecs.resetIntegrals(); } + const bool disable_underspeed_handling = true; + tecs_update_pitch_throttle(control_interval, altitude_setpoint_amsl, target_airspeed, @@ -1550,7 +1554,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _param_fw_thr_max.get(), _param_sinkrate_target.get(), _performance_model.getMaximumClimbRate(_air_density), - true); // disable underspeed handling + disable_underspeed_handling); _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation @@ -1626,6 +1630,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo const float max_takeoff_throttle = (_launchDetector.getLaunchDetected() < launch_detection_status_s::STATE_FLYING) ? _param_fw_thr_idle.get() : _param_fw_thr_max.get(); + const bool disable_underspeed_handling = true; tecs_update_pitch_throttle(control_interval, altitude_setpoint_amsl, @@ -1636,7 +1641,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo max_takeoff_throttle, _param_sinkrate_target.get(), _performance_model.getMaximumClimbRate(_air_density), - true); // disable underspeed handling + disable_underspeed_handling); if (_launchDetector.getLaunchDetected() < launch_detection_status_s::STATE_FLYING) { // explicitly set idle throttle until motors are enabled @@ -1813,6 +1818,7 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, const float throttle_max = flare_ramp_interpolator_sqrt * _param_fw_thr_idle.get() + (1.0f - flare_ramp_interpolator_sqrt) * _param_fw_thr_max.get(); + const bool disable_underspeed_handling = true; tecs_update_pitch_throttle(control_interval, altitude_setpoint, @@ -1823,7 +1829,7 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, throttle_max, _param_sinkrate_target.get(), _param_climbrate_target.get(), - true, + disable_underspeed_handling, height_rate_setpoint); /* set the attitude and throttle commands */ @@ -2029,6 +2035,7 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, const float throttle_max = flare_ramp_interpolator_sqrt * _param_fw_thr_idle.get() + (1.0f - flare_ramp_interpolator_sqrt) * _param_fw_thr_max.get(); + const bool disable_underspeed_handling = true; tecs_update_pitch_throttle(control_interval, _current_altitude, // is not controlled, control descend rate @@ -2039,7 +2046,7 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, throttle_max, _param_sinkrate_target.get(), _param_climbrate_target.get(), - true, + disable_underspeed_handling, height_rate_setpoint); /* set the attitude and throttle commands */ @@ -2085,6 +2092,8 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, const float glide_slope_sink_rate = airspeed_land * glide_slope / sqrtf(glide_slope * glide_slope + 1.0f); const float desired_max_sinkrate = math::min(math::max(glide_slope_sink_rate, _param_sinkrate_target.get()), _param_fw_t_sink_max.get()); + const bool disable_underspeed_handling = false; + tecs_update_pitch_throttle(control_interval, _current_altitude, // is not controlled, control descend rate target_airspeed, @@ -2094,7 +2103,7 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, _param_fw_thr_max.get(), desired_max_sinkrate, _param_climbrate_target.get(), - false, + disable_underspeed_handling, -glide_slope_sink_rate); // heightrate = -sinkrate /* set the attitude and throttle commands */ @@ -2151,6 +2160,8 @@ FixedwingPositionControl::control_manual_altitude(const float control_interval, throttle_max = 0.0f; } + const bool disable_underspeed_handling = false; + tecs_update_pitch_throttle(control_interval, _current_altitude, calibrated_airspeed_sp, @@ -2160,7 +2171,7 @@ FixedwingPositionControl::control_manual_altitude(const float control_interval, throttle_max, _param_sinkrate_target.get(), _param_climbrate_target.get(), - false, + disable_underspeed_handling, height_rate_sp); float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); @@ -2251,6 +2262,8 @@ FixedwingPositionControl::control_manual_position(const float control_interval, } } + const bool disable_underspeed_handling = false; + tecs_update_pitch_throttle(control_interval, _current_altitude, // TODO: check if this is really what we want.. or if we want to lock the altitude. calibrated_airspeed_sp, @@ -2260,7 +2273,7 @@ FixedwingPositionControl::control_manual_position(const float control_interval, throttle_max, _param_sinkrate_target.get(), _param_climbrate_target.get(), - false, + disable_underspeed_handling, height_rate_sp); if (!_yaw_lock_engaged || fabsf(_manual_control_setpoint.roll) >= HDG_HOLD_MAN_INPUT_THRESH || From aad607e0dd1b216ec3e156d2d00fff7b870a74f5 Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 13 Aug 2024 14:37:52 +0200 Subject: [PATCH 614/652] ekf2: send airspeed data to ekf backend regardless of sign On ground the airspeed can sometimes be slightly negative but the ekf should still know that airspeed data is flowing regularly --- src/modules/ekf2/EKF2.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index bceb4d3dcc23..af2eb6615f40 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2076,14 +2076,19 @@ void EKF2::UpdateAirspeedSample(ekf2_timestamps_s &ekf2_timestamps) if (_airspeed_validated_sub.update(&airspeed_validated)) { if (PX4_ISFINITE(airspeed_validated.true_airspeed_m_s) - && PX4_ISFINITE(airspeed_validated.calibrated_airspeed_m_s) - && (airspeed_validated.calibrated_airspeed_m_s > 0.f) && (airspeed_validated.selected_airspeed_index > 0) ) { + float cas2tas = 1.f; + + if (PX4_ISFINITE(airspeed_validated.calibrated_airspeed_m_s) + && (airspeed_validated.calibrated_airspeed_m_s > FLT_EPSILON)) { + cas2tas = airspeed_validated.true_airspeed_m_s / airspeed_validated.calibrated_airspeed_m_s; + } + airspeedSample airspeed_sample { .time_us = airspeed_validated.timestamp, .true_airspeed = airspeed_validated.true_airspeed_m_s, - .eas2tas = airspeed_validated.true_airspeed_m_s / airspeed_validated.calibrated_airspeed_m_s, + .eas2tas = cas2tas, }; _ekf.setAirspeedData(airspeed_sample); } From e2c0e5c88ab68cafbee9b4fe4562882858706a63 Mon Sep 17 00:00:00 2001 From: Stefano Colli <45536733+StefanoColli@users.noreply.github.com> Date: Tue, 13 Aug 2024 22:20:28 +0200 Subject: [PATCH 615/652] MissionBase: replay the gimbal and trigger cached items only upon reaching resume waypoint (#23484) * Fix: replay the mission cached items only upon reaching resume waypoint * Refactoring Split camera mode mission items from gimbal ones so to have a finer control over the relative replays * Chore: fix formatting --------- Co-authored-by: Silvan Fuhrer --- src/modules/navigator/mission_base.cpp | 42 ++++++++++++++++++-------- src/modules/navigator/mission_base.h | 21 ++++++++++--- 2 files changed, 47 insertions(+), 16 deletions(-) diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index d41456ccce66..6a64f46044e8 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -235,6 +235,7 @@ MissionBase::on_activation() checkClimbRequired(_mission.current_seq); set_mission_items(); + _mission_activation_index = _mission.current_seq; _inactivation_index = -1; // reset // reset cruise speed @@ -293,17 +294,27 @@ MissionBase::on_active() _align_heading_necessary = false; } - // replay gimbal and camera commands immediately after resuming mission - if (haveCachedGimbalOrCameraItems()) { - replayCachedGimbalCameraItems(); + // Replay camera mode commands immediately upon mission resume + if (haveCachedCameraModeItems()) { + replayCachedCameraModeItems(); } - // replay trigger commands upon raching the resume waypoint if the trigger relay flag is set - if (cameraWasTriggering() && is_mission_item_reached_or_completed()) { - replayCachedTriggerItems(); - } - replayCachedSpeedChangeItems(); + // Replay cached mission commands once the last mission waypoint is re-reached after the mission interruption. + // Each replay function also clears the cached items afterwards + if (_mission.current_seq > _mission_activation_index) { + // replay gimbal commands + if (haveCachedGimbalItems()) { + replayCachedGimbalItems(); + } + + // replay trigger commands + if (cameraWasTriggering()) { + replayCachedTriggerItems(); + } + + replayCachedSpeedChangeItems(); + } /* lets check if we reached the current mission item */ if (_mission_type != MissionType::MISSION_TYPE_NONE && is_mission_item_reached_or_completed()) { @@ -1255,7 +1266,7 @@ void MissionBase::cacheItem(const mission_item_s &mission_item) } } -void MissionBase::replayCachedGimbalCameraItems() +void MissionBase::replayCachedGimbalItems() { if (_last_gimbal_configure_item.nav_cmd > 0) { issue_command(_last_gimbal_configure_item); @@ -1266,7 +1277,10 @@ void MissionBase::replayCachedGimbalCameraItems() issue_command(_last_gimbal_control_item); _last_gimbal_control_item = {}; // delete cached item } +} +void MissionBase::replayCachedCameraModeItems() +{ if (_last_camera_mode_item.nav_cmd > 0) { issue_command(_last_camera_mode_item); _last_camera_mode_item = {}; // delete cached item @@ -1297,11 +1311,15 @@ void MissionBase::resetItemCache() _last_camera_trigger_item = {}; } -bool MissionBase::haveCachedGimbalOrCameraItems() +bool MissionBase::haveCachedGimbalItems() { return _last_gimbal_configure_item.nav_cmd > 0 || - _last_gimbal_control_item.nav_cmd > 0 || - _last_camera_mode_item.nav_cmd > 0; + _last_gimbal_control_item.nav_cmd > 0; +} + +bool MissionBase::haveCachedCameraModeItems() +{ + return _last_camera_mode_item.nav_cmd > 0; } bool MissionBase::cameraWasTriggering() diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index 2f416f29e206..35d4d37030de 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -328,6 +328,7 @@ class MissionBase : public MissionBlock, public ModuleParams mission_s _mission; /**< Currently active mission*/ float _mission_init_climb_altitude_amsl{NAN}; /**< altitude AMSL the vehicle will climb to when mission starts */ int _inactivation_index{-1}; // index of mission item at which the mission was paused. Used to resume survey missions at previous waypoint to not lose images. + int _mission_activation_index{-1}; /**< Index of the mission item that will bring the vehicle back to a mission waypoint */ int32_t _load_mission_index{-1}; /**< Mission inted of loaded mission items in dataman cache*/ int32_t _dataman_cache_size_signed; /**< Size of the dataman cache. A negativ value indicates that previous mission items should be loaded, a positiv value the next mission items*/ @@ -398,9 +399,14 @@ class MissionBase : public MissionBlock, public ModuleParams void updateCachedItemsUpToIndex(int end_index); /** - * @brief Replay the cached gimbal and camera mode items + * @brief Replay the cached gimbal items */ - void replayCachedGimbalCameraItems(); + void replayCachedGimbalItems(); + + /** + * @brief Replay the cached camera mode items + */ + void replayCachedCameraModeItems(); /** * @brief Replay the cached trigger items @@ -415,11 +421,18 @@ class MissionBase : public MissionBlock, public ModuleParams void replayCachedSpeedChangeItems(); /** - * @brief Check if there are cached gimbal or camera mode items to be replayed + * @brief Check if there are cached gimbal items to be replayed + * + * @return true if there are cached items + */ + bool haveCachedGimbalItems(); + + /** + * @brief Check if there are cached camera mode items to be replayed * * @return true if there are cached items */ - bool haveCachedGimbalOrCameraItems(); + bool haveCachedCameraModeItems(); /** * @brief Check if the camera was triggering From fd062d00859fccce7f25de8dacae9d67c5440545 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Tue, 13 Aug 2024 13:30:33 +0300 Subject: [PATCH 616/652] icm40609d: Clear interrupt status at FIFO reset If DRDY signal is used, the interrupt status needs to be cleared at FIFO reset in order to make DRDY go back inactive. Otherwise there won't be a falling edge interrupt at the next sample. Signed-off-by: Jukka Laitinen --- src/drivers/imu/invensense/icm40609d/ICM40609D.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp b/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp index 8dc0f4b79512..55db372d5d39 100644 --- a/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp +++ b/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp @@ -599,6 +599,9 @@ void ICM40609D::FIFOReset() // SIGNAL_PATH_RESET: FIFO flush RegisterSetBits(Register::BANK_0::SIGNAL_PATH_RESET, SIGNAL_PATH_RESET_BIT::FIFO_FLUSH); + // Read INT_STATUS to clear + RegisterRead(Register::BANK_0::INT_STATUS); + // reset while FIFO is disabled _drdy_timestamp_sample.store(0); } From cc4d5bd2a66f5a68c8e1b5850545376449e41dd4 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Tue, 13 Aug 2024 13:40:49 +0300 Subject: [PATCH 617/652] icm40609d: Add INTF register definition and disable I2C interface Disable I2C to make sure that the sensor doesn't switch to that by accident Signed-off-by: Jukka Laitinen --- src/drivers/imu/invensense/icm40609d/ICM40609D.hpp | 3 ++- .../icm40609d/InvenSense_ICM40609D_registers.hpp | 12 ++++++++++++ 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp b/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp index ab6fcfa1f27b..882e11a91ee8 100644 --- a/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp +++ b/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp @@ -160,10 +160,11 @@ class ICM40609D : public device::SPI, public I2CSPIDriver int32_t _fifo_gyro_samples{static_cast(_fifo_empty_interval_us / (1000000 / GYRO_RATE))}; uint8_t _checked_register_bank0{0}; - static constexpr uint8_t size_register_bank0_cfg{10}; + static constexpr uint8_t size_register_bank0_cfg{11}; register_bank0_config_t _register_bank0_cfg[size_register_bank0_cfg] { // Register | Set bits, Clear bits { Register::BANK_0::INT_CONFIG, INT_CONFIG_BIT::INT1_MODE | INT_CONFIG_BIT::INT1_DRIVE_CIRCUIT, INT_CONFIG_BIT::INT1_POLARITY }, + { Register::BANK_0::INTF_CONFIG0, INTF_CONFIG0_BIT::UI_SIFS_CFG_DISABLE_I2C, 0}, { Register::BANK_0::FIFO_CONFIG, FIFO_CONFIG_BIT::FIFO_MODE_STOP_ON_FULL, 0 }, { Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE, 0 }, { Register::BANK_0::GYRO_CONFIG0, GYRO_CONFIG0_BIT::GYRO_ODR_8kHz, Bit7 | Bit6 | Bit5 | Bit3 | Bit2 }, diff --git a/src/drivers/imu/invensense/icm40609d/InvenSense_ICM40609D_registers.hpp b/src/drivers/imu/invensense/icm40609d/InvenSense_ICM40609D_registers.hpp index 4d359526ba92..e9880ec8cdd0 100644 --- a/src/drivers/imu/invensense/icm40609d/InvenSense_ICM40609D_registers.hpp +++ b/src/drivers/imu/invensense/icm40609d/InvenSense_ICM40609D_registers.hpp @@ -82,6 +82,8 @@ enum class BANK_0 : uint8_t { SIGNAL_PATH_RESET = 0x4B, + INTF_CONFIG0 = 0x4C, + PWR_MGMT0 = 0x4E, GYRO_CONFIG0 = 0x4F, ACCEL_CONFIG0 = 0x50, @@ -132,6 +134,16 @@ enum SIGNAL_PATH_RESET_BIT : uint8_t { FIFO_FLUSH = Bit1, }; +// INTF_CONFIG0 +enum INTF_CONFIG0_BIT : uint8_t { + FIFO_HOLD_LAST_DATA_EN = Bit7, + FIFO_COUNT_REC = Bit6, + FIFO_COUNT_ENDIAN = Bit5, + SENSOR_DATA_ENDIAN = Bit4, + UI_SIFS_CFG_DISABLE_SPI = Bit1, + UI_SIFS_CFG_DISABLE_I2C = Bit1 | Bit0 +}; + // PWR_MGMT0 enum PWR_MGMT0_BIT : uint8_t { GYRO_MODE_LOW_NOISE = Bit3 | Bit2, // 11: Places gyroscope in Low Noise (LN) Mode From 0459481cb4e4e22912fa9d29bea2a1385bf05ea6 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Mon, 12 Aug 2024 16:08:10 +0300 Subject: [PATCH 618/652] icm40609d: Change FIFO count to samples instead of bytes As the sensor can directly report the amount of samples in the fifo, use it to simplify the logic. Also combine the fifo empty/fifo overflow checks for interrupt and polling modes. Signed-off-by: Jukka Laitinen --- .../imu/invensense/icm40609d/ICM40609D.cpp | 89 ++++++------------- .../imu/invensense/icm40609d/ICM40609D.hpp | 2 +- 2 files changed, 29 insertions(+), 62 deletions(-) diff --git a/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp b/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp index 55db372d5d39..28fce0691ce9 100644 --- a/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp +++ b/src/drivers/imu/invensense/icm40609d/ICM40609D.cpp @@ -203,57 +203,45 @@ void ICM40609D::RunImpl() case STATE::FIFO_READ: { hrt_abstime timestamp_sample = now; - uint8_t samples = 0; + uint8_t samples = FIFOReadCount(); - if (_data_ready_interrupt_enabled) { - // scheduled from interrupt if _drdy_timestamp_sample was set as expected - const hrt_abstime drdy_timestamp_sample = _drdy_timestamp_sample.fetch_and(0); - - if ((now - drdy_timestamp_sample) < _fifo_empty_interval_us) { - timestamp_sample = drdy_timestamp_sample; - samples = _fifo_gyro_samples; + if (samples == 0) { + perf_count(_fifo_empty_perf); - } else { - perf_count(_drdy_missed_perf); + } else { + // tolerate minor jitter, leave sample to next iteration if behind by only 1 + if (samples == _fifo_gyro_samples + 1) { + timestamp_sample -= static_cast(FIFO_SAMPLE_DT); + samples--; } - // push backup schedule back - ScheduleDelayed(_fifo_empty_interval_us * 2); - } - - if (samples == 0) { - // check current FIFO count - const uint16_t fifo_count = FIFOReadCount(); - - if (fifo_count >= FIFO::SIZE) { + if (samples > FIFO_MAX_SAMPLES) { + // not technically an overflow, but more samples than we expected or can publish FIFOReset(); perf_count(_fifo_overflow_perf); + samples = 0; + } + } - } else if (fifo_count == 0) { - perf_count(_fifo_empty_perf); + bool success = false; - } else { - // FIFO count (size in bytes) - samples = (fifo_count / sizeof(FIFO::DATA)); + if (samples > 0) { + if (_data_ready_interrupt_enabled) { + // scheduled from interrupt if _drdy_timestamp_sample was set as expected + const hrt_abstime drdy_timestamp_sample = _drdy_timestamp_sample.fetch_and(0); - // tolerate minor jitter, leave sample to next iteration if behind by only 1 - if (samples == _fifo_gyro_samples + 1) { - timestamp_sample -= static_cast(FIFO_SAMPLE_DT); - samples--; - } + if ((now - drdy_timestamp_sample) < _fifo_empty_interval_us) { + timestamp_sample = drdy_timestamp_sample; + samples = _fifo_gyro_samples; - if (samples > FIFO_MAX_SAMPLES) { - // not technically an overflow, but more samples than we expected or can publish - FIFOReset(); - perf_count(_fifo_overflow_perf); - samples = 0; + } else { + perf_count(_drdy_missed_perf); } - } - } - bool success = false; + // push backup schedule back + ScheduleDelayed(_fifo_empty_interval_us * 2); + } - if (samples >= 1) { if (FIFORead(timestamp_sample, samples)) { success = true; @@ -374,17 +362,11 @@ void ICM40609D::ConfigureSampleRate(int sample_rate) void ICM40609D::ConfigureFIFOWatermark(uint8_t samples) { - // FIFO watermark threshold in number of bytes - const uint16_t fifo_watermark_threshold = samples * sizeof(FIFO::DATA); - for (auto &r : _register_bank0_cfg) { if (r.reg == Register::BANK_0::FIFO_CONFIG2) { // FIFO_WM[7:0] FIFO_CONFIG2 - r.set_bits = fifo_watermark_threshold & 0xFF; + r.set_bits = samples & 0xFF; - } else if (r.reg == Register::BANK_0::FIFO_CONFIG3) { - // FIFO_WM[11:8] FIFO_CONFIG3 - r.set_bits = (fifo_watermark_threshold >> 8) & 0x0F; } } } @@ -537,25 +519,10 @@ bool ICM40609D::FIFORead(const hrt_abstime ×tamp_sample, uint8_t samples) return false; } - const uint16_t fifo_count_bytes = combine(buffer.FIFO_COUNTH, buffer.FIFO_COUNTL); - - if (fifo_count_bytes >= FIFO::SIZE) { - perf_count(_fifo_overflow_perf); - FIFOReset(); - return false; - } - - const uint8_t fifo_count_samples = fifo_count_bytes / sizeof(FIFO::DATA); - - if (fifo_count_samples == 0) { - perf_count(_fifo_empty_perf); - return false; - } - // check FIFO header in every sample uint8_t valid_samples = 0; - for (int i = 0; i < math::min(samples, fifo_count_samples); i++) { + for (int i = 0; i < samples; i++) { bool valid = true; // With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8’b_0110_10xx diff --git a/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp b/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp index 882e11a91ee8..8dee6c2fb793 100644 --- a/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp +++ b/src/drivers/imu/invensense/icm40609d/ICM40609D.hpp @@ -164,7 +164,7 @@ class ICM40609D : public device::SPI, public I2CSPIDriver register_bank0_config_t _register_bank0_cfg[size_register_bank0_cfg] { // Register | Set bits, Clear bits { Register::BANK_0::INT_CONFIG, INT_CONFIG_BIT::INT1_MODE | INT_CONFIG_BIT::INT1_DRIVE_CIRCUIT, INT_CONFIG_BIT::INT1_POLARITY }, - { Register::BANK_0::INTF_CONFIG0, INTF_CONFIG0_BIT::UI_SIFS_CFG_DISABLE_I2C, 0}, + { Register::BANK_0::INTF_CONFIG0, INTF_CONFIG0_BIT::FIFO_COUNT_REC | INTF_CONFIG0_BIT::UI_SIFS_CFG_DISABLE_I2C, 0}, { Register::BANK_0::FIFO_CONFIG, FIFO_CONFIG_BIT::FIFO_MODE_STOP_ON_FULL, 0 }, { Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE, 0 }, { Register::BANK_0::GYRO_CONFIG0, GYRO_CONFIG0_BIT::GYRO_ODR_8kHz, Bit7 | Bit6 | Bit5 | Bit3 | Bit2 }, From a327b14cefbbe1f61b56a2e1ec3b71894e920f19 Mon Sep 17 00:00:00 2001 From: "murata,katsutoshi" Date: Wed, 14 Aug 2024 10:33:36 +0900 Subject: [PATCH 619/652] navigator: always fully initialize geofence msg --- src/modules/navigator/geofence.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index ea2c30a18eee..2c317bb79d9b 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -104,7 +104,7 @@ void Geofence::run() _initiate_fence_updated = false; _dataman_state = DatamanState::Read; - geofence_status_s status; + geofence_status_s status{}; status.timestamp = hrt_absolute_time(); status.geofence_id = _opaque_id; status.status = geofence_status_s::GF_STATUS_LOADING; @@ -159,7 +159,7 @@ void Geofence::run() _dataman_state = DatamanState::UpdateRequestWait; _fence_updated = true; - geofence_status_s status; + geofence_status_s status{}; status.timestamp = hrt_absolute_time(); status.geofence_id = _opaque_id; status.status = geofence_status_s::GF_STATUS_READY; @@ -179,7 +179,7 @@ void Geofence::run() _updateFence(); _fence_updated = true; - geofence_status_s status; + geofence_status_s status{}; status.timestamp = hrt_absolute_time(); status.geofence_id = _opaque_id; status.status = geofence_status_s::GF_STATUS_READY; From 5121358e879d9a61bb9e4565206e2705be2e650e Mon Sep 17 00:00:00 2001 From: mirusu400 Date: Tue, 13 Aug 2024 21:34:39 -0400 Subject: [PATCH 620/652] Makefile: Fix error message when cannot find target board not $(MAKE) help|list_config_targets, we should use $(MAKE) list_config_targets for the desired results. --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index fe8580402dab..7d4283a95690 100644 --- a/Makefile +++ b/Makefile @@ -549,7 +549,7 @@ distclean: # All other targets are handled by PX4_MAKE. Add a rule here to avoid printing an error. %: $(if $(filter $(FIRST_ARG),$@), \ - $(error "Make target $@ not found. It either does not exist or $@ cannot be the first argument. Use '$(MAKE) help|list_config_targets' to get a list of all possible [configuration] targets."),@#) + $(error "Make target $@ not found. It either does not exist or $@ cannot be the first argument. Use '$(MAKE) list_config_targets' to get a list of all possible [configuration] targets."),@#) # Print a list of non-config targets (based on http://stackoverflow.com/a/26339924/1487069) help: From f3a8d05f8c2ad79c8ea22ea70328aebddc3371b7 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 14 Aug 2024 12:18:14 +1000 Subject: [PATCH 621/652] MPC_ACC_DECOUPLE - better description (#23518) --- .../mc_pos_control/multicopter_position_control_limits_params.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/mc_pos_control/multicopter_position_control_limits_params.c b/src/modules/mc_pos_control/multicopter_position_control_limits_params.c index 91039f04ea6d..8307b82d7259 100644 --- a/src/modules/mc_pos_control/multicopter_position_control_limits_params.c +++ b/src/modules/mc_pos_control/multicopter_position_control_limits_params.c @@ -143,6 +143,8 @@ PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.f); * Acceleration to tilt coupling * * Set to decouple tilt from vertical acceleration. + * This provides smoother flight but slightly worse tracking in position and auto modes. + * Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight. * * @boolean * @group Multicopter Position Control From dec550dcb92039d5fc377c989d06a7d3f2bd7f3b Mon Sep 17 00:00:00 2001 From: "murata,katsutoshi" Date: Wed, 14 Aug 2024 16:40:36 +0900 Subject: [PATCH 622/652] navigator: Change IF statement to SWITCH statement (#23534) --- src/modules/navigator/geofence.cpp | 62 +++++++++++++++++++++--------- 1 file changed, 44 insertions(+), 18 deletions(-) diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index 2c317bb79d9b..00a1e3f94011 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -406,17 +406,25 @@ bool Geofence::checkPointAgainstPolygonCircle(const PolygonInfo &polygon, double { bool checksPass = true; - if (polygon.fence_type == NAV_CMD_FENCE_CIRCLE_INCLUSION) { + switch (polygon.fence_type) { + case NAV_CMD_FENCE_CIRCLE_INCLUSION: checksPass &= insideCircle(polygon, lat, lon, altitude); + break; - } else if (polygon.fence_type == NAV_CMD_FENCE_CIRCLE_EXCLUSION) { + case NAV_CMD_FENCE_CIRCLE_EXCLUSION: checksPass &= !insideCircle(polygon, lat, lon, altitude); + break; - } else if (polygon.fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION) { + case NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION: checksPass &= insidePolygon(polygon, lat, lon, altitude); + break; - } else if (polygon.fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION) { + case NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION: checksPass &= !insidePolygon(polygon, lat, lon, altitude); + break; + + default: // unknown fence type + break; } return checksPass; @@ -452,12 +460,18 @@ bool Geofence::insidePolygon(const PolygonInfo &polygon, double lat, double lon, break; } - if (temp_vertex_i.frame != NAV_FRAME_GLOBAL && temp_vertex_i.frame != NAV_FRAME_GLOBAL_INT - && temp_vertex_i.frame != NAV_FRAME_GLOBAL_RELATIVE_ALT - && temp_vertex_i.frame != NAV_FRAME_GLOBAL_RELATIVE_ALT_INT) { + switch (temp_vertex_i.frame) { + case NAV_FRAME_GLOBAL: + case NAV_FRAME_GLOBAL_INT: + case NAV_FRAME_GLOBAL_RELATIVE_ALT: + case NAV_FRAME_GLOBAL_RELATIVE_ALT_INT: + break; + + default: // TODO: handle different frames PX4_ERR("Frame type %i not supported", (int)temp_vertex_i.frame); - break; + return c; + } if (((double)temp_vertex_i.lon >= lon) != ((double)temp_vertex_j.lon >= lon) && @@ -482,12 +496,18 @@ bool Geofence::insideCircle(const PolygonInfo &polygon, double lat, double lon, return false; } - if (circle_point.frame != NAV_FRAME_GLOBAL && circle_point.frame != NAV_FRAME_GLOBAL_INT - && circle_point.frame != NAV_FRAME_GLOBAL_RELATIVE_ALT - && circle_point.frame != NAV_FRAME_GLOBAL_RELATIVE_ALT_INT) { + switch (circle_point.frame) { + case NAV_FRAME_GLOBAL: + case NAV_FRAME_GLOBAL_INT: + case NAV_FRAME_GLOBAL_RELATIVE_ALT: + case NAV_FRAME_GLOBAL_RELATIVE_ALT_INT: + break; + + default: // TODO: handle different frames PX4_ERR("Frame type %i not supported", (int)circle_point.frame); return false; + } if (!_projection_reference.isInitialized()) { @@ -675,20 +695,26 @@ void Geofence::printStatus() for (int i = 0; i < _num_polygons; ++i) { total_num_vertices += _polygons[i].vertex_count; - if (_polygons[i].fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION) { + switch (_polygons[i].fence_type) { + case NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION: ++num_inclusion_polygons; - } + break; - if (_polygons[i].fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION) { + case NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION: ++num_exclusion_polygons; - } + break; - if (_polygons[i].fence_type == NAV_CMD_FENCE_CIRCLE_INCLUSION) { + case NAV_CMD_FENCE_CIRCLE_INCLUSION: ++num_inclusion_circles; - } + break; - if (_polygons[i].fence_type == NAV_CMD_FENCE_CIRCLE_EXCLUSION) { + case NAV_CMD_FENCE_CIRCLE_EXCLUSION: ++num_exclusion_circles; + break; + + default: // unknown fence type + break; + } } From 1fa878ad88d80e084f0b332b76677321376ff0ff Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 9 Aug 2024 11:15:15 +0200 Subject: [PATCH 623/652] navigator: add navigation state ID to every mode class --- src/modules/navigator/land.cpp | 4 ++-- src/modules/navigator/loiter.cpp | 2 +- src/modules/navigator/mission.cpp | 2 +- src/modules/navigator/mission_base.cpp | 6 +++--- src/modules/navigator/mission_base.h | 2 +- src/modules/navigator/mission_block.cpp | 4 ++-- src/modules/navigator/mission_block.h | 2 +- src/modules/navigator/navigator_mode.cpp | 5 +++-- src/modules/navigator/navigator_mode.h | 7 ++++++- src/modules/navigator/precland.cpp | 2 +- src/modules/navigator/rtl.cpp | 2 +- src/modules/navigator/rtl_base.h | 2 +- src/modules/navigator/rtl_direct.cpp | 4 ++-- src/modules/navigator/takeoff.cpp | 4 ++-- src/modules/navigator/vtol_takeoff.cpp | 4 ++-- 15 files changed, 29 insertions(+), 23 deletions(-) diff --git a/src/modules/navigator/land.cpp b/src/modules/navigator/land.cpp index b6a951d1b766..74f54fbb079a 100644 --- a/src/modules/navigator/land.cpp +++ b/src/modules/navigator/land.cpp @@ -42,7 +42,7 @@ #include "navigator.h" Land::Land(Navigator *navigator) : - MissionBlock(navigator) + MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) { } @@ -93,7 +93,7 @@ Land::on_active() if (_navigator->get_land_detected()->landed) { _navigator->get_mission_result()->finished = true; _navigator->set_mission_result_updated(); - _navigator->mode_completed(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND); + _navigator->mode_completed(getNavigatorStateId()); set_idle_item(&_mission_item); struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); diff --git a/src/modules/navigator/loiter.cpp b/src/modules/navigator/loiter.cpp index 15408baaff05..db61030528c1 100644 --- a/src/modules/navigator/loiter.cpp +++ b/src/modules/navigator/loiter.cpp @@ -43,7 +43,7 @@ #include "navigator.h" Loiter::Loiter(Navigator *navigator) : - MissionBlock(navigator), + MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER), ModuleParams(navigator) { } diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 2949c88d62b3..ea7dae675217 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -65,7 +65,7 @@ using namespace time_literals; static constexpr int32_t DEFAULT_MISSION_CACHE_SIZE = 10; Mission::Mission(Navigator *navigator) : - MissionBase(navigator, DEFAULT_MISSION_CACHE_SIZE) + MissionBase(navigator, DEFAULT_MISSION_CACHE_SIZE, vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) { } diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index 6a64f46044e8..8963a0685d08 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -46,8 +46,8 @@ #include "mission_feasibility_checker.h" #include "navigator.h" -MissionBase::MissionBase(Navigator *navigator, int32_t dataman_cache_size_signed) : - MissionBlock(navigator), +MissionBase::MissionBase(Navigator *navigator, int32_t dataman_cache_size_signed, uint8_t navigator_state_id) : + MissionBlock(navigator, navigator_state_id), ModuleParams(navigator), _dataman_cache_size_signed(dataman_cache_size_signed) { @@ -476,7 +476,7 @@ MissionBase::set_mission_items() if (set_end_of_mission) { setEndOfMissionItems(); - _navigator->mode_completed(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION); + _navigator->mode_completed(getNavigatorStateId()); } } diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index 35d4d37030de..f819b5c0e51a 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -65,7 +65,7 @@ class Navigator; class MissionBase : public MissionBlock, public ModuleParams { public: - MissionBase(Navigator *navigator, int32_t dataman_cache_size_signed); + MissionBase(Navigator *navigator, int32_t dataman_cache_size_signed, uint8_t navigator_state_id); ~MissionBase() override = default; virtual void on_inactive() override; diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index 1f0c9f0dd021..f1f202231853 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -55,8 +55,8 @@ using matrix::wrap_pi; -MissionBlock::MissionBlock(Navigator *navigator) : - NavigatorMode(navigator) +MissionBlock::MissionBlock(Navigator *navigator, uint8_t navigator_state_id) : + NavigatorMode(navigator, navigator_state_id) { } diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h index 13815b860211..edc1b0e843f5 100644 --- a/src/modules/navigator/mission_block.h +++ b/src/modules/navigator/mission_block.h @@ -64,7 +64,7 @@ class MissionBlock : public NavigatorMode /** * Constructor */ - MissionBlock(Navigator *navigator); + MissionBlock(Navigator *navigator, uint8_t navigator_state_id); virtual ~MissionBlock() = default; MissionBlock(const MissionBlock &) = delete; diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp index b0ced9006c56..392ca6abb458 100644 --- a/src/modules/navigator/navigator_mode.cpp +++ b/src/modules/navigator/navigator_mode.cpp @@ -42,8 +42,9 @@ #include "navigator_mode.h" #include "navigator.h" -NavigatorMode::NavigatorMode(Navigator *navigator) : - _navigator(navigator) +NavigatorMode::NavigatorMode(Navigator *navigator, uint8_t navigator_state_id) : + _navigator(navigator), + _navigator_state_id(navigator_state_id) { /* set initial mission items */ on_inactivation(); diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h index 60abdcd165e0..ca418e5b2d9a 100644 --- a/src/modules/navigator/navigator_mode.h +++ b/src/modules/navigator/navigator_mode.h @@ -41,12 +41,14 @@ #pragma once +#include + class Navigator; class NavigatorMode { public: - NavigatorMode(Navigator *navigator); + NavigatorMode(Navigator *navigator, uint8_t navigator_state_id); virtual ~NavigatorMode() = default; NavigatorMode(const NavigatorMode &) = delete; NavigatorMode &operator=(const NavigatorMode &) = delete; @@ -56,6 +58,8 @@ class NavigatorMode bool isActive() {return _active;}; + uint8_t getNavigatorStateId() const { return _navigator_state_id; } + /** * This function is called while the mode is inactive */ @@ -81,4 +85,5 @@ class NavigatorMode private: bool _active{false}; + uint8_t _navigator_state_id{0}; }; diff --git a/src/modules/navigator/precland.cpp b/src/modules/navigator/precland.cpp index 080491d37ca7..74c81569cf3d 100644 --- a/src/modules/navigator/precland.cpp +++ b/src/modules/navigator/precland.cpp @@ -62,7 +62,7 @@ static constexpr const char *LOST_TARGET_ERROR_MESSAGE = "Lost landing target while landing"; PrecLand::PrecLand(Navigator *navigator) : - MissionBlock(navigator), + MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND), ModuleParams(navigator) { _handle_param_acceleration_hor = param_find("MPC_ACC_HOR"); diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index 2b6bd55b3f91..6fef45f9df6e 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -55,7 +55,7 @@ static constexpr float MAX_DIST_FROM_HOME_FOR_LAND_APPROACHES{10.0f}; // [m] We static constexpr float MIN_DIST_THRESHOLD = 2.f; RTL::RTL(Navigator *navigator) : - NavigatorMode(navigator), + NavigatorMode(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_RTL), ModuleParams(navigator), _rtl_direct(navigator) { diff --git a/src/modules/navigator/rtl_base.h b/src/modules/navigator/rtl_base.h index dc698687fce6..a4c88e06b026 100644 --- a/src/modules/navigator/rtl_base.h +++ b/src/modules/navigator/rtl_base.h @@ -46,7 +46,7 @@ class RtlBase : public MissionBase { public: RtlBase(Navigator *navigator, int32_t dataman_cache_size_signed): - MissionBase(navigator, dataman_cache_size_signed) {}; + MissionBase(navigator, dataman_cache_size_signed, vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) {}; virtual ~RtlBase() = default; virtual rtl_time_estimate_s calc_rtl_time_estimate() = 0; diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index 62a940f6c0cf..145b99d0d1db 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -51,7 +51,7 @@ using namespace math; RtlDirect::RtlDirect(Navigator *navigator) : - MissionBlock(navigator), + MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_RTL), ModuleParams(navigator) { _destination.lat = static_cast(NAN); @@ -318,7 +318,7 @@ void RtlDirect::set_rtl_item() case RTLState::IDLE: { set_idle_item(&_mission_item); - _navigator->mode_completed(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL); + _navigator->mode_completed(getNavigatorStateId()); break; } diff --git a/src/modules/navigator/takeoff.cpp b/src/modules/navigator/takeoff.cpp index c9e59fec1e20..d9b22720f34a 100644 --- a/src/modules/navigator/takeoff.cpp +++ b/src/modules/navigator/takeoff.cpp @@ -43,7 +43,7 @@ #include Takeoff::Takeoff(Navigator *navigator) : - MissionBlock(navigator) + MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF) { } @@ -68,7 +68,7 @@ Takeoff::on_active() } else if (is_mission_item_reached_or_completed() && !_navigator->get_mission_result()->finished) { _navigator->get_mission_result()->finished = true; _navigator->set_mission_result_updated(); - _navigator->mode_completed(vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF); + _navigator->mode_completed(getNavigatorStateId()); position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); diff --git a/src/modules/navigator/vtol_takeoff.cpp b/src/modules/navigator/vtol_takeoff.cpp index 7b36201856d3..f9a552ef58fc 100644 --- a/src/modules/navigator/vtol_takeoff.cpp +++ b/src/modules/navigator/vtol_takeoff.cpp @@ -43,7 +43,7 @@ using matrix::wrap_pi; VtolTakeoff::VtolTakeoff(Navigator *navigator) : - MissionBlock(navigator), + MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF), ModuleParams(navigator) { } @@ -151,7 +151,7 @@ VtolTakeoff::on_active() // the VTOL takeoff is done _navigator->get_mission_result()->finished = true; _navigator->set_mission_result_updated(); - _navigator->mode_completed(vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF); + _navigator->mode_completed(getNavigatorStateId()); break; } From 9f69e9ee6ca3aaf5091866b202671311885fc10e Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 9 Aug 2024 11:19:08 +0200 Subject: [PATCH 624/652] navigator: publish navigator_state feedback to commander --- msg/CMakeLists.txt | 1 + msg/NavigatorStatus.msg | 6 ++++ src/modules/logger/logged_topics.cpp | 1 + src/modules/navigator/navigator.h | 14 ++++++++- src/modules/navigator/navigator_main.cpp | 37 ++++++++++++++++++++++++ src/modules/navigator/rtl_direct.cpp | 10 +++++++ 6 files changed, 68 insertions(+), 1 deletion(-) create mode 100644 msg/NavigatorStatus.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index f0f6d520c701..3b31b7de554d 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -146,6 +146,7 @@ set(msg_files MountOrientation.msg ModeCompleted.msg NavigatorMissionItem.msg + NavigatorStatus.msg NormalizedUnsignedSetpoint.msg NpfgStatus.msg ObstacleDistance.msg diff --git a/msg/NavigatorStatus.msg b/msg/NavigatorStatus.msg new file mode 100644 index 000000000000..21517d61e7bb --- /dev/null +++ b/msg/NavigatorStatus.msg @@ -0,0 +1,6 @@ +# Current status of a Navigator mode +# The possible values of nav_state are defined in the VehicleStatus msg. +uint64 timestamp # time since system start (microseconds) + +uint8 nav_state # Source mode (values in VehicleStatus) +bool failure # True when the current mode cannot continue diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 24b5004ee9af..5be39234e34f 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -91,6 +91,7 @@ void LoggedTopics::add_default_topics() add_topic("manual_control_switches"); add_topic("mission_result"); add_topic("navigator_mission_item"); + add_topic("navigator_status"); add_topic("npfg_status", 100); add_topic("offboard_control_mode", 100); add_topic("onboard_computer_status", 10); diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 45c4f158b7c4..70068a9c515b 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -69,6 +69,7 @@ #include #include #include +#include #include #include #include @@ -283,8 +284,12 @@ class Navigator : public ModuleBase, public ModuleParams void mode_completed(uint8_t nav_state, uint8_t result = mode_completed_s::RESULT_SUCCESS); + void set_failsafe_status(uint8_t nav_state, bool failsafe); + void sendWarningDescentStoppedDueToTerrain(); + void trigger_failsafe(uint8_t nav_state); + private: int _local_pos_sub{-1}; @@ -305,6 +310,7 @@ class Navigator : public ModuleBase, public ModuleParams uORB::Publication _geofence_result_pub{ORB_ID(geofence_result)}; uORB::Publication _mission_result_pub{ORB_ID(mission_result)}; + uORB::Publication _navigator_status_pub{ORB_ID(navigator_status)}; uORB::Publication _pos_sp_triplet_pub{ORB_ID(position_setpoint_triplet)}; uORB::Publication _vehicle_cmd_ack_pub{ORB_ID(vehicle_command_ack)}; uORB::Publication _vehicle_cmd_pub{ORB_ID(vehicle_command)}; @@ -324,6 +330,7 @@ class Navigator : public ModuleBase, public ModuleParams // Publications geofence_result_s _geofence_result{}; + navigator_status_s _navigator_status{}; position_setpoint_triplet_s _pos_sp_triplet{}; /**< triplet of position setpoints */ position_setpoint_triplet_s _reposition_triplet{}; /**< triplet for non-mission direct position command */ position_setpoint_triplet_s _takeoff_triplet{}; /**< triplet for non-mission direct takeoff command */ @@ -333,7 +340,10 @@ class Navigator : public ModuleBase, public ModuleParams Geofence _geofence; /**< class that handles the geofence */ GeofenceBreachAvoidance _gf_breach_avoidance; - hrt_abstime _last_geofence_check = 0; + hrt_abstime _last_geofence_check{0}; + + bool _navigator_status_updated{false}; + hrt_abstime _last_navigator_status_publication{0}; hrt_abstime _wait_for_vehicle_status_timestamp{0}; /**< If non-zero, wait for vehicle_status update before processing next cmd */ @@ -386,6 +396,8 @@ class Navigator : public ModuleBase, public ModuleParams */ void publish_mission_result(); + void publish_navigator_status(); + void publish_vehicle_command_ack(const vehicle_command_s &cmd, uint8_t result); bool geofence_allows_position(const vehicle_global_position_s &pos); diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index f2694b595ab7..a00ca0e79c49 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -41,6 +41,7 @@ * @author Julian Oes * @author Anton Babushkin * @author Thomas Gubler + * and many more... */ #include "navigator.h" @@ -897,6 +898,8 @@ void Navigator::run() publish_mission_result(); } + publish_navigator_status(); + _geofence.run(); perf_end(_loop_perf); @@ -1355,6 +1358,40 @@ void Navigator::set_mission_failure_heading_timeout() } } +void Navigator::trigger_failsafe(const uint8_t nav_state) +{ + if (!_navigator_status.failure || _navigator_status.nav_state != nav_state) { + _navigator_status.failure = true; + _navigator_status.nav_state = nav_state; + + _navigator_status_updated = true; + } +} + +void Navigator::publish_navigator_status() +{ + uint8_t current_nav_state = _vstatus.nav_state; + + if (_navigation_mode != nullptr) { + current_nav_state = _navigation_mode->getNavigatorStateId(); + } + + if (_navigator_status.nav_state != current_nav_state) { + _navigator_status.nav_state = current_nav_state; + _navigator_status.failure = false; + _navigator_status_updated = true; + } + + if (_navigator_status_updated + || (hrt_elapsed_time(&_last_navigator_status_publication) > 500_ms)) { + _navigator_status.timestamp = hrt_absolute_time(); + _navigator_status_pub.publish(_navigator_status); + + _navigator_status_updated = false; + _last_navigator_status_publication = hrt_absolute_time(); + } +} + void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd) { vcmd->timestamp = hrt_absolute_time(); diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index 145b99d0d1db..216a94c858b4 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -158,6 +158,16 @@ void RtlDirect::set_rtl_item() { position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + if (_global_pos_sub.get().terrain_alt_valid + && ((_rtl_alt - _global_pos_sub.get().terrain_alt) > _navigator->get_local_position()->hagl_max)) { + // Handle case where the RTL altidude is above the maximum HAGL and land in place instead of RTL + mavlink_log_info(_navigator->get_mavlink_log_pub(), "RTL: return alt higher than max HAGL, landing\t"); + events::send(events::ID("rtl_fail_max_hagl"), events::Log::Warning, "RTL: return alt higher than max HAGL, landing"); + + _navigator->trigger_failsafe(getNavigatorStateId()); + _rtl_state = RTLState::IDLE; + } + const float destination_dist = get_distance_to_next_waypoint(_destination.lat, _destination.lon, _global_pos_sub.get().lat, _global_pos_sub.get().lon); const float loiter_altitude = math::min(_land_approach.height_m, _rtl_alt); From 25fcb3c91338d62c3c2cfeae2851c9f768c98ff2 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 9 Aug 2024 14:12:23 +0200 Subject: [PATCH 625/652] comander: trigger failsafe when navigator reports failure --- msg/FailsafeFlags.msg | 1 + .../HealthAndArmingChecks/CMakeLists.txt | 1 + .../HealthAndArmingChecks.hpp | 3 ++ .../checks/navigatorCheck.cpp | 47 +++++++++++++++++ .../checks/navigatorCheck.hpp | 51 +++++++++++++++++++ src/modules/commander/failsafe/failsafe.cpp | 10 ++++ src/modules/navigator/rtl_direct.cpp | 4 +- 7 files changed, 115 insertions(+), 2 deletions(-) create mode 100644 src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp create mode 100644 src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.hpp diff --git a/msg/FailsafeFlags.msg b/msg/FailsafeFlags.msg index 2cd31bf83598..de514fb2db4b 100644 --- a/msg/FailsafeFlags.msg +++ b/msg/FailsafeFlags.msg @@ -49,6 +49,7 @@ bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure fai bool wind_limit_exceeded # Wind limit exceeded bool flight_time_limit_exceeded # Maximum flight time exceeded bool local_position_accuracy_low # Local position estimate has dropped below threshold, but is currently still declared valid +bool navigator_failure # Navigator failed to execute a mode # Failure detector bool fd_critical_failure # Critical failure (attitude/altitude limit exceeded, or external ATS) diff --git a/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt b/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt index 7c78c47c8534..7265e042b4c0 100644 --- a/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt +++ b/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt @@ -55,6 +55,7 @@ px4_add_library(health_and_arming_checks checks/manualControlCheck.cpp checks/missionCheck.cpp checks/modeCheck.cpp + checks/navigatorCheck.cpp checks/offboardCheck.cpp checks/openDroneIDCheck.cpp checks/parachuteCheck.cpp diff --git a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp index af0fd9aec5f0..fdf38f5d5d77 100644 --- a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp +++ b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp @@ -49,6 +49,7 @@ #include "checks/escCheck.hpp" #include "checks/estimatorCheck.hpp" #include "checks/failureDetectorCheck.hpp" +#include "checks/navigatorCheck.hpp" #include "checks/gyroCheck.hpp" #include "checks/imuConsistencyCheck.hpp" #include "checks/loggerCheck.hpp" @@ -129,6 +130,7 @@ class HealthAndArmingChecks : public ModuleParams EscChecks _esc_checks; EstimatorChecks _estimator_checks; FailureDetectorChecks _failure_detector_checks; + NavigatorChecks _navigator_checks; GyroChecks _gyro_checks; ImuConsistencyChecks _imu_consistency_checks; LoggerChecks _logger_checks; @@ -167,6 +169,7 @@ class HealthAndArmingChecks : public ModuleParams &_esc_checks, &_estimator_checks, &_failure_detector_checks, + &_navigator_checks, &_gyro_checks, &_imu_consistency_checks, &_logger_checks, diff --git a/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp new file mode 100644 index 000000000000..8c7d0e314af4 --- /dev/null +++ b/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp @@ -0,0 +1,47 @@ +/**************************************************************************** + * + * 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 "navigatorCheck.hpp" + +void NavigatorChecks::checkAndReport(const Context &context, Report &reporter) +{ + navigator_status_s status; + + if (!_navigator_status_sub.copy(&status)) { + status = {}; + } + + if (context.status().nav_state == status.nav_state) { + reporter.failsafeFlags().navigator_failure = status.failure; + } +} diff --git a/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.hpp new file mode 100644 index 000000000000..48c6965deaf8 --- /dev/null +++ b/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.hpp @@ -0,0 +1,51 @@ +/**************************************************************************** + * + * 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 "../Common.hpp" +#include +#include + + +class NavigatorChecks : public HealthAndArmingCheckBase +{ +public: + NavigatorChecks() = default; + ~NavigatorChecks() = default; + + void checkAndReport(const Context &context, Report &reporter) override; + +private: + uORB::Subscription _navigator_status_sub{ORB_ID(navigator_status)}; +}; diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index fef6e2136bf3..11285af40352 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -472,6 +472,16 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state, CHECK_FAILSAFE(status_flags, local_position_accuracy_low, ActionOptions(Action::RTL)); } + if (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF || + state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { + CHECK_FAILSAFE(status_flags, navigator_failure, + ActionOptions(Action::Land).clearOn(ClearCondition::OnModeChangeOrDisarm)); + + } else { + CHECK_FAILSAFE(status_flags, navigator_failure, + ActionOptions(Action::Hold).clearOn(ClearCondition::OnModeChangeOrDisarm)); + } + CHECK_FAILSAFE(status_flags, geofence_breached, fromGfActParam(_param_gf_action.get()).cannotBeDeferred()); // Battery flight time remaining failsafe diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index 216a94c858b4..9be8ce24a937 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -161,8 +161,8 @@ void RtlDirect::set_rtl_item() if (_global_pos_sub.get().terrain_alt_valid && ((_rtl_alt - _global_pos_sub.get().terrain_alt) > _navigator->get_local_position()->hagl_max)) { // Handle case where the RTL altidude is above the maximum HAGL and land in place instead of RTL - mavlink_log_info(_navigator->get_mavlink_log_pub(), "RTL: return alt higher than max HAGL, landing\t"); - events::send(events::ID("rtl_fail_max_hagl"), events::Log::Warning, "RTL: return alt higher than max HAGL, landing"); + mavlink_log_info(_navigator->get_mavlink_log_pub(), "RTL: return alt higher than max HAGL\t"); + events::send(events::ID("rtl_fail_max_hagl"), events::Log::Error, "RTL: return alt higher than max HAGL"); _navigator->trigger_failsafe(getNavigatorStateId()); _rtl_state = RTLState::IDLE; From 4ed3e9e2103e75c1e9d52fe240d4f0c2cf6266c8 Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 13 Aug 2024 17:57:29 +0200 Subject: [PATCH 626/652] navigator: add failure enum --- msg/NavigatorStatus.msg | 5 ++++- .../HealthAndArmingChecks/checks/navigatorCheck.cpp | 13 ++++++++++++- src/modules/navigator/navigator.h | 2 +- src/modules/navigator/navigator_main.cpp | 8 ++++---- src/modules/navigator/rtl_direct.cpp | 2 +- 5 files changed, 22 insertions(+), 8 deletions(-) diff --git a/msg/NavigatorStatus.msg b/msg/NavigatorStatus.msg index 21517d61e7bb..da666533574f 100644 --- a/msg/NavigatorStatus.msg +++ b/msg/NavigatorStatus.msg @@ -3,4 +3,7 @@ uint64 timestamp # time since system start (microseconds) uint8 nav_state # Source mode (values in VehicleStatus) -bool failure # True when the current mode cannot continue +uint8 failure # Navigator failure enum + +uint8 FAILURE_NONE = 0 +uint8 FAILURE_HAGL = 1 # Target altitude exceeds maximum height above ground diff --git a/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp index 8c7d0e314af4..2a0245bb1fbd 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/navigatorCheck.cpp @@ -42,6 +42,17 @@ void NavigatorChecks::checkAndReport(const Context &context, Report &reporter) } if (context.status().nav_state == status.nav_state) { - reporter.failsafeFlags().navigator_failure = status.failure; + + reporter.failsafeFlags().navigator_failure = (status.failure != navigator_status_s::FAILURE_NONE); + + if (status.failure == navigator_status_s::FAILURE_HAGL) { + /* EVENT + */ + reporter.armingCheckFailure(NavModes::All, + health_component_t::system, + events::ID("check_navigator_failure_hagl"), + events::Log::Error, + "Waypoint above maximum height"); + } } } diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 70068a9c515b..ec72881fc527 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -288,7 +288,7 @@ class Navigator : public ModuleBase, public ModuleParams void sendWarningDescentStoppedDueToTerrain(); - void trigger_failsafe(uint8_t nav_state); + void trigger_hagl_failsafe(uint8_t nav_state); private: diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index a00ca0e79c49..15db1abdc44d 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1358,10 +1358,10 @@ void Navigator::set_mission_failure_heading_timeout() } } -void Navigator::trigger_failsafe(const uint8_t nav_state) +void Navigator::trigger_hagl_failsafe(const uint8_t nav_state) { - if (!_navigator_status.failure || _navigator_status.nav_state != nav_state) { - _navigator_status.failure = true; + if ((_navigator_status.failure != navigator_status_s::FAILURE_HAGL) || _navigator_status.nav_state != nav_state) { + _navigator_status.failure = navigator_status_s::FAILURE_HAGL; _navigator_status.nav_state = nav_state; _navigator_status_updated = true; @@ -1378,7 +1378,7 @@ void Navigator::publish_navigator_status() if (_navigator_status.nav_state != current_nav_state) { _navigator_status.nav_state = current_nav_state; - _navigator_status.failure = false; + _navigator_status.failure = navigator_status_s::FAILURE_NONE; _navigator_status_updated = true; } diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index 9be8ce24a937..f26df56530d2 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -164,7 +164,7 @@ void RtlDirect::set_rtl_item() mavlink_log_info(_navigator->get_mavlink_log_pub(), "RTL: return alt higher than max HAGL\t"); events::send(events::ID("rtl_fail_max_hagl"), events::Log::Error, "RTL: return alt higher than max HAGL"); - _navigator->trigger_failsafe(getNavigatorStateId()); + _navigator->trigger_hagl_failsafe(getNavigatorStateId()); _rtl_state = RTLState::IDLE; } From c8501cc1d02021e85fcc020bab3287d9e0ae08e8 Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Wed, 14 Aug 2024 17:52:42 -0600 Subject: [PATCH 627/652] boards: Support for 3DR Control Zero H7 OEM Rev G board --- .ci/Jenkinsfile-compile | 1 + .github/workflows/compile_nuttx.yml | 1 + .vscode/cmake-variants.yaml | 5 + Makefile | 1 + .../ctrl-zero-h7-oem-revg/bootloader.px4board | 3 + .../ctrl-zero-h7-oem-revg/default.px4board | 96 ++++++ .../3dr_ctrl-zero-h7-oem-revg_bootloader.bin | Bin 0 -> 42864 bytes .../ctrl-zero-h7-oem-revg/firmware.prototype | 13 + .../init/rc.board_defaults | 9 + .../init/rc.board_sensors | 19 ++ .../nuttx-config/bootloader/defconfig | 91 ++++++ .../nuttx-config/include/board.h | 288 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 44 +++ .../nuttx-config/nsh/defconfig | 260 ++++++++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 221 ++++++++++++++ .../nuttx-config/scripts/script.ld | 228 ++++++++++++++ .../ctrl-zero-h7-oem-revg/src/CMakeLists.txt | 65 ++++ .../ctrl-zero-h7-oem-revg/src/board_config.h | 187 ++++++++++++ .../src/bootloader_main.c | 75 +++++ .../3dr/ctrl-zero-h7-oem-revg/src/hw_config.h | 135 ++++++++ boards/3dr/ctrl-zero-h7-oem-revg/src/i2c.cpp | 40 +++ boards/3dr/ctrl-zero-h7-oem-revg/src/init.c | 204 +++++++++++++ boards/3dr/ctrl-zero-h7-oem-revg/src/led.c | 111 +++++++ boards/3dr/ctrl-zero-h7-oem-revg/src/spi.cpp | 53 ++++ .../src/timer_config.cpp | 54 ++++ boards/3dr/ctrl-zero-h7-oem-revg/src/usb.c | 82 +++++ 26 files changed, 2286 insertions(+) create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/bootloader.px4board create mode 100644 boards/3dr/ctrl-zero-h7-oem-revg/default.px4board create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/extras/3dr_ctrl-zero-h7-oem-revg_bootloader.bin create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/firmware.prototype create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/init/rc.board_defaults create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/init/rc.board_sensors create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/bootloader/defconfig create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/include/board.h create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/include/board_dma_map.h create mode 100644 boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/nsh/defconfig create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/bootloader_script.ld create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/script.ld create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/CMakeLists.txt create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/board_config.h create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/bootloader_main.c create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/hw_config.h create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/i2c.cpp create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/init.c create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/led.c create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/spi.cpp create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/timer_config.cpp create mode 100755 boards/3dr/ctrl-zero-h7-oem-revg/src/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index c482b14d459d..fcf70a5a2fdc 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -35,6 +35,7 @@ pipeline { def nuttx_builds_archive = [ target: [ + "3dr_ctrl-zero-h7-oem-revg_default", "airmind_mindpx-v2_default", "ark_can-flow_canbootloader", "ark_can-flow_default", diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml index 5468e51d2049..cc44c55ea252 100644 --- a/.github/workflows/compile_nuttx.yml +++ b/.github/workflows/compile_nuttx.yml @@ -19,6 +19,7 @@ jobs: fail-fast: false matrix: config: [ + 3dr_ctrl-zero-h7-oem-revg, airmind_mindpx-v2, ark_can-flow, ark_can-gps, diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 1311079ff988..d55b170485e2 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -111,6 +111,11 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: px4_fmu-v6xrt_bootloader + 3dr_ctrl-zero-h7-oem-revg_default: + short: 3dr_ctrl-zero-h7-oem-revg + buildType: MinSizeRel + settings: + CONFIG: 3dr_ctrl-zero-h7-oem-revg_default airmind_mindpx-v2_default: short: airmind_mindpx-v2 buildType: MinSizeRel diff --git a/Makefile b/Makefile index 7d4283a95690..37c61db1c0b3 100644 --- a/Makefile +++ b/Makefile @@ -324,6 +324,7 @@ px4io_update: git status bootloaders_update: \ + 3dr_ctrl-zero-h7-oem-revg_bootloader \ ark_fmu-v6x_bootloader \ ark_pi6x_bootloader \ cuav_nora_bootloader \ diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/bootloader.px4board b/boards/3dr/ctrl-zero-h7-oem-revg/bootloader.px4board new file mode 100755 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board new file mode 100644 index 000000000000..549ba99b7331 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board @@ -0,0 +1,96 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_PCA9685_PWM_OUT=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +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 +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_REFLECT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/extras/3dr_ctrl-zero-h7-oem-revg_bootloader.bin b/boards/3dr/ctrl-zero-h7-oem-revg/extras/3dr_ctrl-zero-h7-oem-revg_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..86dc50de7b9c4140d7356a8214ecd9a4b48857a7 GIT binary patch literal 42864 zcmeFZd3;k<{y%)~lH|52O}YT-0%T$72Bs}&1sy|DZkK>%aU2#$14X^H3RTdl%9NC% zBB%qDae(S~kUEN@LJFP7!qis58J*GjCM-^&FjheVEy@jT$?clweG+hH)OlXN=fCHV zC$HDZz4zR6&+<8+^V!eo98Jbg;E3=R`~Ro^9|r&5!2xpp7rOk>)?fZw_3@Q%m3yqr z>sarV?x^Y)#fL;TAhB1v<7y^!Y_^j3JCQ0XJ^T1r=eXi=MVst59Vc>1-<9sf8i&ktHQk9DQi>C#-MwEtW|3`< zkCb<^6C_7Z1()C=@-O>Zx=Vi3(!KIG2`FQc8RRYqUl+J;ydknUNaW~#BF`OkD16E% z{`m^8#hvyO|6n2+-$BTDfMopUH;6#*r(Pi)n~@ed*X>W1%spX2=m_QrjWyHx9<{i{G38_Lvv ze_!izIP;6sX6#(%C{8YQ6z?o$dr406a(nUVWyz9V-ZMYhl`LUnSdi+ntICqf2 zlQVF2$ZFJes}tpVZ1!+De(>bYMbXk`T&Lk`msvL2H8p(4;0`t6O}5i)PIg)Gomtkf zc9~=8x2&AU8Z!EQnT1)!9L8W<;OHR>INI+X+bZ0zN^nhdCP}8Aj+rxi-1CxL;d>MA zvy)tLl1WCs?4B3r0ygy6;%4@cIELo;*s|kLzgf0nEbRV@f@En6cSr9p_c1$}>38`_ zKD$u4X$vvnnu?T$WVYEz3Cn55u?(|8Xdy9$>_P()kJN+rSv*-tjAXtZ_je&JM4F2P zd~z}-Vx*8`FsjtzI3zt%k`!%AEwamc{_4*Sq`MQ;&^AAq;({?;==ihrNyqD(oVeR@t)5*EuD4=&7_5nMW`n8Xulr3GTcc> zh{?iz8`2r14x|u6^cQihCh9ZPb_Zpm2Q2_V}D$Sl~L2J-#~G9q;phpiWIkj z>v2C`>0z?t-0>S8_Z;#N3w?XOVLi(3_3%dPpRf+zFY++Ae(NV0SG z9h1w{_WC2a%-Q96-(1hT7S21+yJ9WV9-VjgKT6)4$(&{KzWBc6yQ>&-gGQ*G1SDopcHEIA zw586r=B4Jxg!754cU|@0m&LakX3q`hcKg@jY2@sR@Y7}gZ?o7_C348BZ;qS2Ih^;k zU+?78v@Xt9(&I*7j`>w-Ebd9J;#Y_7+?H;?F72F8S6ZCJBeZV)`Il9O&JIPfdV-+toxppjFz>F-8 zjBdHZ4tiOOQgMJ!T#?q8j2VBepO|$;oRP?{^jkp3);b(=hr{BMEp$eg{ZS7b;L*05 z_6hv}Z52}K^*rgIxbfR4B0P$e(CD@>ZI~AWrRMEP` zq_LJX(z36cxJe^(kjT8k{E0M2p7{({JCV8ArQJ2LPdSfYjFoBrjTEOaGYHb|0K@*b z`^lH&acLQvcF#p++%BZufiyNPBY65t<(02WI=5>7c~L9RQ}`J+q>13R2C@sugu6W4 z<&jj}RpPFajK-aUJB7s4I|g^m2ztlijuYse26r0DvlSigbj=s#aV&TP$p8UvzR^Qw z`hS0ljQju1_|h__wbL=8&2dJBol(-6;8@;0&Qa2tn16rwxcrjNk+UA?9yhC`bCmdC z_c*bnb98~!J+7dn(@_!k<9{PF;$`Ai`rzjlbUM8&X#7(ro7g2>2)hj{r!^MX4W3mLy) zPHsg>&%wv$J5{}}SJpJnD=~>_;%%-qu2k1Ot~;Io`kxcNkNk7;{|s{$gSoiKChmQr z*!fQN$CvnAwPkM&Cx1O$;Jg)eJfpZ~eyl9dK5~hy=j7Xm>`vw_NgU&1Ei-55Rxt9k zeyl+TZ~A$Q#buG0%(-WcQY+!)VyyaGoh8>oYetI(mr+WRHrr>NF-v6p2v>?UvG5gl z`dV;4HQExN+o3L?)RP|4GWiF`;=;cFt#R*3wO!pQ!?LBB;> zLf-VxRB|ekB&O>lhRJzN;alGUU6gn-Ud9@J7}rXq7m&6gtw&mj^bTmkv=|~>L>V`p zmm{r4av_-#iBM)F!r>YsoJ^(k3bY`Y7E(D&dh(VnH<4{T#`O=yC{lVwT0Y%D1O@fc zaI8$pC2l=(wiMWafL5tG|Mvz`Ub`T-YCZ3+cf4w*&GY@zU4gH4%c zBV8X8yX#p{Sl~?aN_iw1!1&&ZCBiG{>mSmD#+bIK;`xfzy2QhFwX*Z2?FDMcDo9i^ zF{_-{{K+EyhL)$WpyQ?A|2Mjs3%VH!zA`MlMg)~p-rb?gT-Nb?YO&HHJKc>M4`^H*HX4DyCIad?qOpz8eecM1~0%FW-W@gkiptj6j z-xWV2#|#9}M_MnPvx>%N_wypwLPf0j`6WJwlSlQb#7{giJD#m!w`g}TTcUTIMLyYL zf($ZM;m4{@r-_{01&FKnS2U-IjeRjTBG>m_^RJY(e7ApGqxu!HH5#=sQ;8)Byyx=} zkNF$dsCk9mrhet~OJr(-7%j4%fL4+Ml$J95Fgz zU}#<+zP@sLZ#j1$J6yiLKc!=@R3z$)=^9ECwRPlWB9FxwN3_T6oQX0-{+mMoclYt4 z&7&!zBfocm+;qlEbAR7QF%wkpInvS>PXvnZptU8>0HPRuJXd=i_kJLIeyQYbL8|_% z*aW^vjBN_p&*T)8#5de7?Xiz&&yy&Huq*Z=l}OU&_^vfjti))Dt%J$9U3$NTF*CQ1 zw3T#z9HZ^}IChCLZ7!KS&G&bO*se98HtXA{_m%v26yCVIntsdHamH7bJfmePS4TO{ zs|v3#U0T1%^n^t|!YzFwT}*KBfqb^U25TOp`oj~9+}alk9vn6o88PNlpjP!ygo1~L z(?k^=@o$(M#v0%7hJU(50(=apR@Hnm-9^l!ML}9;*R?Mai7~!px+G+?UB@2V-?dDq zZC@y|^8bcDQOMkN{#l?USxQa^lXC%eFxKoo{xfF!JVm%Irjun=T_44u1kKH&qd4uS zbc4c|(hW*KraC8I3YL)c#Fh=>c2Oge@gv2VqQOjhU$5ZgltG*L94Ij-#}10Avkqs8 z?9@C_-L;-!s_73o(Cx52MOr49T3j=rM zpPH5IBgSHdkNJzTd?^o)z$|l-1;t z->L8=KUes1;6Gb9`I7;+$m}qRLVyuCxoIFj--k7`n4F|5haB@8K?n3V>TRt2?FY0EDo~AQD_D7Wm>2UrQ;n?LH@wT0)?~zr?+DQmsX7=lF>&%xA2Gh; z%4^==7h|lEpgX!5^WsM<3i2A)ODb`yr}RlClRw4GD1DSz_M#je+5LTdz(~~c#eRx^ z!=N^yU}NYzKkXNKWmU`nz#G~hBLDI5zj8nOK6me7Vo?{X3zI}9_l?Ytz;)Sxz$(5_ zZ~|llN~0-lu0VZr51?nH!-LgI^|c>pR5~Y_m?AMVINOLql{8DqbrFel9pQlU72B_C zZ}sH~9tyjs!u_lbfiB34hbbSq!SAddZbJ&soPaLlrZNfTFBJv)#!&ETh|<*Mc21TQ z9$G?Zs!`N8D~+SYB&Ql2Y>X5N%7Z#j`NK0@CukpQh&jy7);;z|s#C6mHp@*^OGCx zY9AL!WUNgBX8up|CtN@jwT?zAmL#qArT#6!x%&P}oyzNNHJu$MEC^yWl(4 zKrJM>o($Mu9)kU)!=EC_7{{ey#dB97EANATxB%C^A(D2?n<+V5er|xIIlZgUeuK2m)h*Sj`4j1tjAfH8!BOMNl#ZZZ+|r+Jkq^vfXq)NRp%V(; zIe?NIehlMea6iz$;rc2y=;;rkYYE-gzd_kRzr0ECGN-Yg)K<_Wxf;|@ecWGPrOM=d zyouJ)+gD$u$-LsrtQ0aY`)JOGeHXDNZs1(NKm<)AvxUeH_oaE59o+t3DtuQc*!#gs zh}Yq#0V-SY;xqeUNr(alMw7r@0{UIU{2sIU++%-y9zA&uv$=Z{^Sdt_;(N$ry!Sce zML0IN*;er1VQ!}yQpHv8Yn!;OupmDATFp#QtNP&+O8)*v$=Rt=-M^fEwMtS4Vi<0x z_37;ev=w$Im1pRRrR{{N&eoaY?oC$FjFxuSEPMFpwsoCacBJi@PA%%doDOq!5gHT< z{_l_#WB#K54cHMPvTi8&3}`ixQ~T%&3o#df?rO7Gh+Kkhv{FalDeNuLi|nL6H|$wmM)z2VG@ywV45Myo!P>@YKALt_Cq}rYoF0Bfrl6#~-g=xr-XP&-24;=Z+Ftq}b@d+KY&VTy+6pMcX*ID@w!~ddA zq=mMN`Eoo9{Y^ioL}sH>Z{CHuvjWy{50^`;JU3M`ZxQq7O3dawDlO(gFO@6%ZWU>X zwZqI*VVX9p6LLp*_G)N-`o@|~yqKaId188#TT1gdz&BZ68lbWpyqU<_F!#9&v^o@g zXQ+M?EN!LrHG0rWP%PPqw-J8%^7|M=^^eC~v+2`@1es^mUWcsbYHBEVp)jOZy;xB& z-b!T4Ax$F-4$J_TMh?Mlw39IzAdmO?9us3v>z`i%8 z9c@zz^aFh?+Nmu{k)pzUmgzdeAME38>+LZu^Dtw?7_pH;2Q&_1&D`Lrl&=2tY}8co zGq_AxJLLpOt{SXB%X$L&KQcpk%^DMt-yaAt$V)DkI9LdN^YPlM~;N;U;EgJqs!w8jQ4+ z2V1QI-8Rjcey7U_3qpRHlm1V-{{Ls((`Qzm+OHA|JtW}LWIdiH8m46fXFeL-XAk;X zK|Lq*Q`wCKT2<_%(RWUI+$b8R(h{D*KcIvSB@(Zfu&Kx-{hgCmLE;FP*cC3}MhRG4 z!*#e(hwyJDeiJUCG=By@c>?JS(hV9`(Kr`hUVyGd`!-j_-)R&R!}YEne8;Z%D!^mu zcT5p0m;WhpKlzg47%ARTJPw@hm_ppKVw)mt=1x)hsQIE&GqdSdu@Kn%YseS(H;p<> zjNN{c+2hl~auV={fC&>zpxve2G|C$dVWQS)NiU(^W5(yUt11 z{K(IL$JOqiCNY!ad>POi=~q{VRN^yDB+KhHicz3>tUNKihW3X3;)hKpT;}Z1xBeHJ zV!`>Q4DzBCGSP-mG@d5mX`zRHWfUi^X64Yp{jOC~z3YH<&b22j*Vlz*Z8~mZxutQP z#89p9nIGc+U1eF(}T3n@5j6ogL_C(iKMJntvSrX$)5vQtI}}0HtneO$N+cbf4e> z$9-Jid}CfAWBvNS$yltsap1-Z`9GDheD9N%8+HHpwJUoZ(m9XbNsK8{yQki+^I4=6 z&razzDLQ|rYoR9^*z?2yF}hqgRB6K zww~)c%B4KnuHjA+d5rST6M4<7ymX-7|32(RD(AW?ed7WpN6%xWJUjsT=?Q9cqVHJP z=CSU~)K@|4)HiA+w(5WmY&*9!#?Q%u%_j~$e-9Q+I`2B%?-_tTmry2_T#KoA7ux)b3TtD2 z%gNVbI}qnO63{Q;dWl8r zqW#~D@w9ex2|{Lcn;Ohe%F1V*M{p}T-`U>sz{ z-JRG|QF64KyDiac)Rf3N!P)XgK;Ux4@kXPuj?7h59YQ~+#PoCBQ#yrMM`tYOm{-y% z3Y;ZP;?lW(q1)KWk(HfXEQ5PTC*d+(E4_S=Ef@W`<6$p)cSlSM3mZ$9MEV6ewv*!w zj*G581&B`Xv(Pr9e$-}b6xz!|Nyogxu}qq?4fU0xrj>=L&$hC_Ti@$`_)LIsj;RgM9+b=h#ORKZP))(mf?>GI+hDm)$)po(l=P`j39J~jao9yt{+|=iz zym*9IQ_hQVqGs9zS)rzMvO-V095q{Lv``K9C;VV)d3m2vS`8^_c^@4wF>8y2MlI~a zZcB7AGlTm227FPly;Bd43VfQ#n+7Pf82JeJ;gt{G{U;quM4TOs8l`bmQLNAtRvlFa ztt;hGcz(r7EJrWR&6O?n59T#fI>1s%JI~NUWjxw$MWYtA zi<5d!SAB>)S{ktgEnY=2&U|3q1M60P^nh0xG_ns0#jVJ5o7X*vvX8YQkCvr)eWRb# zCK6#J>>R1m|FxfyJt38ZF*3{^*sF$b_*P3-7{!Rb^JDp#k$)Fbx$0Lid(5@xR10jhI@VE`V~x1+p1m4Ts(3N zEwDU&`Y9$Gx~Hv3Frv)P6?)gs6+Tz3a<|@6%%roOgw6HYds>&(D!(96X{=XBv-+Mq zfLNpXsMoc9MXj>XHIqiq%!~Cv6P`CSoVUnTP4gZd>$!I&&38Xq?aFY}tvKJ1?4r_= z-27p;oi)ii#)h_|_^6mTN2{Mr7g|vBvQPX6(7va)VT$?M<~*qRq7ZFe-)!mG{HO^q@9`fg zuUpYp*4k~;V@`3uV_D=%^IDNdWvp=BKcTPEx)*sIohdu5D$;q#VZb(!X+0D?A zg@R*Ym!dYiUzSmsWQYB7xytM5tzMh%T`3y~FgRnjcbjszb-=@9BAVjSn3fX6F+tjJ zY*QBM^&+*<+f2knpBL%r6L{E6`s|RcT&?S?M_Bn6z{^wqB=NjI=RmE*$yUaiZt{^# z=Je8)mplomb+k93hpbI(VIbA7M{Bi`UOdw6PFSxj#C^MNy|M^e@B*dd{xooue++-& zM=5<*m><3aE$?XgHpNATf=`5qncl^PHDSopO?izUm#d31#NQ%!ICvhqi=m0$4+U3; zrR(Q2sNQ{~JW;Gg8=0P(^13p!hnTh(SVRNtw2Y|_^(Ts3R~#>^YuK)SU72r9IC&83 z;(4|1B!y~P=pgcv)oPk+O;NMqTtBSC`sM^VR(Hi4Ye`sk8FU~I{Uj!pSid64Me${< zbEloBF)HRUg+oF0aK{R)>jC4+P%vk}wNe0Oo-(j|1%>khL=^pcL6ip?|AGbZWbIxN zN29512`>8n=X$J3M9k53>FAtUTI&i0XASROL5wuQjVy4;BM^_pSYB7=lJ&}6R?I45 zk%*1PP;noGa-ow>JX)?2@s3*ho^zXXp?Cj#G*z}pZ4Ny{p$2L>>O$W~pzkVQ4txY| zlNP;yb7=Pp#JPoAqT|>X9>+Tvhrt6W2lk&g4lDoG?%GCekpzqS#1OGW%}EvEMM=5U zb8o6OR}x=TqF^0eH<$|_jgS@a@$f@dKz3P!M6n)}sth(%kF$(h$~8Hb5{q+bX_c|+ zNO!Bs*wi7BHLmU>T)&1e;JV@kNF;cYX_Hfccpfr+owG+bFUsUcpV-Ukoso7jVe|aHoz539pOLl>|3_P-im|AQ zYiz_AiL>iyCQ-Eh+(BBu^U3HZKdrQPa%M*r%v?UaLsbyvrTlF_}NvA!2 zc8lPQaz3v~$fwbLB)%|AEr9kzO!sI*G$ONhRs7)rmU7H(%%6y~2K81ku&_`@|?$C1@HtV&c4 zYV95omVpJpf?Kn+dnU)NrlUb^uA>Y zjqx(W=ejWM%GB%nIh8p`3xz9%i`uCvMvQ8}Wk04|oX%dmXhsY&qCTmdrU%Zz4DON} zRaM54N0_cfoJ<@fBiH-q4R?*5ntyQMT8~(j;Go`rN9R!oGsSSH(BkOKU)42lRux~R zk~!6KhM8QyNaKs2Gg1u|*UzKtE`{R)$m?Y+>+DRIn`h6+ z&CK|}`^Uo@o$BhrJnHHCK%#wD8e_{e@W$QSq^-KCXbH1;pSwuGFm!4PEs*;q=I2#-f)t**HMzQ~wz8TYv8J8Dci* zS5kf`_+W^B$)gvRDofMTYgFcC-I|1_SLZz6y?x@ z1JYEC%i73^+S$otQj&Mr$r)?2MLN>0nZPRiZLGrGgZo)XrL4le30QmhUJtmW zt=q3Y3#(@lpBpW0w=-M&&(Jth`YsZAV=i0VWT{FnT*4$RoGFu~Nr2U|Fsv$?eH)U( ze&Y0@F8{d=@pmpB8<%gc@(gqb<}*&m=0%Rq4;?W@@S$PEweu`h5qR@<3hx^uC7Gvv zztj(C!Gfv;#F3BjC6+mt-qu8)c=bn@__!$8 z|G191Wiyu=#Cc02vQPzhw4RR>IcjShwu;^GNBt($3CTi7;NNQ@mj3IEfADA?R-mx5v5uOvg^w z1`_2T6!roVF;i_YPIOsA!Ia_BHGFt}N>@jGJmdrVHWYjSJ%~0&7ttPIg*qHPBw@ka zq2Swn>f*3e5^j~wwE(Q9b~su;g{i%Y6OXBx6QSVg7Pd-VIG>4INaNt+<`U!LD!VMO zi=UwIr+xcxRFLYlzrAjA2aOA!3@MP<0(jxa%WT7Dgkm8H`E~+AU&AGcEpDbTPBx$sT_5aiLf6;m&mD6 z=T=)Dj~Y<-=81@d*+pj!*WJv`pI7FVX;VwPvK ziz`CGfx+@8HB&6|Y_9y#(}*pm9%o`oEKG)m%)~EtX)V~N;ew^%w)slpZI+(lQai3T zvt?ss4+YOz*0C1LW1-*|12#~40TF1g!UiE1go4?CGlel7+j%4d?h}#r#KJEJc+!|G z(!2F>UR)`Qh^Rt*&>$ah5&FbzroOsu%I(UKx`-EA=?7WI+d3Xj11$hZ6Lp+zG|D2+ObU;-8!jiY1P+NvpY4DW_EI>ZOW+4 z_Rd(duKzhj+o0=TH{2A6(WSNNuJX}~m2`RL&9HgiLWE!7T6X=a%_G8`>*?pXu0r~B zS|r_va@!PrYby55sJv_j=Nl!vb;LXFzzrGCvZh@#>f|=1(wZi2jZl0@Jd5Yj@ld>^ zGXf-r!wxqL$o898drBaS1e+iXaxzb<3BK<2!qTu=~2miIM zLczNS-||2Bt2cio`;BY#7|s89NyaNa+B!RBl#krBwx?uYq>VeS74M_1Y$sYZ>bGJp zD~#YDI@pjyLG$o4ellfkPu@NT-%Q)biOahA1k36h_1@9**glf6wrAzONZs+M`)9sL z&C|oZkA;j_L;k(yv|*qBfy2yAoX;lfiE;H`{p?NSeQ|O~XYxfw*RNr2<a{(V zeG6cDUE4Em-`bn*xR$!FbPbKiXEX2U8MV&>d5x|GSYi_rTt=sPV}gy^fEn!NShvcu zuFBty8rXeJ7ffqPQ0LHlGM@Y2TL>%g+Ma9gF&KCEdv9MbubGFp-@QlM>v}KJp8vfY z_}kG(($@Bzd(XVlfDsB#4wN~u#nHoJZ;uQ9QpS0<7ZB4U@Gu}u}#CA)Jt)$ zC4w<$v7b!*QfYO6skH3^t=@k{bIVEi7?Kt#Ld9u#U&h%KP0C5eGD;4SB1N#)DRI_J z;JwVbGIhR5pr2n2)}b9p5sU`WPA~P-5=$Y0ZNjxl!=7X<^tKgzjqG_ z;dhS+>Hwqu&^H=UP84U)`RF*ve!47LA7Rr}PPRo4?pG*{ru>)k zUP_~H&~GE&6TO>I+D&PAiR{wC@*;evS#|OeMDZ6UKjOrwx1>m;5H-G7iK<}xg{wJs zveiIkW^SBqG$=Jwdz+WkA^C8`SY9zf@*_xUzdz+|D&;6awp> zE*2}BMQjYPoaZbl*P zTb`4?9}6Cw-tP{VctoI)mfAq7w#K*S0$O3&j1%ZjQoqknx!0@x{tJ1}4{w+u-JER5 zf6u)M`^?~S87nPe&({ry79 z9Koatj3lAp!v5d(jYJ%FbbH3yuBru{tVQK5Uqh*yCZT+F(}nUitXc8b^J{xm@99y) z?rS})r6&Z-jE19{!$(R_-Z4eFh0=?UaHUkM0(`P{L4vF68!E5sktlx-+XgV-H|9LA zQ9HZCWfD2ik?jR4=y8Yyhb1Vl`Elc5Fm{+h3`8inU7@@m9`qJkM+IatDkHil5=%r| zrcq*4TLv#1h{%z#a}YZrrHe~YE6O5P;y+71Zam*G82sxH^+JS#5-fQa!&XwN^F`W7 zn{!d3wyIA;`2Hv2*f18;IK+U3fjQb>+5=l|?VrK9NZ4vu@4opJ31ZsZ~sa+XrQW;r-X`D!}eie}nR3P%cCrEwdi zd9zF&gY`Bn(a*!4(9MOz!OFhh;Q#UP|6_eGl>kPem#_<==P_#E{~2NwelxVGh!r^z zavnT^wivtON+Bk@YuN05;G@;-y&$J%jLDaCVib!XnVMFWjBL2yOrYBb3W|hn`E2dYdE5eUwTBbGO4*WiZQN6iHXw; zu-K8YMY(;ZCWC%ajk|g!cHTvN^I#F3|4KwnaoC?j?QA!exHy#S9GC$g9@Ea;7W6TeT-QC$9O)QnB{PHCF39*nNW=>dmhSXZS?8|~jKV-}-LKJl_$qJXsC*x5H zCG=S+6|)JY#urT}jD}nt${7y}4J%okW_hjM+=E5jv&L?gLu`Vh+RVAeI%5j8*v%P> zQp3Ru!-(nadz|`iZG*vi@axgNwc2+C5`z@|UKF_uJ0-%9Ys(tS$*c_d2z^?5M_`#UXBMWmMOgeBuR)xw!tX6HsbcZ%#}a>&-J zene^IFk7ijgYL{8cparq@Z zyB{+^&;Kl$n8t`)@9rmPJUj<)sgWhUyB^&g(371@^*Q?7wxt^p_e3L;HQ3Ez#(t7e zaBnD0tZ1h3>F^~VqFU*2@K=a{p*AsIe!ZWh^|kYIM&De-b@TF{`&u2XI_#T~U+&|u zLin>Z_c_RWz3q(g8$T}(z>}cD-Us+N<&la#Rnomu>C`2@7k~Ykob&1gDkB2oeVnulilyiS*JB?EOiMa2R zip|vCV0L}1*k*?J{5RhP&F}Sqz+fdh@^OC`c2xY;FjpdJ3GIJdc ze|E)7cpIb7&&U5_iIs_+bu4xzi?oivB`?G``u5|OSbeoC%F`x&0y`!xFXS6s^CSjd z9L6!vm4qniP_P=%q@LkW@TnFB-b@|kD?ia+V)mk^?G3HyH|;OUnhq`EX0IkNS~Wq| zsrK2eZC2EGOQ;cW$vsBvUJ+6Qmg~#-17@jSdfT3H{A;Ne5nWo(*Vq$okrt-t(qc|o z@|PyL=FM?UaNQV*Ra^{uKQ&Y;2~!={p+W0ThhIl&o&XKqDrVu?89EGjf96jWKZjL^ zICj{nPVW{+itKS3%OF4ZVSq$ucSdv3os6c}r@x7Bqy8hRF+bnJ0wWZevG9Q`G69hcGjoZY ztEwE zFTbUz#Djg&)*5>hY!U)uxjFf_;GF&KjOG4nrsJH1U3spG<|BwbWY01)j=*Y7YZ0st z_y`;>PF7lA5p`*$geC#;Ulj#T$>8euBU(({7mhU zwf24=;&4bT z*($N7QGoT%EEPA6xN`(-S9#Ej@-}|}KO|$Zxb_qb2G0-Ojs3ZfSv|*{v#uV)Za!vv z0o~Jj*e8gtU>>{ z^xwnROZ`Heq;>3U;atQR`SRc2Z2FHk6bcj?pSKI;}-5PL{g-YS`nIMhEsX=|qzGv-bVrveV%|J3gFMHt2b;?4Vr( z{u2s*J^W5tdfD=1N`bn{Ua?Q~-JFsmnnVd+?*i<37;*ZyiXGM^mU{-*Q1HHCURrLa zUw%A%-p}XXoUHSZDc_vQESs3Wcj-a<3Gd#r#i?&EO;ni74BGTMw+S2fqph4a1zoXUblM#z8rO=VhfH55@{_SdV+H#woNUh>kE;vDv_6rviE7 z=S8r=Azdmag50?Az+W_+m)5}h`DC`n0!*J>z&8$w9 zII1OaT%w3blybAkb@4HpjD)tYg_W{K19{hen~lq` zVl~3_zg!{@obz)TU$n`7Cgan#fZslr?m~wr;|`KZqr*5c8N0*cDoJ|3PoG>-z~(cz za-zPm)~@lQWC?odB-r~?YbQQ^GkxmA*kd6*S{sjFB6orI`95A+11-(HfbxJOM>R0j z+WZzGX+B(P5(9oFN5~zQaS>0Dh38%J>mg^gmH|r}!SUb1UOdDvzth5Qr*Zy>R~n#_ z2#p$8g#7+?v?>1`QSTK6;7Qo~@#6kkkxbYE%Q3a1AfmnIP+)>i@H$fwjU>&(m&~+N zh+oS3YKy|`+LTJ)vb6y(nG|jQnfSi=e&7zBv+YnIQ+K;J5m%#bhWAjwqWhWm?SPeQ zZ-~k)X)|Ch<6GDP%`JtpTVMy&H)}c$1t#m#QPQgG^cBjCz}6)w%wD#Z_Tq%^?Z7P9 zEGpZg1IFmW9#7NJEw=}_Q)U0;Ju-sons3wzv!pEeNlrjA0H6$)iuIPEW# z1>qm~*9#~7@As0mhmIc#Jf)kAwpQyh@c)o*yf3ZCEseuYo5CKW^r8PyAOo?RwEiWa zL#)@*dG1$#L`?XbEwsO5#e40A@&@5ul$)Y!3zxIW_t&89%6jBItkWWotTnWtr_#S_ zCY9UpRtmp$ue|Y=R7To$OV8kKg^q1WLmwh}q;j4A?ZEvQ`G!-60;QOZ_o}1iFS!M< zXPv4(CGK)AQuw_TLPE<OJYQCMvB(XKK34YKeTyz^h6s>_$;6lVSH7WL9VQ8N%m1fg8Z9V2neA3;=PW^}9nebmNy zjkkW@;+8x@2F1sD6vj)#fuhl03kjBx`!QHzmO9GTUos zrJp{G8Yl$VcBZaw*7(!f0Ha~*zD&{eZ|EkOTxo>)&N=?W= zU_aP$EtyO-$Wgi!U#^(g!R#m;`(XpK<*zt}=DxB2^pizElhSt0WppfOhbAv7rDVtfrE-w_=MO}B<2XOUJS*DwsxrnnEhD*2g}YQ(()7ThY>Qb+3a|0a1vevJ$_T6N zp+M*km2Yn<{hkL6*p3>S{Mi=jr`5ks1OX`qiL{17s8eqgv(v}6(D}AtkI#$rif_nG z7U}l0>@@h0qG?Ur3w|*RC(oS5O1Y2DX=2MP)BT8fqVvSJ=g>Y`+tpJ}{w+YXlTDFX zx0((IqI46_M4l{?HehAYr)k>@Ixa9fDP@{JYhz2y+g8*3{OAA^y`d#uNl2x%Vtc_~ z!gIvuc7A<0@m-(8i(<_ zukLo|U)8e%4O;Ad*TWZ;DaS?AH_4cHBERa6dE1^JuOwwzGi>rp?u?$+;tW}Ty@UXJ z`m63_nSmecfZcudkM3Y{cSAvbeV0mmANuut$0<-BvX;WlfSvE>9^FZ);>zE7k-IXc z#n7;@;lt6J{dBy^|1sV)S*<-3Sg50;y9FF#C3m_ZDr0(ERAwH0Hk>?j;w|`%zU7uQ zTE8~HN43Lp%Xo?DD?e?a|9T7VhSr82f0{f>8x7lj1X7%LG=&s9&P(A`?so#BDHtu| z1x%fK%jF10;Hec>B!1O-Kb^4&CW;vmy0yKa=^Me)=6_#Y;CG0pMG5~8_>+6wCBUOx z(!u7oH>~u}ysBoCJ6YWwJrC{crgZ>I7}TNdQi0zcu=lp#pdl32<3ST6>z&pU4}3f% zdS_*}zu6^__h)^AeTS-iO6}5pOkHOF7;)7%1!6JUB=@NTtjZ!Kwk$MNhVk%g+A^06 z+IQBQ42rD^FyZ%^CZh>;-)Cr#A9|mc`{)`gDMLww!H^AnS+G0WEC01}$s(5yE9!^6riWnpK?<_T>MWJQ)tjovfZdK(sO&Ag5y(K5$|3%If$T!p{rT=bo zu||v)6RF16;`z>|WyUw+Kk%Kte-utP;2Fo5e3|8=lC8$S8eX>J))~e$cJp&>EHid>(jsgHoyGfcjD8uKK5+B%=7>B|Nh&VPapj5 zFX1+RdD31aSacH@Ym>I&Y2S5kA zd^w&8o!_ita+C9427MhR<~X^oKXbL;lBccTX|%upHuL-X`SynI_@|j^ZscnMD&b4z zb$EYX-#_oNUdv-|Hb%%jFOtpeDX^v0IdHPWZ_dsamxyG05u~%PLnL60StQOC$<`fW zv>7{573Oc8{6%P;xJkU=A9=m+=y$pCJ2gi7mvTB%zCF@!QG0*>jb2~&)q_^k9RZ>6 z@5)+2rcUfFk8u!p$1P7Dnd#^N{Wc(NM7%pyeN>-VqPZ57AyJmw|-WH4X$ycJwarAhGcznY9;K1S=W3D z^cWsm%qVd>cDNZ8T2~bGDypwEgtZzqA}v?R5>lqw|a)ajS6YdFv1dd&aDB~?yc^1QK!?P)DD#8C1@!ybFA zFCqW2vYqw=OI2;eM8BMiez&)ioBY14lvDnZfHk8q|9iM)=YYW4M}6^III=n(nbae&%5&eBE?7Vj-Cm-UCA9PY=@=VBH*E%&3f)hjdZCkDzf9 zxd?mRx%Ox$Yfi4Bsvfyua2C%dPo4|KrfX*Wk=eeWNhj<-$H5 z_&ZLb_k6nw{w5|j0oIOENIn5yzu%2=l_)RZ6bgT6SHQ?Ev@e_~z#0+-OF*n>u4FT4 ze{UMFpiPyJo|;3ge6WHZrv4q;mcB85wgvT$_0n@2RWo+llTPWJI8P@)O0nxKcc(q> z7%#&T39A&{Gs(-T3MY5K2FD{_JF+90$8M5vj1OT29%&=?zr++13yrJBt|h(6L;smu z?essF$L>$;Hmb~Rs+TNHtdW=hqU2cWF)liu)#wxJY;&E)Zo5Hfcr=gdPG2heniuzz z35V{~;G|WdegjUS;eUG&dUr#Ja^(G@&huA=R2-mQg`5AX2y=IcV=5Tb{*p4uL;b)c z6EnAt80mf()n*lBz^kzR^73j$RcD%^&%D^i>_$Ij(sFho5xS9(4JP zCPL8?BGe*XLAw1OBIuB4xi@h=fO0I_$;G^3*Ty=&jz%5xwfA+D^gIQBa9l_=w)JYT znwBwz%LJ;Wv3wf2`fc@>7x9HQHZGCyrfT@6lS1@smiyAro1QMbhW}p|cH@6dq3lnc zkOujT!wo$l#b$DBEA+dwJ~)ml_^c|9q&x3OsJT7 zHJ)QlnmuIFyO1YC!6U;W{IU#sG(UvXa8UEI5M#B;KdiM~(p#g_0WmR65%vWNXeV{zu_1jLC> z$bZK^(nnz4t6Ifjh4yz!VlR7(laN=hxba1 z3_<(M+-$eWYV@ux46!BQwlb^9gqy@E9c1#YzDHAU@oHWkUp!CxuxXp9#m+NMW@48J zAAsX(yfyM8j+&l4uBL}`)W}AT$-^l<*|Q<1c`z2g50EkGVXt7apSJPo?G1DXUrp!e zNj*M(8iny*`)6&KxjmZS;Y^!hIu>kky+CK=&%>I{NBndh(e;q_2O_+L`>jZnHmpfN zLOxx;bbV;{LXXsr5tkd;TG*&yd1$@*i5ohYmaRJs9gT8v*{7*v!|yNRJ$xo^w$6Z- z>V_AIn$6Tgb$&?a|IeD5!!_0a*P4!mYpO*}J2f`>H*O)5Tz$b!Yd!jXtxZF8TsCg) z1&WhzDD<82eWEy_;JZe!mm%AM$G6N(7wm9#)CGNxfMOyncBoU8MNEm6nEY zec^@WsO=GyUeNw=!`R7l+i2}iG4)@@`T|U>|Hp9JLB*~XWgtjd=s79?YH^9 zRJQG>C1!PMwTsYG?Qo?0h~b5^?&$f=d%)=giqjE{UOaU6o5-4-GbDRfrH=4XoY(AO zO_BG-L$n`n4n-t7y3$g(l*}klT12W~A07Sg7<$%z&U*~3>0FUCnchOi$~JI7%%NEt3xehnN|)t=@uVn<(| zZ8*ps!kIeoM{WZ?WC33`<5~%P0e78kgtuo>2y`*m0xFCBbjVL=)Pe4kOx@{NC#{pk z*%g$NQVvMH3sFv^%ODL0|Ix>oA)hctlz6R=N&61EqXv<)v<}(^ZI5+Ee2T36aTCoS z>#S&ujAFxnPQIfrrAUqO6ysdFyaR?J3X}Xk>j9iSgfjsg;oXnZ`?#?Q?eTNU#7vC1 zypOGeO;xn?yuXU>GGc3ou|6K6-Urb8rLgA;kf19t>J3dLJzq^#&1nY(_zJ5SIx}EE z$G-;sn1bt#@xM9zukq7&QBF-Gyr5~?_Q?2HIR~TT!=sCwcR?Z1=ci?Wx@uw>Q?ytuz_ zqIH8fxdHnuwKySo+FpBG3z<;=LJA_yqrIgsOm5iy5aR0_5JB#~e|m6Lt@o6{+Z0uZ zeVD8JRb$7slL^q2v`pQrcK+D8%689)CVZo+FK3{S)s<~8`1(c5OYsdU4LfnROnrIE zLn$6&Ho`Nqy@1y7SwE<3SPQef^!1BL4e<>d?PI;m%9-5x_oOr&?90*bpfIsmo~@S> zdOFssywMpNUxI9d9cqM`nMO6RR{w~MJ|DH58(N|f<47jA_$XB;nNBax@S8hQwyBEf z*-snYH0A~{qaITVv)$!%rw4_^*0Rk7U%hC4DGEK==%cw*t~^&s5F`22K6+i-vt}P4s(LC6!EgPv%)emrAadub9;Pr>m4#2M zs*&z3QwK(==nmvhaJr(Uy&JXM?8~i$q$!6qQ@zYhlj#_K;%uedC#glGyy-x>6&^6y zt;T9j)3cOlU8((4GL)<7ySnhZ1LfT5C6X2JzwECoW1tmmFQBDwsklJ<%AdpkXuiWA zY>Y(&fK5ZsANd9L|Gwa{Jh|*ihiu?-u}iA-QKyG_s{=}ChP2WEIMIYT^ zPES0jkz(QdrTCI6*wB}I`ZQzjY$uaT;1jg5#DcT!mypR*efnHJV2sLFEH1vQhAR|v zm*QNCzS0*C_DuxtGmv~K2JC(z9ym0?S13~a!}(c#6n~cWQT!_WzYF^sxTdbV|8wt6 zLVzd{v?3rT1T+Xp6s-7GLx3xa9aimX)viIrUaFP&Qj6Q38ilUZ+RhfYTJ2Vp*4dYB z1a*V97T0cFU)C+r_IXrvrFCtpv@VExF9gW*{oO?Cv$_92pU=&?FXxeb|aGwT$JAlb#o|&rtfseMI{Q9uN11dPo=cVU|$G0&L`gQ)%9Z@d<8P&S#w~ zcQ)gzY3%rYr@$lTVla}UdsQln54_cP8uVjl@?l_S(EO6T2C1w8??-6CjoObe2fu_h zfyz%~m-eFfRS(FofU4`ReGT*2R!v41AGi-YuxmaoBn}Hvx*fpmOzP~W@8F(1Om~9H z1wv|qzS_UpZguPQZ6&&h-B>cjw_k^Z@jhwHjIdi@k^FRF#F`WMb#JG0GQ^K7%*d48TaOZ20y3}}I!|1k(RPW($ z-Va_4$)8bIg->qRim_V^VwNYinsy7Z6vc9L7e11W-g$54bqOB56D3azNh?3=LUWr>aUOs z-1qjZ@OmlIes|_jbL~v%AkvJ}?4tF94@|}`k9O-CJkJ`cj66?dm67LWJcliNWc*>) z#XM~683X?2Z{5GU`qb9gGrzmKW9y{OgI9NK)=ruT9;7a?ZdYdJb1(kxs$*-G*M2!V z@0X4ugi#2SXx@Q*|6kib?dkJRg?ner+4Gn?lQDPhOZrg7y@TEwtku$i_lde$uTj)zpg@r(r@BC9(Td*!Act)THW4)fun05Ckr@6 zYozneZpl)y(LdGG3?!xVKvJ?)cRSZ$w2op@ghz7gl5RskeAo3vdm`F9Z?Lk~;-MA2 z3Mkmwq2}7G8@+=Iq=&*7x2`Z&nK{wM1?~?~Url0MU>Q(ks26jAyVbL7oGpaDM+&%J z)U&w2ybkI&T6NaG4SE|ucNij`g$}5q78hOjs%V_dOf!zzMJs%kv>cd$ptvfC>+`@M zzTp;jjugKWE0ASNa=S_m;XJGvOQ{;5V-u2J4t)&18OzX!x#G&5ziGWb`x$-TwY3IR z1S8r4qxTYY%EG#swQsBW;~ukq?QKTu?SC-2^}w1BRxASj)2yx~gfF(&(Ol2Y{;Hmv z`d7a~*vN%{dWubGK@Zh{4!Z+;<_HZ&rNy@`J$yv5xgkAM4wWQRl|W%gdz^J)_R;*3;h6D0@gY z4Bg?G3|*O#Xo*&}4lF=zrWM;#-5KTmRIqBjN!Gvk*d%>N)cC{xnDHLWRbgyDvW^0O zi0lhs2U`#N7-J4PEV0|{HS?r*8$NPFhq*d&E@2ro!Wx}r89FfQGm3?H_^11KGr_uB z#Q`L}4M8IO3zbq3ot{6rt>U13AP5Zy;L+wm(<>XgUet;vXmYrvUC1@TL$g%V+sM)E zmO}Erw~0!>bsuz}JY}f#Fl^~<`_uRd+{}8M6-u#ElFO9#;`(JSmbTY*#+9^w z+4?imBbCVu4REV1kJ@J)N>;)(6sR^q1+Vgcd8DX=4tWtY|UT7Ca5 z)@Ro9W4&Dr%2oZlmHSX1RX|)=4jiTmpQdMb^e4)0C!4guyFp^+yeEuOtD>o)K}FDs#E zU7W%DWV^5p-^~rm^I)SKl2_h9tsoo>_Sppy1l5P#;k7Jy8R7?(saZW&W?O zy;pJVB2JC)^L9mNb7mEEI4xY`C(2GY$)qM?*PwCQ2%Bh!un#F83-1^n!;XQOk0@!! zf7*IrXI%fzf%w+lCCR=DtXbiGg9iHsnwx0P6&~N&1K0OipS3d}hwE*$_t2_49>}L1 zU8jGw^T301T2I{PSaN`7DHkCcKIb@4&z*fqNpImMzvtKV>;#I&bFc}#+ca4$6}cH0 zGvK+)?)Ma%F?P+my6*|Wf|j9nu0j5Kw`Y!UBJBH%kdvMHgcgJ?Y%7RN92Y z|Bjrp638ihrXhly5=Kg)zI!u%N~7}=AXE&>ZG*puF2H&9&A)IbV9j2PHTxvi>_!P` zOs(A~w;uGeti(L$R3Sd$f-JWIgD#_sC>Cf!{wubj85CDE_5;s5^q{!Rn0KOEmnZ$9 zm2gGZ_{~p$iKm!BY&os-k}v;lW{>z+NPr zj;O5)q@#CpGduhhJ72z$dS3DsqGz<*)qY5bj(2(Vuv!_EA5qBqg=hfkV_20yq0suF z5gUO5<5rd!L-KzGyVeQPa#~+%!l4r(Q6|f!#JNP%8pOwFT;8H*gC~V~YDJL#PlTA| zTI-tn*XpTn!{-Kc$1yL1#tFZf==^$Vn8>o{d1-cgBQymzGEDh=T_$KXt7@aeEazA6 zuQ7WhtZC09zvc(VgR-|pVcyXHxAHY)DNf+W>}*xFiT~9b3Lv9cB~n{=r4puvENHbHTQ(n5v#73e^+J8N;!Rl zTQpadNp|xKPAX~YK+^-vy2X13WLWRQYAFjnx5bz$36?@25w*Y^*?ax&{o??FZ1qN_064xQ}mv1Q*cIqAHF_4SWBaJgcfX8M+o5VPR0uHv@&8=-lQ zdU`U_#vhz6q-?@9=eIu7@N@l>bFP}ah|MdSCM3wWc0m-;eI$=d=lEZ z46>Xs1qLg~AvWn6u;2?}|D)-7LFigH0=h-eMuprcuk(v_yqVhvnjww8=>y!$>`bef zEYiIxBGpI-?v3lLtO@s=&y-^K3r^}ge^3l=>e)oeXhl~$t+$5TxxBX>wB~;6Bi

      zf-oYk^!*-lA1ncf4y)s;#ZTWx+?6=-S$K}QYs=5KEV#&J`?h#tTlcIY>=G|><9F4L zsI^~=o^(p7T{t4()Wr2aJ+#%g7&>@QU(wCfLOSrV`!ndB2p<*As9Mn8!^e&Hw)Y5e z+4$$MOMKg%Ex~729|N9_1sdR*lDh@k)0~hg9_p}(S?j-c*FvwF zzJ*z%&oIlHZ8~TYy}((K#}V+d{bVmymx-(CeX^frlIG3*{ZIGU@m+ST|8CrQ%$+6e zQI?pJASwKtpUeEQ4_7uWs}`KRCff@oJT%o_C|U1g*)`zQz*2M&&y938F2qc~^KZ+n zR8z35`~OdhyOClsdP|B6aCAq#L=#{^({J^xg;gGV@v~Np;vdVT!kw8zj zdzop^+}|NZN+j1r-*9-yo$A5?UCsp(_IxJ%dg@df=GA76;sM>d4O zgTyG0jnaAYodsf?N^KNfUSNgQLWTq5>a)IKJ;vea(XgDq$MyEtaqN#5EO-C$LdM;% zjIE5G6>N}azGXJn7Bht+_y$!M;}7nfhTZDT!La%sBtF_k~TY=EnKTO_fv z(s8Y;@_fDK>hg`vD~)BqEzFNA17B$utYd65MOAtkXbh5EVMs0xMFEM`gnh+;yn67U zf1$VpXS0J*ViWjRE5HY-$FUZN?dW4Ik4drfjpm;z_h8kKK>xae5_BWJ1ocX3w6I_3 zmme9h;>tcqUKS|5f;B^9B_0P0K$?}3%0}KvyPAW2;3=kjo{}ooIYxHcnPA~DuxLzWu4s$i^`z^4mvT&h=a+u{o#%0Y7Xkd11Q(|O=PQp|Y!tiX{{!ArdXVYc z5FW$9N?mjRj*tURcf6Okj`K=yMp?A!v91NKMb)M2R|dB7J6uBAhc0_s%=(zL9qSEU z*PoxLZdkv=#Ydj8wE61^9qszlXRF_Lg;P^Xddj7J=4a6IqBV`sjY+2XxEnkE@#z!L zOZ0k-k)Dv-!kPKB@<8=Wvh30?I{x~pEX zI@cl9MB8wr%0gMP5hK%CujC;1BpkUoY{%=B$?OvH%R`JQc$$xtQ}N_>W4$sBPYc+g zYA1HL^~!V{Gfef$OvIRl7_*IckoD0v+VL7;*PuT--xIrKJ~+i%A)%;jeS+tG%uSDj zuL0|cZy-L(XJe=gCB}GtSzP!PcS=VMSoRvqU3qG)@>S)H3OoO!CdX!?B?2E zIJ9SM=(}G8fiucty1tJm19E2&I`>nLIs7MAJAdV3CX#tE^MEX?`|QVRx!F-CoYH{& zXJAhdFQiXickH*!HNH|hb+4`1cn1rZ`fuwoLgSY149JIrU!t!l<>UvdK^!fPh2;_p zd^NBQ|8Ih0dPgVe=iVhgukg0Eju=QBKY(7qlhAmB-Z}cxbMUevoGC@@OM}*~Gtl9T z0XF7otVIHBua|bLaI8QpmS21lm^+&IM#;pTY=@<>Thsj!#WF2kDiq)E#F=e5&VG60 ztW-Sb#O?uO8DH_!lh7LC@{LpU+2^21$;D7<;BBtt^4ZuPo}+RsMmgT>qT)a zo}tc_YQ<l^FFR$+(*d;^XBjWjHK<*y+&hrgnnMW<4 z-a_d<8zdfOB`Eu5H&N8^OV_ps@&U4UX8|vEFGu=#SZsm62482eRB?y>2YFyka{x9( zRqkf@RrG606II&Mr@`t>wp(@XuP2;5^0*#R29yW}`$AI_g;y+gWl7?9QI* zPi!|H%bnQkgN02`qQK3+)M@9`rMQ;wYizl;Kj_NfWM{{lWKD( z>b(=@kF-sg#|1cL4Wvzl-YjQEnN>=WgxcJ!**-RYnz*1nO{@W(HL(I{`e|6Gy{J@(&@Q_D#?ECj?l~2w5XxaWo$Oykfi3@SOMV zF43O+;xtRAJk!LJ{z_?rm?C}z9mbDwFw2Mdg4i(jweW$T>fDAkjp`k~?NIJVJ^7%y zS4jp>(_9VsfGlt?{8ON8c_>>RaRl?>wJ!kv!(%OEtvSd0xWsaSdyzTA+u*p}OKmY0 zp5_ue^CZ@|Q9`>-gRNQP%<7Lk{ZA08gfMZKud}+*Q;pn-n$(DfGn6U=?L?#FvLrm4 zEG2j(JpCs$oHVZk(<8J7^u2zn@ZkYR39M>MFlrLSt3H-a@_4=GbL>QaB59yAG)la~ zb9?n99I2ibgTn`dQc=zg@S7 zy-B+zwa-6Jsi>bM_%bi*g+-$Fd3861TE7S?zCe5pbDY$NG}bS@1M+jq7pU>3xtII{ z@-s>&>PD+kabeNtNx$&*+G+PfPSZD4{Ox!J9mMPhp)l` zO)7teKSWl2Vc&*THKP^^k6KI#;hd%S4hRtucC&jr?{6NtcLT4A_YCulxhfGKynfz*}rQ&?WON!n7 z#|v7E0URuc?L`mEm<3LPx+i}814UE#nZGn$6V&a_&i?|vK(D2pX{@%zKU?fpS3ugW zjD@C1NcN$n<2!{{x#tN}$OP&lx)U}(>1UoGD{Du9@RE~=J11Rtu#M@H3}))LGKqF(_-c!+yKxgNE?H+A-NRq+u!k^ z)QFgki20J53&~C2M=o_}uOMW22Kf3r|3s%Q7FMQ>h!I{Ji`%%F$&l|fZws8GJMgje z7L9cc#;Ml>&np&g7k5avJG}nz#Tbu-|25d;i0VWycT{4`FLn}YJIkZBCMe73>w3%= zn!SzivrV(csgUFWF1K-hgnt=Y zlT@Oh{8xAnWPzuk>kOaiszx$oFsjU-2b$;}iFr&m*W6lQ%g4bdYBJ`)!+ohHHZkU0 z(xbwo(8oCuGp|pc4L&_Hk&g}?e0256Q-^qq$s?p4*qkOcZtnFrZ|?C^9^~T`IE=_; zdAlG9Xj zYZ&EyRjPv>xBw2dfkky$#iBJ9XWg1gAV#A;oCTolIC!q5{0ffV20xMDQ{6(YdCCKS zgy<cnDNr3D3Msqd35p(A}JMmidH$0fAyDAuj!Pi;(G zo{vJp*nV$#P5BdM3>|dRK=DBuK{{|~ZFp@OfwmkYo%#>xyy3D$pA#CW{|avGX(HZ~ zj6|t2MSUyT6VrE5FZ`d#%oHT=vNzT))enw!66u-ULi0mtn0qa>fuvsAi1tTKUxD+vG$$#!lPtw}$WR;(mC?>7ymvbT>1(}KTjYcu>+dFnf%0k~v9vp-6<2RKh zjNhTi@dGH$EjYhf4N02lPqN?@a`>lVo~k0p0QJ{(jAi$p<7UxZuqTw>deNWlzT^i_ zFcm9R=eW$#rxf|?Al4?x?5be{!WKTIaO5M##5MNG=P>gq@>keZg)yq{(ezPyHJ}H- zi8?BI^z)gyC3v})4<<0y2qRRiFg!L9#huske-xF~QGQeLA$kg9fz|^?xn;bb+VtQ2_{TTw@vFm{eSE(alnw5UFjwy8dmiX_o_9MXqw^hwGCdXM0< z(s$4FI;3$xVxM;13--VGko-(pg|@%e3R#>x2rLcqRY85BKr!~j#%V;Ik0cR9d#T!v zb&o@Pj!J$))#2jyOc$HG_53c!j*jC=%wz{|;rD%%LLDQ}$zvU%5BAO^eXi|~>L$iO z$0U^21ljARG&eYrERA2?C%Yko4}CL({P`A<6#p4fowIJCF&G8@cb~kXzrYU7L7Cgt z;^7V{vUP}Ly^4HdFvr8gUPLnovoN$&bXyeo10y_o;CRq(sV+}yUPT&Od0yIYGjnRG zrYBvGZ|^#u_?c3BJb8X$H@HleZ-T=)76=SjVAnKyK5=VL5yfZjlYcp2M+x>r4!^?4 zEaNhpSH%ObCJ1zf2FS-&I9bkn-X+Qkl%NtNIPTY>xAtMpruv9cwNnM%H|pFu2V;!J z*{`1f-|fS_GYKhWo{ITRdJ_8iaVCA4eqIu|^vj%zyr&Pi*=cd6Bqw=`k>&9np+!+_ zWEboDcn8xP5nk7!W&ys9aG8i#LKrr2qPd;WYLxPzJmszU_Mm(+nApYlj23`b5WB2| zT|VaC-=o(AA;r2!(XTyRVmPHau?(0Lq;c@=z-%@ADdbbc-+)GCil$o!1vplC26b4G z#Ii~y!p~ySOBCHMaMHVV!s{J+c=;8ImzVtb+~Av!O%g=k z1^%6P;6I6WgS_`c=`V`Gw8uf?WbWx0=|oaqag5UfR1;v~I959GKFl)Ao>=rD&Zu-^ z5GXCNz|`TVi%UgW{^!tm3HX=ZEb)FZraM}D26X!~&JnQQF_=DdrWQY6GTxbW`ju`$ z*gvNEE?}HM_Cz@fMRswGGbpD9ANNxk>me=O?tQ-G?1{tO(Sp%?r}&EBB3(|b1kM>N zN^@3HS!@E%6R0e6lO9=liondu@R7tFb`;I}N}5%3Ry)6s92^v4LdMQATo5nBXEf<}n(QoM@)!uhb` zy+sHyiB1|fn87#fip=M+PQI+Dh?&apg!-22Xfbr@c<6=b%f1|~FFhaROQPnR646>h zNjHZ+J}GEZHQs zuM;(gglEBrQqo{or#Tdq>xXneE;E8E56W*~MQ~D%dtnz77^4V#$)+PHZy3sV8sGtf zXpMei4Y zq)v@X$R()#GKy1&?`Iu%MV`aX(~SPoHVr##ZWnuY*J1j)^9nSH_l~X2$>F?NIj|Yd z;~LE(w+H)wB_}7&*V4nvqfZCrEx|MkSxqwgkK0Fev5as0{h+5n(^$1-y6o6qf|uRrJ4 zfH%W3gFb`!PqgkZ(ID+=x76BT&|g`*Iz<3V#?q{@K3+7MoA90#rOm_V8%^23Rx(&}SQ9PK({5O>FV7N}@rY4*#bkoSr3wD0+zy^& z9VoQP-nh&uYE9{5$4<_lGvc}u_xX^()p=pVRezZ^Fi`X-oz^}<<&WL zU|Gp{;=Jie`2HeCWp|O_ni~#Tp#0xreD|#Irf1jFEpDHW@`X!<5={=5>gn%F6&Qb0 zD%ac>zl~i}_|0hG2*fU*0IUADF1@#=?UGpb(xs9g4P5&3k8ZnUOd5S@R}8HgWY5pk zUto45EF_Mp{udf?Cs4xdfjajN$7pfx>DK=3mmQvWpx>O{&jQcbpR?O9a)#aZ@{6NO zErz#(%C&L*j}PgCxBa2$B3Gmf4)1y1f%PO&*Aue217o&5@33FKZ5w~b%;M!qFSQ;H zDgk}am{)vJC}zRoLkCNuPtO{|u*Y`?wA&7r*e~#IlJ{U8mvnNp_dd_z?&16c z-CR^uzhU6AeF4y9WIO6<0vjK$(@C(|hy`BVg|8CD!LN!+zC6*^%@41}u9PeI%&!+u z_?_ZY{%vBrf3^6q-v(@x*L!%w^x_0R^_g_cbJVw^uyPoWMw|2t6zmW%wkwlO7VJ{| z1IZ>u{s+7u2=gsKYzF72!wnx|r*J^`+XTrp_A#JXU7ga>A_lu97B~v;?|Q5e`+y%y z_R2&9AIANCeGKv4_zyp?fehO~epawfke`)B@QD%)Ud9NV>*u8f4lPQ%Vgz2IZa&?? zJc@HFE4*bdHR50_#AU1HKzW_CKQ9k(>TZe!Qs1Dr?g4E>Pc%0@8EPkVSn%c4y!79) zt~h9&!^548r1C|n!?TD77Ig}K(fdu%)eCcBr@VnL??GNy5iij2W?hul_uchz_^?LF za9rp2F(X@HDNCOpP`RC>8{X}WW#5;Q4WoY8=E(9s_e2}`Rh-F?p$)RM?@Ob8Sa=yG ztqzmdahXGyijb~TyoKtuzGGR&%G6kKQ)*0cqhs_5$SP}=raao7oxa_X;^I#4Nx9Eu zPYQr5_o@Hhj0^sy8GirwGrk1H!4z)omq5PwC)%0H^a9$0D?7eat;er>#=%FuRRAIf zSE|V8fL)Ost6|}LoO`NY*7fQejB|(l z`9Sz)HsvV%sC=*Jic3gvPAQu*KUos4ZcPxbKDu}x--zDT7Mz6iM}s-|Zw+#$YjQcX z7xJZRa@kO3*$WP6yQS0J;-Lwkf%2W#rNC;$-phhe6HJ2z_i$eZaGTBGiA4Lp zh2^*I6!k|op`_?_M?pun7>yoW1v&WA_Itqn-ZexyCJ&7$%f`sbL!P66q#j=yl#_;d z^9Y2ufiu9;u_qe>g+HXgO1mMSoA8dm0exkmoh@~v-l$*GH%GNZwKRe3c?rjT|E2wt zYO@WxVLlE4Jhr7pLYXPB)lR+b2-490o=?@5X-f?qdNXI{0~&seQ)9j+v$yFv?fXei z&Xr!1WsEhthEI930Bq-L@})r@IE6`0_!`6gM9M1?_wyTZp$Ukzrz6)IYj{OZI7MH* za!|;L24(_dhK_XD)iLv8Xu^ys(w2=uJuDt1%@JBLgZ@n@KYc4~nMM6k9<(St=YZcY z%LNMdONwTmwk$^CuXL?UfPcG=-twOg`3n=7LBXvo!^hbxCAVe1Ee)gDnu9mZfG6}zK zyF>9Mih6Lwhk?Vd9F4Ogr_~x@dWqr>RNUkTQ4ZMlK}IxBEo(z43VesTD)#97kj64Y zqMWL~(^RY`UfZuL3wd{?0K(B6bh&h{qsAy9jCeOJhW{Q{+< ztNCi2yVUP29x%K~lD~e4WCX^=8q7&zJDy)2I$Z1!TSVSsz#b$dUmQABGQ~@M zp`*9vr}rwRS@6VUyH`m;s6m*BP>*mVLIXl0LL)*0!jTB|2on)%5T@9!=R-MvJfwfK zQi_IkF!iwGHKV=E!lMr9*>8t1X7X6tNcHLvW)Hf@atg7J9+I0Pd^SBScYjN@p}j;q z^c(Sa4NZ~mK}q*I@_ZX`mV&cMzE+$i;w;m58D}GLmhPKUeGf{!*D=nw0cQrBCHY!$ zrpMVR-({R>aAt&dm1$bIlrcWj?LR2_v+w5jEmie*HCob+*JyvOw$g9>*0hkhUrvNv zQM-W3FT)nk%0hB4G+!#Q>c37pFTn9(K)W`8xNm-n(6s&_3(UQDxqhO~C30Cckl;dy91E!26VfbBr<{8`B4`L;;4 zk4XDU)p4%HP-PvI_r=jHy<)>do2TVGl#B3wsba&b)fEq~-889^&0Dp$%Cw|n;~EBC zy~vN`BOK027NWf=T#9RoLh>bgzB_VV9|^11Rc~U2E|+6N^|}Y{cCqRW>vM73|M0r1 zT31!&rm9ud8#mycv)0wDt9YpD4!rUm%IDKDz!i#wLL}7TK|Ah8;hI7{u78g(Ch|NQ z*OV?cat%q3dOa)>Zmil+S+j1&3{%OXMdgcTmMPzze3nE1$q)tKoz=;cL|KstX z1rWM37^C*57r+a>nqeG;pX0qogy?NNh4lgxC`3jYgr@ybOiR}v>Y0v0<8T&*ka*R4 zy52p4MI&^chaM?HcYP|0Mc9-vo*57xe=mm(L)i7eR5lzTi=NHm5LT~S&DK?{W7c(O z@JzIgikmmND2$^w;9zW5>L1^F525|b7i`ZWWCwO9-ACcqn@cB9Xu7}Yav?%i_3<$^ ztpA_K)zBNiSPfAYHDnKdZKrsw;cz&#Zw-fRUL+i8-}^lM+UNXennX^ z`?6Ub8@HY-AN4S`bvC=vdu`NLwpO73N$5XLraxC1?qi=;G5z9|;q&XUF-S93A;Ho0 zOyA>Tde26te+A*(2Vtjzueb%~g`sZNJN#)Lpgrg$&`w-9Z@Y*%( zp+z-p;nIAQV}S{$rlOj4n>N&}T~@WBrgWOAyyQ+6k50s+$zC6y4#$%mFK}v^sEtt` z%A0-w64H0$2wySw&&YYk7N)0z?&n0pjE%V&8(Hp6HIY4e^3*9d+l@Q;S{qxu + * + * 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 NuttX 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 "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/* Clocking *************************************************************************/ +/* The board provides the following clock sources: + * + * X1: 24 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed internal oscillator + * HSE: 24 MHz crystal for HSE + */ +#define STM32_BOARD_XTAL 24000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 0 + +#define STM32_HSEBYP_ENABLE 1 + +/* Main PLL Configuration. + * + * PLL source is HSE = 24,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (24,000,000 / 2) * 80 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(2) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(80) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 80) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_4_8_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(32) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 32) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(32) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 32) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * Note: look at Table 54 in ST Manual + */ +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */ +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */ +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */ +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */ +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */ +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */ +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */ +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + +/* FLASH wait states */ +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + + +/* UART/USART */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ + +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */ +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */ + +#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */ +#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */ + +#define GPIO_USART6_TX 0 /* USART6 is RX-only */ +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ + +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ + +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ + + +/* CAN */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ + +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + + +/* SPI */ +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */ + +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_3) /* PB10 */ +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */ + +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */ + + +/* I2C */ +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_4 /* PB6 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_4 /* PB7 */ diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/include/board_dma_map.h b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/include/board_dma_map.h new file mode 100755 index 000000000000..99a2fe3ba9b9 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/include/board_dma_map.h @@ -0,0 +1,44 @@ +/**************************************************************************** + * + * Copyright (c) 2021 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 + +// DMAMUX1 +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA1:71 */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA1:72 */ + +#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:83 */ +#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:84 */ diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/nsh/defconfig b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..c9ec46ed878e --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/nsh/defconfig @@ -0,0 +1,260 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x1124 +CONFIG_CDCACM_PRODUCTSTR="3DRControlZeroH7OEM_revG" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_VENDORSTR="3DR" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_STM32H7_PWR_EXTERNAL_SOURCE_SUPPLY=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI5_DMA=y +CONFIG_STM32H7_SPI5_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM2=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_SERIAL_CONSOLE=y +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=3000 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/bootloader_script.ld b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/bootloader_script.ld new file mode 100755 index 000000000000..3fb4cc1f33ce --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,221 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The board uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > AXI_SRAM AT > FLASH + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + .ramfunc : { + _sramfuncs = .; + *(.ramfunc .ramfunc.*) + . = ALIGN(4); + _eramfuncs = .; + } > ITCM_RAM AT > FLASH + + _framfuncs = LOADADDR(.ramfunc); +} diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/script.ld b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/script.ld new file mode 100755 index 000000000000..02e763a790fb --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/nuttx-config/scripts/script.ld @@ -0,0 +1,228 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2021 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The board uses an STM32H743XIH6 and has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/CMakeLists.txt b/boards/3dr/ctrl-zero-h7-oem-revg/src/CMakeLists.txt new file mode 100755 index 000000000000..6a7d2ce306f7 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/CMakeLists.txt @@ -0,0 +1,65 @@ +############################################################################ +# +# Copyright (c) 2021 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + spi.cpp + timer_config.cpp + usb.c + ) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/board_config.h b/boards/3dr/ctrl-zero-h7-oem-revg/src/board_config.h new file mode 100755 index 000000000000..bcc8bba1a619 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/board_config.h @@ -0,0 +1,187 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +#include +#include +#include +#include + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ +#define GPIO_nLED_RED /* PB11 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) +#define GPIO_nLED_GREEN /* PB1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1) +#define GPIO_nLED_BLUE /* PB3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN3) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_OVERLOAD_LED LED_RED +#define BOARD_ARMED_STATE_LED LED_BLUE + +/* ADC channels */ +#define PX4_ADC_GPIO \ + /* PA2 */ GPIO_ADC12_INP14, \ + /* PA3 */ GPIO_ADC12_INP15, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PC1 */ GPIO_ADC123_INP11 + +/* Define Channel numbers must match above GPIO pins */ +#define ADC_BATTERY_VOLTAGE_CHANNEL 14 /* PA2 BATT_VOLT_SENS */ +#define ADC_BATTERY_CURRENT_CHANNEL 15 /* PA3 BATT_CURRENT_SENS */ +#define ADC_SCALED_V5_CHANNEL 18 /* PA4 VDD_5V_SENS */ +#define ADC_RC_RSSI_CHANNEL 11 /* PC1 */ + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_RC_RSSI_CHANNEL)) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* CAN Silence: Silent mode control */ +#define GPIO_CAN1_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5) + +/* PWM */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +/* Power supply control and monitoring GPIOs */ +#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5) + +#define GPIO_VDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define BOARD_NUMBER_BRICKS 1 + +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4) +#define GPIO_VDD_1V2_CORE_POWER_EN /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) + +/* Define True logic Power Control in arch agnostic form */ +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (!on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() (px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) == 0) + +/* Tone alarm output */ +#define TONE_ALARM_TIMER 2 /* timer 2 */ +#define TONE_ALARM_CHANNEL 1 /* PA15 TIM2_CH1 */ + +#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2 + +/* USB OTG FS */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 3 /* use timer3 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */ + +#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */ +#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1 + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS3" + +#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1) + +/* Safety Switch: Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_SAFETY_SWITCH_IN /* PC4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * Board has a separate RC_IN + * + * GPIO PPM_IN on PB0 T3CH3 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * Inversion is possible in the UART and can drive GPIO_PPM_IN as an output + */ +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID BOARD_ADC_USB_CONNECTED +#define BOARD_ADC_SERVO_VALID (1) /* never powers off the Servo rail */ +#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_BRICK1_VALID)) + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + +#define BOARD_HAS_STATIC_MANIFEST 1 + + +#define BOARD_NUM_IO_TIMERS 3 + + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_nPOWER_IN_A, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_VDD_1V2_CORE_POWER_EN, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_OTGFS_VBUS, \ + } + +__BEGIN_DECLS +#ifndef __ASSEMBLY__ + +extern void stm32_spiinitialize(void); +extern void board_peripheral_reset(int ms); + +#include +#endif /* __ASSEMBLY__ */ +__END_DECLS diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/bootloader_main.c b/boards/3dr/ctrl-zero-h7-oem-revg/src/bootloader_main.c new file mode 100755 index 000000000000..bb6b4dc23aad --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2020, 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_configgpio(GPIO_OTGFS_VBUS); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/hw_config.h b/boards/3dr/ctrl-zero-h7-oem-revg/src/hw_config.h new file mode 100755 index 000000000000..b212ccd60273 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2020 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 + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1124 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 24 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_RED +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_RED +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/i2c.cpp b/boards/3dr/ctrl-zero-h7-oem-revg/src/i2c.cpp new file mode 100755 index 000000000000..1b8927c69939 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/i2c.cpp @@ -0,0 +1,40 @@ +/**************************************************************************** + * + * Copyright (C) 2020 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 + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(3), + initI2CBusExternal(4), +}; diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/init.c b/boards/3dr/ctrl-zero-h7-oem-revg/src/init.c new file mode 100755 index 000000000000..daaace48fb2f --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/init.c @@ -0,0 +1,204 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * board-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + VDD_3V3_SPEKTRUM_POWER_EN(last); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + board_control_spi_sensors_power_configgpio(); + + /* configure LEDs */ + board_autoled_initialize(); +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Power on Interfaces */ + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + px4_platform_init(); + + stm32_spiinitialize(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + +#ifdef CONFIG_MMCSD + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0); + } + + if (mmcsd_slotinitialize(0, sdio_dev) != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n"); + } + + /* Assume that the SD card is inserted. What choice do we have? */ + sdio_mediachange(sdio_dev, true); +#endif /* CONFIG_MMCSD */ + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + return OK; +} diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/led.c b/boards/3dr/ctrl-zero-h7-oem-revg/src/led.c new file mode 100755 index 000000000000..0e7beb3a9e3b --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/led.c @@ -0,0 +1,111 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(led, true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(led, false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(led, !phy_get_led(led)); +} diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/spi.cpp b/boards/3dr/ctrl-zero-h7-oem-revg/src/spi.cpp new file mode 100755 index 000000000000..4a4c3502bbd9 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/spi.cpp @@ -0,0 +1,53 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin15}, SPI::DRDY{GPIO::PortE, GPIO::Pin12}), + }, {GPIO::PortE, GPIO::Pin3}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10}), + initSPIDevice(DRV_BARO_DEVTYPE_DPS310, SPI::CS{GPIO::PortD, GPIO::Pin7}), + }), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortF, GPIO::Pin3}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin6}, SPI::DRDY{GPIO::PortF, GPIO::Pin1}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/timer_config.cpp b/boards/3dr/ctrl-zero-h7-oem-revg/src/timer_config.cpp new file mode 100755 index 000000000000..e23880491444 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/timer_config.cpp @@ -0,0 +1,54 @@ +/**************************************************************************** + * + * Copyright (C) 2021 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 + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer8, DMA{DMA::Index1}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}), + initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/src/usb.c b/boards/3dr/ctrl-zero-h7-oem-revg/src/usb.c new file mode 100755 index 000000000000..fe32ce71ac63 --- /dev/null +++ b/boards/3dr/ctrl-zero-h7-oem-revg/src/usb.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + + + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} From af0129dab7521bff7807feb0bfe5a7f338f7975c Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 14 Aug 2024 07:42:20 -0700 Subject: [PATCH 628/652] github: update bug report template Removes unnecessary required fields --- .github/ISSUE_TEMPLATE/bug_report.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml index 60d93ea9b811..ffbb271a900f 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.yml +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -20,14 +20,14 @@ body: 3. Took off '....' 4. See error validations: - required: true + required: false - type: textarea attributes: label: Expected behavior description: A clear and concise description of what you expected to happen. validations: - required: true + required: false - type: textarea attributes: @@ -45,7 +45,7 @@ body: placeholder: | # PASTE HERE THE LINK TO THE LOG validations: - required: true + required: false - type: markdown attributes: @@ -60,14 +60,14 @@ body: placeholder: | # If you don't know the version, paste the output of `ver all` in the MAVLink Shell of QGC validations: - required: true + required: false - type: input attributes: label: Flight controller description: Specify your flight controller model (what type is it, where was it bought from, ...). validations: - required: true + required: false - type: dropdown attributes: From 2a124fd99898166637e6bea3e3123aa6bfe176ef Mon Sep 17 00:00:00 2001 From: Vilius Date: Thu, 15 Aug 2024 12:29:02 +0300 Subject: [PATCH 629/652] Add Bosch BMM350 magnetometer (#23362) * Add Bosch BMM350 magnetometer * BMM350 replace info messages with debug messages * BMM350 update measurement interval * BMM350 fix offsets, update based on review * BMM350 Update default parameters to 50Hz * Update OTP Word LSB check * BMM350 fix styles and formatting * BMM350 update error checks --- src/drivers/drv_sensor.h | 2 + src/drivers/magnetometer/bosch/CMakeLists.txt | 1 + .../magnetometer/bosch/bmm350/BMM350.cpp | 773 ++++++++++++++++++ .../magnetometer/bosch/bmm350/BMM350.hpp | 210 +++++ .../bosch/bmm350/Bosch_BMM350_registers.hpp | 159 ++++ .../magnetometer/bosch/bmm350/CMakeLists.txt | 48 ++ src/drivers/magnetometer/bosch/bmm350/Kconfig | 5 + .../magnetometer/bosch/bmm350/bmm350_main.cpp | 89 ++ .../magnetometer/bosch/bmm350/module.yaml | 44 + 9 files changed, 1331 insertions(+) create mode 100755 src/drivers/magnetometer/bosch/bmm350/BMM350.cpp create mode 100644 src/drivers/magnetometer/bosch/bmm350/BMM350.hpp create mode 100644 src/drivers/magnetometer/bosch/bmm350/Bosch_BMM350_registers.hpp create mode 100644 src/drivers/magnetometer/bosch/bmm350/CMakeLists.txt create mode 100644 src/drivers/magnetometer/bosch/bmm350/Kconfig create mode 100644 src/drivers/magnetometer/bosch/bmm350/bmm350_main.cpp create mode 100644 src/drivers/magnetometer/bosch/bmm350/module.yaml diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 378c92b6736c..53eecce4be71 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -242,6 +242,8 @@ #define DRV_INS_DEVTYPE_VN300 0xE3 #define DRV_DIFF_PRESS_DEVTYPE_ASP5033 0xE4 +#define DRV_MAG_DEVTYPE_BMM350 0xE5 + #define DRV_DEVTYPE_UNUSED 0xff #endif /* _DRV_SENSOR_H */ diff --git a/src/drivers/magnetometer/bosch/CMakeLists.txt b/src/drivers/magnetometer/bosch/CMakeLists.txt index b814e7224fb1..d7e848ec86a4 100644 --- a/src/drivers/magnetometer/bosch/CMakeLists.txt +++ b/src/drivers/magnetometer/bosch/CMakeLists.txt @@ -32,3 +32,4 @@ ############################################################################ add_subdirectory(bmm150) +add_subdirectory(bmm350) diff --git a/src/drivers/magnetometer/bosch/bmm350/BMM350.cpp b/src/drivers/magnetometer/bosch/bmm350/BMM350.cpp new file mode 100755 index 000000000000..e4e8e19f9c5e --- /dev/null +++ b/src/drivers/magnetometer/bosch/bmm350/BMM350.cpp @@ -0,0 +1,773 @@ +/**************************************************************************** + * + * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "BMM350.hpp" +using namespace time_literals; + +BMM350::BMM350(const I2CSPIDriverConfig &config) : + I2C(config), + I2CSPIDriver(config), + ModuleParams(nullptr), + _px4_mag(get_device_id(), config.rotation) + +{ +} + +BMM350::~BMM350() +{ + perf_free(_reset_perf); + perf_free(_bad_read_perf); + perf_free(_self_test_failed_perf); +} + +int BMM350::init() +{ + ModuleParams::updateParams(); + ParametersUpdate(true); + int ret = I2C::init(); + + if (ret != PX4_OK) { + DEVICE_DEBUG("I2C::init failed (%i)", ret); + return ret; + } + + return Reset() ? 0 : -1; +} + +bool BMM350::Reset() +{ + RegisterWrite(Register::CMD, SOFT_RESET); + _state = STATE::RESET; + ScheduleClear(); + ScheduleDelayed(1_ms); + return true; +} + +void BMM350::print_status() +{ + I2CSPIDriverBase::print_status(); + + perf_print_counter(_reset_perf); + perf_print_counter(_bad_read_perf); + perf_print_counter(_self_test_failed_perf); +} + +void BMM350::ParametersUpdate(bool force) +{ + if (_parameter_update_sub.updated() || force) { + parameter_update_s param_update; + _parameter_update_sub.copy(¶m_update); + updateParams(); + UpdateMagParams(); + } +} + +void BMM350::UpdateMagParams() +{ + uint8_t odr = GetODR(_param_bmm350_odr.get()); + uint8_t avg = GetAVG(_param_bmm350_avg.get()); + + _mag_odr_mode = odr; + _mag_avg_mode = avg; + _mag_pad_drive = static_cast(_param_bmm350_drive.get()); + PX4_DEBUG("Set params odr = %d, avg = %d, drive = %d", _mag_odr_mode, _mag_avg_mode, _mag_pad_drive); +} + +uint8_t BMM350::GetODR(int value) +{ + switch (value) { + case 0: return ODR_400HZ; + + case 1: return ODR_200HZ; + + case 2: return ODR_100HZ; + + case 3: return ODR_50HZ; + + case 4: return ODR_25HZ; + + case 5: return ODR_12_5HZ; + + case 6: return ODR_6_25HZ; + + case 7: return ODR_3_125HZ; + + case 8: return ODR_1_5625HZ; + + default: return ODR_200HZ; + } +} + +hrt_abstime BMM350::OdrToUs(uint8_t odr) +{ + switch (odr) { + case ODR_400HZ: + return 2500_us; + + case ODR_200HZ: + return 5000_us; + + case ODR_100HZ: + return 10000_us; + + case ODR_50HZ: + return 20000_us; + + case ODR_25HZ: + return 40000_us; + + case ODR_12_5HZ: + return 80000_us; + + case ODR_6_25HZ: + return 160000_us; + + case ODR_3_125HZ: + return 320000_us; + + case ODR_1_5625HZ: + return 640000_us; + + default: + return 5000_us; + } +} + +uint8_t BMM350::GetAVG(int value) +{ + switch (value) { + case 0: return AVG_NO_AVG; + + case 1: return AVG_2; + + case 2: return AVG_4; + + case 3: return AVG_8; + + default: return AVG_2; + } +} + + +int BMM350::probe() +{ + for (int i = 0; i < 3; i++) { + uint8_t chip_id; + + if (PX4_OK == RegisterRead(Register::CHIP_ID, &chip_id)) { + PX4_DEBUG("CHIP_ID: 0x%02hhX", chip_id); + + if (chip_id == chip_identification_number) { + return PX4_OK; + } + } + } + + return PX4_ERROR; +} + +void BMM350::RunImpl() +{ + const hrt_abstime now = hrt_absolute_time(); + int ret = PX4_OK; + ParametersUpdate(); + + switch (_state) { + case STATE::RESET: { + if (RegisterWrite(Register::CMD, SOFT_RESET) == PX4_OK) { + _reset_timestamp = now; + _state = STATE::WAIT_FOR_RESET; + perf_count(_reset_perf); + } + + ScheduleDelayed(10_ms); + } + break; + + case STATE::WAIT_FOR_RESET: { + ret = probe(); + + if (ret == PX4_OK) { + _state = STATE::RESET; + uint8_t status_0; + ret = RegisterRead(Register::PMU_STATUS_0, &status_0); + + if (ret == PX4_OK && (status_0 & PWR_NORMAL) != 0) { + ret = PX4_ERROR; + } + + if (ret == PX4_OK) { + ret = UpdateMagOffsets(); + } + + if (ret == PX4_OK) { + PX4_DEBUG("Going to FGR"); + _state = STATE::FGR; + + } + + ScheduleDelayed(10_ms); + + } else { + if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) { + PX4_DEBUG("Reset failed, retrying"); + _state = STATE::RESET; + ScheduleDelayed(100_ms); + + } else { + PX4_DEBUG("Reset not complete, check again in 10 ms"); + ScheduleDelayed(10_ms); + } + } + } + break; + + case STATE::FGR: { + _state = STATE::RESET; + uint8_t odr_reg_data = (ODR_100HZ & 0xf); + odr_reg_data = ((odr_reg_data & ~(0x30)) | ((AVG_2 << 0x4) & 0x30)); + ret = RegisterWrite(Register::PMU_CMD_AGGR_SET, odr_reg_data); + + if (ret == PX4_OK) { + ret = RegisterWrite(Register::PMU_CMD_AXIS_EN, EN_XYZ); + } + + if (ret == PX4_OK) { + ret = RegisterWrite(Register::PMU_CMD, PMU_CMD_FGR); + } + + if (ret == PX4_OK) { + PX4_DEBUG("Going to BR"); + _state = STATE::BR; + } + + ScheduleDelayed(30_ms); + } + break; + + case STATE::BR: { + uint8_t status_0; + _state = STATE::RESET; + ret = RegisterRead(Register::PMU_STATUS_0, &status_0); + + if (ret == PX4_OK && PMU_CMD_STATUS_0_RES(status_0) == PMU_STATUS_FGR) { + ret = RegisterWrite(Register::PMU_CMD, PMU_CMD_BR_FAST); + + if (ret == PX4_OK) { + PX4_DEBUG("Going to after reset"); + _state = STATE::AFTER_RESET; + } + } + + ScheduleDelayed(4_ms); + } + break; + + case STATE::AFTER_RESET: { + uint8_t status_0; + _state = STATE::RESET; + ret = RegisterRead(Register::PMU_STATUS_0, &status_0); + + if (ret == PX4_OK && PMU_CMD_STATUS_0_RES(status_0) == PMU_STATUS_BR_FAST) { + _state = STATE::MEASURE_FORCED; + _self_test_state = SELF_TEST_STATE::INIT; + PX4_DEBUG("Going to fast FM"); + } + + ScheduleNow(); + } + break; + + case STATE::MEASURE_FORCED: { + ret = RegisterWrite(Register::PMU_CMD, PMU_CMD_FAST_FM); + + if (ret == PX4_OK) { + _state = STATE::SELF_TEST_CHECK; + + } else { + _state = STATE::RESET; + } + + ScheduleDelayed(OdrToUs(_mag_odr_mode)); + break; + } + + case STATE::SELF_TEST_CHECK: { + + float xyzt[4]; + _state = STATE::RESET; + + if (ReadOutRawData(xyzt) != PX4_OK) { + perf_count(_self_test_failed_perf); + ScheduleNow(); + break; + } + + switch (_self_test_state) { + case SELF_TEST_STATE::INIT: + memcpy(_initial_self_test_values, xyzt, sizeof(_initial_self_test_values)); + + if (RegisterWrite(Register::TMR_SELF_TEST_USER, SELF_TEST_POS_X) == PX4_OK) { + _self_test_state = SELF_TEST_STATE::POS_X; + _state = STATE::MEASURE_FORCED; + } + + break; + + case SELF_TEST_STATE::POS_X: + if (xyzt[0] - _initial_self_test_values[0] >= 130.0f && + RegisterWrite(Register::TMR_SELF_TEST_USER, SELF_TEST_NEG_X) == PX4_OK) { + _self_test_state = SELF_TEST_STATE::NEG_X; + _state = STATE::MEASURE_FORCED; + } + + break; + + case SELF_TEST_STATE::NEG_X: + if (xyzt[0] - _initial_self_test_values[0] <= -130.0f && + RegisterWrite(Register::TMR_SELF_TEST_USER, SELF_TEST_POS_Y) == PX4_OK) { + _self_test_state = SELF_TEST_STATE::POS_Y; + _state = STATE::MEASURE_FORCED; + } + + break; + + case SELF_TEST_STATE::POS_Y: + if (xyzt[1] - _initial_self_test_values[1] >= 130.0f && + RegisterWrite(Register::TMR_SELF_TEST_USER, SELF_TEST_NEG_Y) == PX4_OK) { + _self_test_state = SELF_TEST_STATE::NEG_Y; + _state = STATE::MEASURE_FORCED; + } + + break; + + case SELF_TEST_STATE::NEG_Y: + if (xyzt[1] - _initial_self_test_values[1] <= -130.0f && + RegisterWrite(Register::TMR_SELF_TEST_USER, SELF_TEST_DISABLE) == PX4_OK) { + PX4_DEBUG("Self test good, going to configure"); + _state = STATE::CONFIGURE; + } + + break; + + } + + if (_state == STATE::RESET) { + PX4_DEBUG("Self test failed"); + perf_count(_self_test_failed_perf); + } + + ScheduleDelayed(1_ms); + } + break; + + + case STATE::CONFIGURE: + if (Configure() == PX4_OK) { + _state = STATE::READ; + PX4_DEBUG("Configure went fine"); + ScheduleOnInterval(OdrToUs(_mag_odr_mode), 50_ms); + + } else { + // CONFIGURE not complete + if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) { + PX4_DEBUG("Configure failed, resetting"); + _state = STATE::RESET; + + } else { + PX4_DEBUG("Configure failed, retrying"); + } + + ScheduleDelayed(100_ms); + } + + break; + + case STATE::READ: { + // -- start get_compensated_mag_xyz_temp_data + float out_data[4] = {0.0f}; + float dut_offset_coeff[3], dut_sensit_coeff[3], dut_tcos[3], dut_tcss[3]; + float cr_ax_comp_x, cr_ax_comp_y, cr_ax_comp_z; + + ret = ReadOutRawData(out_data); + + if (ret == PX4_OK) { + // Apply compensation to temperature reading + out_data[3] = (1 + _mag_comp_vals.dut_sensit_coef.t_sens) * out_data[3] + + _mag_comp_vals.dut_offset_coef.t_offs; + + // Store magnetic compensation structure to an array + dut_offset_coeff[0] = _mag_comp_vals.dut_offset_coef.offset_x; + dut_offset_coeff[1] = _mag_comp_vals.dut_offset_coef.offset_y; + dut_offset_coeff[2] = _mag_comp_vals.dut_offset_coef.offset_z; + + dut_sensit_coeff[0] = _mag_comp_vals.dut_sensit_coef.sens_x; + dut_sensit_coeff[1] = _mag_comp_vals.dut_sensit_coef.sens_y; + dut_sensit_coeff[2] = _mag_comp_vals.dut_sensit_coef.sens_z; + + dut_tcos[0] = _mag_comp_vals.dut_tco.tco_x; + dut_tcos[1] = _mag_comp_vals.dut_tco.tco_y; + dut_tcos[2] = _mag_comp_vals.dut_tco.tco_z; + + dut_tcss[0] = _mag_comp_vals.dut_tcs.tcs_x; + dut_tcss[1] = _mag_comp_vals.dut_tcs.tcs_y; + dut_tcss[2] = _mag_comp_vals.dut_tcs.tcs_z; + + for (int idx = 0; idx < 3; idx++) { + out_data[idx] *= 1 + dut_sensit_coeff[idx]; + out_data[idx] += dut_offset_coeff[idx]; + out_data[idx] += dut_tcos[idx] * (out_data[3] - _mag_comp_vals.dut_t0); + out_data[idx] /= 1 + dut_tcss[idx] * (out_data[3] - _mag_comp_vals.dut_t0); + } + + cr_ax_comp_x = (out_data[0] - _mag_comp_vals.cross_axis.cross_x_y * out_data[1]) / + (1 - _mag_comp_vals.cross_axis.cross_y_x * _mag_comp_vals.cross_axis.cross_x_y); + cr_ax_comp_y = (out_data[1] - _mag_comp_vals.cross_axis.cross_y_x * out_data[0]) / + (1 - _mag_comp_vals.cross_axis.cross_y_x * _mag_comp_vals.cross_axis.cross_x_y); + cr_ax_comp_z = + (out_data[2] + + (out_data[0] * + (_mag_comp_vals.cross_axis.cross_y_x * _mag_comp_vals.cross_axis.cross_z_y - + _mag_comp_vals.cross_axis.cross_z_x) - + out_data[1] * + (_mag_comp_vals.cross_axis.cross_z_y - _mag_comp_vals.cross_axis.cross_x_y * + _mag_comp_vals.cross_axis.cross_z_x)) / + (1 - _mag_comp_vals.cross_axis.cross_y_x * _mag_comp_vals.cross_axis.cross_x_y)); + + out_data[0] = cr_ax_comp_x; + out_data[1] = cr_ax_comp_y; + out_data[2] = cr_ax_comp_z; + _px4_mag.set_error_count(perf_event_count(_bad_read_perf) + perf_event_count(_self_test_failed_perf)); + _px4_mag.set_temperature(out_data[3]); + _px4_mag.update(now, out_data[0], out_data[1], out_data[2]); + + } else { + perf_count(_bad_read_perf); + } + } + + break; + } +} + +int BMM350::Configure() +{ + PX4_DEBUG("Configuring"); + uint8_t readData = 0; + int ret; + + // Set pad drive + ret = RegisterWrite(Register::PAD_CTRL, (_mag_pad_drive & 0x7)); + + if (ret != PX4_OK) { + PX4_DEBUG("Couldn't set pad drive, defaults to 7"); + return ret; + } + + // Set PMU data aggregation + uint8_t odr = _mag_odr_mode; + uint8_t avg = _mag_avg_mode; + + if (odr == ODR_400HZ && avg >= AVG_2) { + avg = AVG_NO_AVG; + + } else if (odr == ODR_200HZ && avg >= AVG_4) { + avg = AVG_2; + + } else if (odr == ODR_100HZ && avg >= AVG_8) { + avg = AVG_4; + } + + uint8_t odr_reg_data = (odr & 0xf); + odr_reg_data = ((odr_reg_data & ~(0x30)) | ((avg << 0x4) & 0x30)); + + ret = RegisterWrite(Register::PMU_CMD_AGGR_SET, odr_reg_data); + + if (ret != PX4_OK) { + PX4_DEBUG("Cannot set PMU AGG REG"); + return ret; + } + + ret = RegisterRead(Register::PMU_CMD_AGGR_SET, &readData); + + if (ret != PX4_OK || readData != odr_reg_data) { + PX4_DEBUG("Couldn't check PMU AGGR REG"); + return ret; + } + + odr_reg_data = PMU_CMD_UPDATE_OAE; + ret = RegisterWrite(Register::PMU_CMD, odr_reg_data); + + if (ret != PX4_OK) { + PX4_DEBUG("Couldn't write PMU CMD REG"); + return ret; + } + + ret = RegisterRead(Register::PMU_CMD, &readData); + + if (ret != PX4_OK || readData != odr_reg_data) { + PX4_DEBUG("Couldn't check PMU CMD REG"); + return ret; + } + + // Enable AXIS + uint8_t axis_data = EN_X | EN_Y | EN_Z; + // PMU_CMD_AXIS_EN + ret = RegisterWrite(Register::PMU_CMD_AXIS_EN, axis_data); + + if (ret != PX4_OK) { + PX4_DEBUG("Couldn't write AXIS data"); + return ret; + } + + ret = RegisterRead(Register::PMU_CMD_AXIS_EN, &readData); + + if (ret != PX4_OK || readData != axis_data) { + PX4_DEBUG("Couldn't cross check the set AXIS"); + return ret; + } + + ret = RegisterWrite(Register::PMU_CMD, PMU_CMD_NM); + + if (ret != PX4_OK) { + PX4_DEBUG("Failed to start mag in normal mode"); + return ret; + } + + // microTesla -> Gauss + _px4_mag.set_scale(0.01f); + + return ret; +} + +int32_t BMM350::FixSign(uint32_t inval, int8_t num_bits) +{ + int32_t power = 1 << (num_bits - 1); // Calculate 2^(num_bits - 1) + int32_t retval = static_cast(inval); + + if (retval >= power) { + retval -= (power << 1); // Equivalent to retval = retval - (power * 2) + } + + return retval; +} + +int BMM350::ReadOutRawData(float *out_data) +{ + if (out_data == NULL) { + return -1; + } + + float temp = 0.0; + struct BMM350::raw_mag_data raw_data = {0}; + + // --- Start read_uncomp_mag_temp_data + uint8_t mag_data[14] = {0}; + + uint32_t raw_mag_x, raw_mag_y, raw_mag_z, raw_temp; + uint8_t cmd = static_cast(Register::DATAX_XLSB); + + uint8_t res = transfer(&cmd, 1, (uint8_t *)&mag_data, sizeof(mag_data)); + + if (res != PX4_OK) { + return -1; + } + + raw_mag_x = mag_data[2] + ((uint32_t)mag_data[3] << 8) + ((uint32_t)mag_data[4] << 16); + raw_mag_y = mag_data[5] + ((uint32_t)mag_data[6] << 8) + ((uint32_t)mag_data[7] << 16); + raw_mag_z = mag_data[8] + ((uint32_t)mag_data[9] << 8) + ((uint32_t)mag_data[10] << 16); + raw_temp = mag_data[11] + ((uint32_t)mag_data[12] << 8) + ((uint32_t)mag_data[13] << 16); + + raw_data.raw_x = FixSign(raw_mag_x, 24); + raw_data.raw_y = FixSign(raw_mag_y, 24); + raw_data.raw_z = FixSign(raw_mag_z, 24); + raw_data.raw_t = FixSign(raw_temp, 24); + // --- End read_uncomp_mag_temp_data + + // --- Start read_out_raw_data + out_data[0] = (float)raw_data.raw_x * lsb_to_utc_degc[0]; + out_data[1] = (float)raw_data.raw_y * lsb_to_utc_degc[1]; + out_data[2] = (float)raw_data.raw_z * lsb_to_utc_degc[2]; + out_data[3] = (float)raw_data.raw_t * lsb_to_utc_degc[3]; + + // Adjust temperature + if (out_data[3] > 0.0f) { + temp = (float)(out_data[3] - (1 * 25.49f)); + + } else if (out_data[3] < 0.0f) { + temp = (float)(out_data[3] - (-1 * 25.49f)); + + } else { + temp = (float)(out_data[3]); + } + + out_data[3] = temp; + + return res; +} + +int BMM350::ReadOTPWord(uint8_t addr, uint16_t *lsb_msb) +{ + uint8_t otp_cmd = OTP_DIR_READ | (addr & OTP_WORD_MSK); + int ret = RegisterWrite(Register::OTP_CMD, otp_cmd); + uint8_t otp_status = 0; + + if (ret == PX4_OK) { + do { + ret = RegisterRead(Register::OTP_STATUS, &otp_status); + + if (ret != PX4_OK) { + return PX4_ERROR; + } + } while (!(otp_status & 0x01)); + + uint8_t msb = 0, lsb = 0; + ret = RegisterRead(Register::OTP_DATA_MSB, &msb); + + if (ret == PX4_OK) { + ret = RegisterRead(Register::OTP_DATA_LSB, &lsb); + + if (ret == PX4_OK) { + *lsb_msb = ((msb << 8) | lsb) & 0xffff; + } + } + } + + return ret; +} + +int BMM350::UpdateMagOffsets() +{ + PX4_DEBUG("DUMPING OTP"); + uint16_t otp_data[32] = {0}; + + for (int idx = 0; idx < 32; idx++) { + if (ReadOTPWord(idx, &otp_data[idx]) != PX4_OK) { + return PX4_ERROR; + } + + PX4_DEBUG("i: %i, val = %i", idx, otp_data[idx]); + } + + if (RegisterWrite(Register::OTP_CMD, PWR_OFF_OTP) != PX4_OK) { + return PX4_ERROR; + } + + PX4_DEBUG("var_id: %i", (otp_data[30] & 0x7f00) >> 9); + + PX4_DEBUG("UPDATING OFFSETS"); + uint16_t off_x_lsb_msb, off_y_lsb_msb, off_z_lsb_msb, t_off; + uint8_t sens_x, sens_y, sens_z, t_sens; + uint8_t tco_x, tco_y, tco_z; + uint8_t tcs_x, tcs_y, tcs_z; + uint8_t cross_x_y, cross_y_x, cross_z_x, cross_z_y; + + off_x_lsb_msb = otp_data[0x0E] & 0x0FFF; + off_y_lsb_msb = ((otp_data[0x0E] & 0xF000) >> 4) + + (otp_data[0x0F] & 0x00FF); + off_z_lsb_msb = (otp_data[0x0F] & 0x0F00) + + (otp_data[0x10] & 0x00FF); + t_off = otp_data[0x0D] & 0x00FF; + + _mag_comp_vals.dut_offset_coef.offset_x = FixSign(off_x_lsb_msb, 12); + _mag_comp_vals.dut_offset_coef.offset_y = FixSign(off_y_lsb_msb, 12); + _mag_comp_vals.dut_offset_coef.offset_z = FixSign(off_z_lsb_msb, 12); + _mag_comp_vals.dut_offset_coef.t_offs = FixSign(t_off, 8) / 5.0f; + + sens_x = (otp_data[0x10] & 0xFF00) >> 8; + sens_y = (otp_data[0x11] & 0x00FF); + sens_z = (otp_data[0x11] & 0xFF00) >> 8; + t_sens = (otp_data[0x0D] & 0xFF00) >> 8; + + _mag_comp_vals.dut_sensit_coef.sens_x = FixSign(sens_x, 8) / 256.0f; + _mag_comp_vals.dut_sensit_coef.sens_y = (FixSign(sens_y, 8) / 256.0f) + 0.01f; + _mag_comp_vals.dut_sensit_coef.sens_z = FixSign(sens_z, 8) / 256.0f; + _mag_comp_vals.dut_sensit_coef.t_sens = FixSign(t_sens, 8) / 512.0f; + + tco_x = (otp_data[0x12] & 0x00FF); + tco_y = (otp_data[0x13] & 0x00FF); + tco_z = (otp_data[0x14] & 0x00FF); + + _mag_comp_vals.dut_tco.tco_x = FixSign(tco_x, 8) / 32.0f; + _mag_comp_vals.dut_tco.tco_y = FixSign(tco_y, 8) / 32.0f; + _mag_comp_vals.dut_tco.tco_z = FixSign(tco_z, 8) / 32.0f; + + tcs_x = (otp_data[0x12] & 0xFF00) >> 8; + tcs_y = (otp_data[0x13] & 0xFF00) >> 8; + tcs_z = (otp_data[0x14] & 0xFF00) >> 8; + + _mag_comp_vals.dut_tcs.tcs_x = FixSign(tcs_x, 8) / 16384.0f; + _mag_comp_vals.dut_tcs.tcs_y = FixSign(tcs_y, 8) / 16384.0f; + _mag_comp_vals.dut_tcs.tcs_z = (FixSign(tcs_z, 8) / 16384.0f) - 0.0001f; + + _mag_comp_vals.dut_t0 = (FixSign(otp_data[0x18], 16) / 512.0f) + 23.0f; + + cross_x_y = (otp_data[0x15] & 0x00FF); + cross_y_x = (otp_data[0x15] & 0xFF00) >> 8; + cross_z_x = (otp_data[0x16] & 0x00FF); + cross_z_y = (otp_data[0x16] & 0xFF00) >> 8; + + _mag_comp_vals.cross_axis.cross_x_y = FixSign(cross_x_y, 8) / 800.0f; + _mag_comp_vals.cross_axis.cross_y_x = FixSign(cross_y_x, 8) / 800.0f; + _mag_comp_vals.cross_axis.cross_z_x = FixSign(cross_z_x, 8) / 800.0f; + _mag_comp_vals.cross_axis.cross_z_y = FixSign(cross_z_y, 8) / 800.0f; + return PX4_OK; +} + +int BMM350::RegisterRead(Register reg, uint8_t *value) +{ + const uint8_t cmd = static_cast(reg); + uint8_t buffer[3] = {0}; + int ret = transfer(&cmd, 1, buffer, 3); + + if (ret != PX4_OK) { + PX4_DEBUG("register read 0x%02hhX failed, ret = %d", cmd, ret); + + } else { + *value = buffer[2]; + } + + return ret; +} + +int BMM350::RegisterWrite(Register reg, uint8_t value) +{ + uint8_t buffer[2] {(uint8_t)reg, value}; + int ret = transfer(buffer, sizeof(buffer), nullptr, 0); + + if (ret != PX4_OK) { + PX4_DEBUG("register write 0x%02hhX failed, ret = %d", (uint8_t)reg, ret); + } + + return ret; +} diff --git a/src/drivers/magnetometer/bosch/bmm350/BMM350.hpp b/src/drivers/magnetometer/bosch/bmm350/BMM350.hpp new file mode 100644 index 000000000000..4ba7f535dbd9 --- /dev/null +++ b/src/drivers/magnetometer/bosch/bmm350/BMM350.hpp @@ -0,0 +1,210 @@ +/**************************************************************************** + * + * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file BMM350.hpp + * + * Driver for the Bosch BMM350 connected via I2C. + * + */ + +#pragma once + +#include "Bosch_BMM350_registers.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace Bosch_BMM350; +using namespace time_literals; + +class BMM350 : public device::I2C, public I2CSPIDriver, public ModuleParams +{ +public: + BMM350(const I2CSPIDriverConfig &config); + ~BMM350() override; + + static void print_usage(); + + void RunImpl(); + + int init() override; + void print_status() override; + +private: + struct mag_temp_data { + float x; + float y; + float z; + float temp; + }; + + struct raw_mag_data { + int32_t raw_x; + int32_t raw_y; + int32_t raw_z; + int32_t raw_t; + }; + + struct register_config_t { + Register reg; + uint8_t set_bits{0}; + uint8_t clear_bits{0}; + }; + + struct dut_offset_coef { + float t_offs; + float offset_x; + float offset_y; + float offset_z; + }; + struct dut_sensit_coef { + float t_sens; + float sens_x; + float sens_y; + float sens_z; + }; + + struct dut_tco { + float tco_x; + float tco_y; + float tco_z; + }; + + struct dut_tcs { + float tcs_x; + float tcs_y; + float tcs_z; + }; + + struct cross_axis { + float cross_x_y; + float cross_y_x; + float cross_z_x; + float cross_z_y; + }; + + struct mag_compensate_vals { + struct dut_offset_coef dut_offset_coef; + struct dut_sensit_coef dut_sensit_coef; + struct dut_tco dut_tco; + struct dut_tcs dut_tcs; + float dut_t0; + struct cross_axis cross_axis; + }; + + int probe() override; + bool Reset(); + int Configure(); + + int RegisterRead(Register reg, uint8_t *value); + int RegisterWrite(Register reg, uint8_t value); + + int8_t CompensateAxisAndTemp(); + int ReadOutRawData(float *out_data); + int ReadOTPWord(uint8_t addr, uint16_t *lsb_msb); + int32_t FixSign(uint32_t inval, int8_t num_bits); + + int UpdateMagOffsets(); + void ParametersUpdate(bool force = false); + void UpdateMagParams(); + uint8_t GetODR(int value); + hrt_abstime OdrToUs(uint8_t value); + uint8_t GetAVG(int value); + + PX4Magnetometer _px4_mag; + + perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME ": reset")}; + perf_counter_t _bad_read_perf{perf_alloc(PC_COUNT, MODULE_NAME ": bad read")}; + perf_counter_t _self_test_failed_perf{perf_alloc(PC_COUNT, MODULE_NAME ": self test failed")}; + + hrt_abstime _reset_timestamp{0}; + hrt_abstime _last_config_check_timestamp{0}; + + mag_compensate_vals _mag_comp_vals{0}; + + float _initial_self_test_values[4]; + + uint8_t _mag_odr_mode = ODR_200HZ; + uint8_t _mag_avg_mode = AVG_2; + uint8_t _mag_pad_drive = 7; + + + static constexpr float BXY_SENS = 14.55f; + static constexpr float BZ_SENS = 9.0f; + static constexpr float TEMP_SENS = 0.00204f; + static constexpr float INA_XY_GAIN_TRT = 19.46f; + static constexpr float INA_Z_GAIN_TRT = 31.0f; + static constexpr float ADC_GAIN = 1 / 1.5f; + static constexpr float LUT_GAIN = 0.714607238769531f; + static constexpr float POWER = 1000000.0f / 1048576.0f; + float lsb_to_utc_degc[4] = { + (POWER / (BXY_SENS *INA_XY_GAIN_TRT *ADC_GAIN * LUT_GAIN)), + (POWER / (BXY_SENS *INA_XY_GAIN_TRT *ADC_GAIN * LUT_GAIN)), + (POWER / (BZ_SENS *INA_Z_GAIN_TRT *ADC_GAIN * LUT_GAIN)), + 1 / (TEMP_SENS *ADC_GAIN *LUT_GAIN * 1048576) + }; + + enum class STATE : uint8_t { + RESET, + WAIT_FOR_RESET, + FGR, + BR, + AFTER_RESET, + MEASURE_FORCED, + SELF_TEST_CHECK, + CONFIGURE, + READ, + } _state{STATE::RESET}; + + enum class SELF_TEST_STATE : uint8_t { + INIT, + POS_X, + NEG_X, + POS_Y, + NEG_Y + } _self_test_state{SELF_TEST_STATE::INIT}; + + DEFINE_PARAMETERS( + (ParamInt) _param_bmm350_odr, + (ParamInt) _param_bmm350_avg, + (ParamInt) _param_bmm350_drive + ) + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; +}; diff --git a/src/drivers/magnetometer/bosch/bmm350/Bosch_BMM350_registers.hpp b/src/drivers/magnetometer/bosch/bmm350/Bosch_BMM350_registers.hpp new file mode 100644 index 000000000000..dc391f8824aa --- /dev/null +++ b/src/drivers/magnetometer/bosch/bmm350/Bosch_BMM350_registers.hpp @@ -0,0 +1,159 @@ +/**************************************************************************** + * + * Copyright (c) 2020-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. + * + ****************************************************************************/ + +/** + * @file Bosch_BMM350_registers.hpp + * + * Bosch BMM350 registers. + * + */ + +#pragma once + +#include + +namespace Bosch_BMM350 +{ +#define ENABLE_X_AXIS(axis_data) (axis_data = (axis_data & ~(0x01)) | (1 & 0x01)) +#define ENABLE_Y_AXIS(axis_data) (axis_data = ((axis_data & ~(0x02)) | ((1 << 0x1) & 0x02))) +#define ENABLE_Z_AXIS(axis_data) (axis_data = ((axis_data & ~(0x04)) | ((1 << 0x2) & 0x04))) + +static constexpr uint32_t I2C_SPEED = 400 * 1000; +static constexpr uint8_t I2C_ADDRESS_DEFAULT = 0x14; +static constexpr uint8_t chip_identification_number = 0x33; + +enum class Register : uint8_t { + CHIP_ID = 0x00, + + PAD_CTRL = 0x03, + PMU_CMD_AGGR_SET = 0x04, + PMU_CMD_AXIS_EN = 0x05, + PMU_CMD = 0x06, + PMU_STATUS_0 = 0x07, + PMU_STATUS_1 = 0x08, + + I2C_WDT_SET = 0x0a, + + DATAX_XLSB = 0x31, + + OTP_CMD = 0x50, + OTP_DATA_MSB = 0x52, + OTP_DATA_LSB = 0x53, + OTP_STATUS = 0x55, + + TMR_SELF_TEST_USER = 0x60, + CMD = 0x7e +}; + +enum CONTROL_CMD : uint8_t { + SOFT_RESET = 0xb6, + EN_XYZ = 0x7 +}; + +enum PMU_CONTROL_CMD : uint8_t { + PMU_CMD_SUSPEND = 0x00, + PMU_CMD_NM = 0x01, + PMU_CMD_UPDATE_OAE = 0x02, + PMU_CMD_FM = 0x03, + PMU_CMD_FAST_FM = 0x04, + PMU_CMD_FGR = 0x05, + PMU_CMD_FAST_FGR = 0x06, + PMU_CMD_BR = 0x07, + PMU_CMD_BR_FAST = 0x08, + PMU_CMD_NM_TC = 0x09 +}; + +static inline uint8_t PMU_CMD_STATUS_0_RES(uint8_t val) +{ + return (val >> 5) & 0x7; +}; + +enum PMU_STATUS_0_BIT : uint8_t { + PMU_BUSY = (1 << 0), + ODR_OVWR = (1 << 1), + AVG_OVWR = (1 << 2), + PWR_NORMAL = (1 << 3), + ILLEGAL_CMD = (1 << 4) +}; + +enum PMU_STATUS_VALUE { + PMU_STATUS_SUS = 0x0, + PMU_STATUS_NM = 0x1, + PMU_STATUS_UPDATE_OAE = 0x2, + PMU_STATUS_FM = 0x3, + PMU_STATUS_FM_FAST = 0x4, + PMU_STATUS_FGR = 0x5, + PMU_STATUS_FGR_FAST = 0x6, + PMU_STATUS_BR = 0x7, + PMU_STATUS_BR_FAST = 0x7, +}; + +enum ODR_CONTROL_CMD : uint8_t { + ODR_400HZ = 0x2, + ODR_200HZ = 0x3, + ODR_100HZ = 0x4, + ODR_50HZ = 0x5, + ODR_25HZ = 0x6, + ODR_12_5HZ = 0x7, + ODR_6_25HZ = 0x8, + ODR_3_125HZ = 0x9, + ODR_1_5625HZ = 0xa +}; + +enum AVG_CONTROL_CMD : uint8_t { + AVG_NO_AVG = 0x0, + AVG_2 = 0x1, + AVG_4 = 0x2, + AVG_8 = 0x3 +}; + +enum ENABLE_AXIS_BIT : uint8_t { + EN_X = (1 << 0), + EN_Y = (1 << 1), + EN_Z = (1 << 2) +}; + +enum OTP_CONTROL_CMD : uint8_t { + PWR_OFF_OTP = 0x80, + OTP_DIR_READ = 0x20, + OTP_WORD_MSK = 0x1F, +}; + +enum SELF_TEST_CMD : uint8_t { + SELF_TEST_DISABLE = 0x00, + SELF_TEST_POS_X = 0x0d, + SELF_TEST_NEG_X = 0x0b, + SELF_TEST_POS_Y = 0x15, + SELF_TEST_NEG_Y = 0x13, +}; +} // namespace Bosch_BMM350 diff --git a/src/drivers/magnetometer/bosch/bmm350/CMakeLists.txt b/src/drivers/magnetometer/bosch/bmm350/CMakeLists.txt new file mode 100644 index 000000000000..ca253077287e --- /dev/null +++ b/src/drivers/magnetometer/bosch/bmm350/CMakeLists.txt @@ -0,0 +1,48 @@ +############################################################################ +# +# Copyright (c) 2020 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_module( + MODULE drivers__magnetometer__bosch__bmm350 + MAIN bmm350 + COMPILE_FLAGS + SRCS + BMM350.cpp + BMM350.hpp + bmm350_main.cpp + Bosch_BMM350_registers.hpp + DEPENDS + drivers_magnetometer + px4_work_queue + MODULE_CONFIG + module.yaml + ) diff --git a/src/drivers/magnetometer/bosch/bmm350/Kconfig b/src/drivers/magnetometer/bosch/bmm350/Kconfig new file mode 100644 index 000000000000..834a2c694780 --- /dev/null +++ b/src/drivers/magnetometer/bosch/bmm350/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_BOSCH_BMM350 + bool "bmm350" + default n + ---help--- + Enable support for bosch bmm350 diff --git a/src/drivers/magnetometer/bosch/bmm350/bmm350_main.cpp b/src/drivers/magnetometer/bosch/bmm350/bmm350_main.cpp new file mode 100644 index 000000000000..c707d7957b6b --- /dev/null +++ b/src/drivers/magnetometer/bosch/bmm350/bmm350_main.cpp @@ -0,0 +1,89 @@ +/**************************************************************************** + * + * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "BMM350.hpp" + +#include +#include + +void BMM350::print_usage() +{ + PRINT_MODULE_USAGE_NAME("bmm350", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("magnetometer"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false); + PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x14); + PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +extern "C" int bmm350_main(int argc, char *argv[]) +{ + int ch; + using ThisDriver = BMM350; + BusCLIArguments cli{true, false}; + cli.default_i2c_frequency = I2C_SPEED; + cli.i2c_address = I2C_ADDRESS_DEFAULT; + + while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { + switch (ch) { + case 'R': + cli.rotation = (enum Rotation)atoi(cli.optArg()); + break; + } + } + + const char *verb = cli.optArg(); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_BMM350); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; +} diff --git a/src/drivers/magnetometer/bosch/bmm350/module.yaml b/src/drivers/magnetometer/bosch/bmm350/module.yaml new file mode 100644 index 000000000000..140c5c321a8a --- /dev/null +++ b/src/drivers/magnetometer/bosch/bmm350/module.yaml @@ -0,0 +1,44 @@ +module_name: BMM350 +parameters: + - group: Magnetometer + definitions: + BMM350_ODR: + description: + short: BMM350 ODR rate + long: | + Defines which ODR rate to use during data polling. + type: enum + values: + 0: 400 Hz + 1: 200 Hz + 2: 100 Hz + 3: 50 Hz + 4: 25 Hz + 5: 12.5 Hz + 6: 6.25 Hz + 7: 3.125 Hz + 8: 1.5625 Hz + reboot_required: true + default: [3] + BMM350_AVG: + description: + short: BMM350 data averaging + long: | + Defines which averaging mode to use during data polling. + type: enum + values: + 0: No averaging + 1: 2 sample averaging + 2: 4 sample averaging + 3: 8 sample averaging + reboot_required: true + default: [1] + BMM350_DRIVE: + description: + short: BMM350 pad drive strength setting + long: | + This setting helps avoid signal problems like overshoot or undershoot. + type: int32 + min: 0 + max: 7 + default: [7] From f7e6e1354af1df0ab8ef3f0ad169518ad54d1989 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 14 Aug 2024 16:00:33 -0400 Subject: [PATCH 630/652] commander: power check only keep error thresholds --- .../checks/powerCheck.cpp | 20 +++++++------------ 1 file changed, 7 insertions(+), 13 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp index 0b23a949aef6..69afd1c12cce 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp @@ -74,16 +74,10 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) if (!system_power.usb_connected) { float avionics_power_rail_voltage = system_power.voltage5v_v; - const float low_error_threshold = 4.5f; - const float low_warning_threshold = 4.8f; - const float high_warning_threshold = 5.4f; + const float low_error_threshold = 4.7f; + const float high_error_threshold = 5.4f; - if (avionics_power_rail_voltage < low_warning_threshold) { - NavModes affected_groups = NavModes::None; - - if (avionics_power_rail_voltage < low_error_threshold) { - affected_groups = NavModes::All; - } + if (avionics_power_rail_voltage < low_error_threshold) { /* EVENT * @description @@ -93,16 +87,16 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) * This check can be configured via CBRK_SUPPLY_CHK parameter. * */ - reporter.healthFailure(affected_groups, health_component_t::system, + reporter.healthFailure(NavModes::All, health_component_t::system, events::ID("check_avionics_power_low"), - events::Log::Error, "Avionics Power low: {1:.2} Volt", avionics_power_rail_voltage, low_warning_threshold); + events::Log::Error, "Avionics Power low: {1:.2} Volt", avionics_power_rail_voltage, low_error_threshold); if (reporter.mavlink_log_pub()) { mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Avionics Power low: %6.2f Volt", (double)avionics_power_rail_voltage); } - } else if (avionics_power_rail_voltage > high_warning_threshold) { + } else if (avionics_power_rail_voltage > high_error_threshold) { /* EVENT * @description * Check the voltage supply to the FMU, it must be below {2:.2} Volt. @@ -113,7 +107,7 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) */ reporter.healthFailure(NavModes::All, health_component_t::system, events::ID("check_avionics_power_high"), - events::Log::Error, "Avionics Power high: {1:.2} Volt", avionics_power_rail_voltage, high_warning_threshold); + events::Log::Error, "Avionics Power high: {1:.2} Volt", avionics_power_rail_voltage, high_error_threshold); if (reporter.mavlink_log_pub()) { mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Avionics Power high: %6.2f Volt", From 4a3cbecf014475342d00232b6210eb9c1a5183f5 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 14 Aug 2024 14:43:57 +0200 Subject: [PATCH 631/652] Commander: only add *autopilot disengaged* to failsafe notifactions in special cases Signed-off-by: Silvan Fuhrer --- src/modules/commander/failsafe/framework.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 9f88f85f3e8e..1eddc8a7f81c 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -224,6 +224,16 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action {events::Log::Warning, events::LogInternal::Warning}, "Failsafe warning:", mavlink_mode); + } else if (action == Action::Descend || action == Action::FallbackAltCtrl || action == Action::FallbackStab) { + /* EVENT + * @description Failsafe actions that disengage the autopilot (remove position control) + * @type append_health_and_arming_messages + */ + events::send( + events::ID("commander_failsafe_enter_autopilot_disengaged"), + {events::Log::Critical, events::LogInternal::Warning}, + "Failsafe activated: Autopilot disengaged, switching to {2}", mavlink_mode, failsafe_action); + } else { /* EVENT * @type append_health_and_arming_messages @@ -231,7 +241,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::send( events::ID("commander_failsafe_enter_generic"), {events::Log::Critical, events::LogInternal::Warning}, - "Failsafe activated: Autopilot disengaged, switching to {2}", mavlink_mode, failsafe_action); + "Failsafe activated: switching to {2}", mavlink_mode, failsafe_action); } } else { From 09638552b74bdd55e57126c82a427215b34c9985 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 16 Aug 2024 13:57:37 +0200 Subject: [PATCH 632/652] estimatorChecks: disable warning for imminent position failure if that is disabled (#23556) COM_POS_FS_EPH can be set to -1, in which case the actual failure eph is INFINITY. Signed-off-by: Silvan Fuhrer --- .../commander/HealthAndArmingChecks/checks/estimatorCheck.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 888835ba7ef6..2b7c45318301 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -727,7 +727,7 @@ void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_f _last_gpos_fail_time_us, !failsafe_flags.global_position_invalid); // Additional warning if the system is about to enter position-loss failsafe after dead-reckoning period - const float eph_critical = 2.5f * _param_com_pos_fs_eph.get(); // threshold used to trigger the navigation failsafe + const float eph_critical = 2.5f * lpos_eph_threshold; // threshold used to trigger the navigation failsafe const float gpos_critical_warning_thrld = math::max(0.9f * eph_critical, math::max(eph_critical - 10.f, 0.f)); estimator_status_flags_s estimator_status_flags; From 4f66410d24196fbaf62efe1a8c88e66048f6ff7c Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 16 Aug 2024 15:58:36 +0200 Subject: [PATCH 633/652] ROMFS gazebo iris opt flow: increase SENS_FLOW_MAXHGT to 15m (#23557) Signed-off-by: Silvan Fuhrer --- .../init.d-posix/airframes/1010_gazebo-classic_iris_opt_flow | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1010_gazebo-classic_iris_opt_flow b/ROMFS/px4fmu_common/init.d-posix/airframes/1010_gazebo-classic_iris_opt_flow index 38d9019adc70..d334bdb43088 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1010_gazebo-classic_iris_opt_flow +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1010_gazebo-classic_iris_opt_flow @@ -47,5 +47,5 @@ param set-default MPC_ALT_MODE 2 param set-default SENS_FLOW_ROT 6 param set-default SENS_FLOW_MINHGT 0.7 -param set-default SENS_FLOW_MAXHGT 3 +param set-default SENS_FLOW_MAXHGT 15 param set-default SENS_FLOW_MAXR 2.5 From ea673b0b5b945c590e07a88c9fc566f254986d9f Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 13 Aug 2024 09:55:51 +0200 Subject: [PATCH 634/652] navigator: check hagl failsafe centrally --- src/modules/navigator/mission_block.cpp | 26 ++++++++++++++++++++++++ src/modules/navigator/mission_block.h | 6 ++++++ src/modules/navigator/navigator_mode.cpp | 1 + src/modules/navigator/navigator_mode.h | 2 ++ src/modules/navigator/rtl.cpp | 2 ++ src/modules/navigator/rtl_direct.cpp | 10 --------- 6 files changed, 37 insertions(+), 10 deletions(-) diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index f1f202231853..2659ad95cc57 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -1042,3 +1042,29 @@ void MissionBlock::updateAltToAvoidTerrainCollisionAndRepublishTriplet(mission_i _mission_item.altitude_is_relative = false; } } + +void MissionBlock::updateFailsafeChecks() +{ + updateMaxHaglFailsafe(); +} + +void MissionBlock::updateMaxHaglFailsafe() +{ + const float target_alt = _navigator->get_position_setpoint_triplet()->current.alt; + + if (_navigator->get_global_position()->terrain_alt_valid + && ((target_alt - _navigator->get_global_position()->terrain_alt) > _navigator->get_local_position()->hagl_max)) { + // Handle case where the altitude setpoint is above the maximum HAGL (height above ground level) + mavlink_log_info(_navigator->get_mavlink_log_pub(), "Target altitude higher than max HAGL\t"); + events::send(events::ID("navigator_fail_max_hagl"), events::Log::Error, "Target altitude higher than max HAGL"); + + _navigator->trigger_hagl_failsafe(getNavigatorStateId()); + + // While waiting for a failsafe action from commander, keep the curren position + setLoiterItemFromCurrentPosition(&_mission_item); + + mission_item_to_position_setpoint(_mission_item, &_navigator->get_position_setpoint_triplet()->current); + + _navigator->set_position_setpoint_triplet_updated(); + } +} diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h index edc1b0e843f5..c19fcfe11877 100644 --- a/src/modules/navigator/mission_block.h +++ b/src/modules/navigator/mission_block.h @@ -145,6 +145,8 @@ class MissionBlock : public NavigatorMode void set_align_mission_item(struct mission_item_s *const mission_item, const struct mission_item_s *const mission_item_next) const; + void updateFailsafeChecks() override; + protected: /** * @brief heading mode for setting navigation items @@ -249,4 +251,8 @@ class MissionBlock : public NavigatorMode bool _payload_deploy_ack_successful{false}; // Flag to keep track of whether we received an acknowledgement for a successful payload deployment hrt_abstime _payload_deployed_time{0}; // Last payload deployment start time to handle timeouts float _payload_deploy_timeout_s{0.0f}; // Timeout for payload deployment in Mission class, to prevent endless loop if successful deployment ack is never received + +private: + void updateMaxHaglFailsafe(); + }; diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp index 392ca6abb458..1c0882923402 100644 --- a/src/modules/navigator/navigator_mode.cpp +++ b/src/modules/navigator/navigator_mode.cpp @@ -61,6 +61,7 @@ NavigatorMode::run(bool active) } else { /* periodic updates when active */ on_active(); + updateFailsafeChecks(); } } else { diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h index ca418e5b2d9a..9164a92b92fc 100644 --- a/src/modules/navigator/navigator_mode.h +++ b/src/modules/navigator/navigator_mode.h @@ -80,6 +80,8 @@ class NavigatorMode */ virtual void on_active(); + virtual void updateFailsafeChecks() {}; + protected: Navigator *_navigator{nullptr}; diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index 6fef45f9df6e..bb3276b37818 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -283,10 +283,12 @@ void RTL::on_active() case RtlType::RTL_MISSION_FAST_REVERSE: case RtlType::RTL_DIRECT_MISSION_LAND: _rtl_mission_type_handle->on_active(); + _rtl_mission_type_handle->updateFailsafeChecks(); break; case RtlType::RTL_DIRECT: _rtl_direct.on_active(); + _rtl_direct.updateFailsafeChecks(); break; default: diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index f26df56530d2..145b99d0d1db 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -158,16 +158,6 @@ void RtlDirect::set_rtl_item() { position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); - if (_global_pos_sub.get().terrain_alt_valid - && ((_rtl_alt - _global_pos_sub.get().terrain_alt) > _navigator->get_local_position()->hagl_max)) { - // Handle case where the RTL altidude is above the maximum HAGL and land in place instead of RTL - mavlink_log_info(_navigator->get_mavlink_log_pub(), "RTL: return alt higher than max HAGL\t"); - events::send(events::ID("rtl_fail_max_hagl"), events::Log::Error, "RTL: return alt higher than max HAGL"); - - _navigator->trigger_hagl_failsafe(getNavigatorStateId()); - _rtl_state = RTLState::IDLE; - } - const float destination_dist = get_distance_to_next_waypoint(_destination.lat, _destination.lon, _global_pos_sub.get().lat, _global_pos_sub.get().lon); const float loiter_altitude = math::min(_land_approach.height_m, _rtl_alt); From ad1d9e13128b433a0d7909050b2fec590951c4f7 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 16 Aug 2024 14:05:06 +0200 Subject: [PATCH 635/652] failsafe: do not add additional hold delay if failsafe action is hold --- src/modules/commander/failsafe/framework.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 1eddc8a7f81c..729205ebe89e 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -477,7 +477,7 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s // Check if we should enter delayed Hold if (_current_delay > 0 && !_user_takeover_active && allow_user_takeover <= UserTakeoverAllowed::AlwaysModeSwitchOnly - && selected_action != Action::Disarm && selected_action != Action::Terminate) { + && selected_action != Action::Disarm && selected_action != Action::Terminate && selected_action != Action::Hold) { returned_state.delayed_action = selected_action; selected_action = Action::Hold; allow_user_takeover = UserTakeoverAllowed::AlwaysModeSwitchOnly; From ea0ef154d8d4a718ab07629f7477144247885e79 Mon Sep 17 00:00:00 2001 From: Vilius Date: Sat, 17 Aug 2024 22:59:18 +0300 Subject: [PATCH 636/652] Fixes upload.sh for arkv6x (#23561) --- Tools/upload.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/upload.sh b/Tools/upload.sh index 25d41e389f76..2a6416ed374d 100755 --- a/Tools/upload.sh +++ b/Tools/upload.sh @@ -15,7 +15,7 @@ SERIAL_PORTS="/dev/tty.usbmodemPX*,/dev/tty.usbmodem*" fi if [ $SYSTYPE = "Linux" ]; then -SERIAL_PORTS="/dev/serial/by-id/*_PX4_*,/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/usb-The_Autopilot*,/dev/serial/by-id/usb-Bitcraze*,/dev/serial/by-id/pci-Bitcraze*,/dev/serial/by-id/usb-Gumstix*,/dev/serial/by-id/usb-UVify*,/dev/serial/by-id/usb-ArduPilot*,/dev/serial/by-id/ARK*," +SERIAL_PORTS="/dev/serial/by-id/*_PX4_*,/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/usb-The_Autopilot*,/dev/serial/by-id/usb-Bitcraze*,/dev/serial/by-id/pci-Bitcraze*,/dev/serial/by-id/usb-Gumstix*,/dev/serial/by-id/usb-UVify*,/dev/serial/by-id/usb-ArduPilot*,/dev/serial/by-id/usb-ARK*," fi if [[ $SYSTYPE = *"CYGWIN"* ]]; then From 435e9665b31f51478b81c05a5e5bc4f348d49e8c Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 19 Aug 2024 07:51:33 +0200 Subject: [PATCH 637/652] RTL: cone: never climb more than to RTL_RETURN_ALT (#23558) This is to prevent that a large NAV_ACC_RAD leads to very high return altitudes. Signed-off-by: Silvan Fuhrer --- src/modules/navigator/rtl.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index bb3276b37818..63e2ab185ff1 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -530,13 +530,14 @@ float RTL::calculate_return_alt_from_cone_half_angle(const PositionYawSetpoint & // avoid the vehicle touching the ground while still moving horizontally. const float return_altitude_min_outside_acceptance_rad_amsl = rtl_position.alt + 2.0f * _param_nav_acc_rad.get(); - float return_altitude_amsl = rtl_position.alt + _param_rtl_return_alt.get(); + const float max_return_altitude = rtl_position.alt + _param_rtl_return_alt.get(); + + float return_altitude_amsl = max_return_altitude; if (destination_dist <= _param_nav_acc_rad.get()) { return_altitude_amsl = rtl_position.alt + 2.0f * destination_dist; } else { - if (destination_dist <= _param_rtl_min_dist.get()) { // constrain cone half angle to meaningful values. All other cases are already handled above. @@ -551,7 +552,7 @@ float RTL::calculate_return_alt_from_cone_half_angle(const PositionYawSetpoint & return_altitude_amsl = max(return_altitude_amsl, return_altitude_min_outside_acceptance_rad_amsl); } - return max(return_altitude_amsl, _global_pos_sub.get().alt); + return constrain(return_altitude_amsl, _global_pos_sub.get().alt, max_return_altitude); } void RTL::init_rtl_mission_type() From e29a36adb46aed60e1166860ebb490400d962d96 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Mon, 19 Aug 2024 08:01:43 +0200 Subject: [PATCH 638/652] Landing horizontal velocity compensation / unsteady landing (#23546) * initial working * implemented feedback --- .../flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp | 2 +- src/modules/navigator/land.cpp | 7 ++++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index dad05e3c31db..b2bb5632b7bf 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -452,7 +452,7 @@ bool FlightTaskAuto::_evaluateTriplets() _triplet_prev_wp(2) = -(_sub_triplet_setpoint.get().previous.alt - _reference_altitude); } else { - _triplet_prev_wp = _position; + _triplet_prev_wp = _triplet_target; } _prev_was_valid = _sub_triplet_setpoint.get().previous.valid; diff --git a/src/modules/navigator/land.cpp b/src/modules/navigator/land.cpp index 74f54fbb079a..8277378a6670 100644 --- a/src/modules/navigator/land.cpp +++ b/src/modules/navigator/land.cpp @@ -57,8 +57,13 @@ Land::on_activation() /* convert mission item to current setpoint */ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); - pos_sp_triplet->previous.valid = false; + + if (_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) { + _navigator->calculate_breaking_stop(_mission_item.lat, _mission_item.lon); + } + mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current); + pos_sp_triplet->previous.valid = false; pos_sp_triplet->next.valid = false; _navigator->set_position_setpoint_triplet_updated(); From 7e45f4915208b2d02e05e5741ff7456cf92120f9 Mon Sep 17 00:00:00 2001 From: jmackay2 <1.732mackay@gmail.com> Date: Mon, 19 Aug 2024 02:54:57 -0400 Subject: [PATCH 639/652] Update GZBridge to be able to use gazebo airspeed. Add quadtailsitter. (#23455) * Update GZBridge to be able to use gazebo airspeed. Add gz quadtailsitter. * Fix formatting --------- Co-authored-by: jmackay2 --- .../1045_gazebo-classic_quadtailsitter | 2 +- .../airframes/4004_gz_standard_vtol | 2 - .../airframes/4014_gz_quadtailsitter | 92 +++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + src/modules/simulation/gz_bridge/GZBridge.cpp | 16 ++-- src/modules/simulation/gz_bridge/GZBridge.hpp | 4 +- .../sensor_airspeed_sim/SensorAirspeedSim.cpp | 2 +- 7 files changed, 103 insertions(+), 16 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter index 87afb523b1a7..9539ba6d7402 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter @@ -33,7 +33,7 @@ param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 param set-default PWM_MAIN_FUNC5 0 -parm set-default FD_FAIL_R 70 +param set-default FD_FAIL_R 70 param set-default FW_P_TC 0.6 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 96bb25d69a52..580b6da368de 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -14,9 +14,7 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol} param set-default SIM_GZ_EN 1 param set-default SENS_EN_GPSSIM 1 -param set-default SENS_EN_BAROSIM 0 param set-default SENS_EN_MAGSIM 1 -param set-default SENS_EN_ARSPDSIM 1 # TODO: Enable motor failure detection when the # VTOL no longer reports 0A for all ESCs in SITL diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter new file mode 100644 index 000000000000..699d1dacc521 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter @@ -0,0 +1,92 @@ +#!/bin/sh +# +# @name Quadrotor + Tailsitter +# +# @type VTOL Quad Tailsitter +# + +. ${R}etc/init.d/rc.vtol_defaults + +PX4_SIMULATOR=${PX4_SIMULATOR:=gz} +PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} +PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadtailsitter} + +param set-default SIM_GZ_EN 1 + +param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 0 +param set-default SENS_EN_MAGSIM 1 +param set-default SENS_EN_ARSPDSIM 0 + +param set-default MAV_TYPE 20 + +param set-default CA_AIRFRAME 4 + +param set-default CA_ROTOR_COUNT 4 +param set-default CA_ROTOR0_PX 0.15 +param set-default CA_ROTOR0_PY 0.23 +param set-default CA_ROTOR0_KM 0.05 +param set-default CA_ROTOR1_PX -0.15 +param set-default CA_ROTOR1_PY -0.23 +param set-default CA_ROTOR1_KM 0.05 +param set-default CA_ROTOR2_PX 0.15 +param set-default CA_ROTOR2_PY -0.23 +param set-default CA_ROTOR2_KM -0.05 +param set-default CA_ROTOR3_PX -0.15 +param set-default CA_ROTOR3_PY 0.23 +param set-default CA_ROTOR3_KM -0.05 + +param set-default CA_SV_CS_COUNT 0 + +param set-default SIM_GZ_EC_FUNC1 101 +param set-default SIM_GZ_EC_MIN1 10 +param set-default SIM_GZ_EC_MAX1 1500 +param set-default SIM_GZ_EC_FUNC2 102 +param set-default SIM_GZ_EC_MIN2 10 +param set-default SIM_GZ_EC_MAX2 1500 +param set-default SIM_GZ_EC_FUNC3 103 +param set-default SIM_GZ_EC_MIN3 10 +param set-default SIM_GZ_EC_MAX3 1500 +param set-default SIM_GZ_EC_FUNC4 104 +param set-default SIM_GZ_EC_MIN4 10 +param set-default SIM_GZ_EC_MAX4 1500 + +param set-default FD_FAIL_R 70 + +param set-default FW_P_TC 0.6 + +param set-default FW_PR_I 0.3 +param set-default FW_PR_P 0.5 +param set-default FW_PSP_OFF 2 +param set-default FW_RR_FF 0.1 +param set-default FW_RR_I 0.1 +param set-default FW_RR_P 0.2 +param set-default FW_YR_FF 0 # make yaw rate controller very weak, only keep default P +param set-default FW_YR_I 0 +param set-default FW_THR_TRIM 0.35 +param set-default FW_THR_MAX 0.8 +param set-default FW_THR_MIN 0.05 +param set-default FW_T_CLMB_MAX 6 +param set-default FW_T_HRATE_FF 0.5 +param set-default FW_T_SINK_MAX 3 +param set-default FW_T_SINK_MIN 1.6 +param set-default FW_AIRSPD_STALL 10 +param set-default FW_AIRSPD_MIN 14 +param set-default FW_AIRSPD_TRIM 18 +param set-default FW_AIRSPD_MAX 22 + +param set-default MC_AIRMODE 2 +param set-default MAN_ARM_GESTURE 0 # required for yaw airmode +param set-default MC_ROLL_P 3 +param set-default MC_PITCH_P 3 +param set-default MC_ROLLRATE_P 0.3 +param set-default MC_PITCHRATE_P 0.3 + +param set-default VT_ARSP_TRANS 15 +param set-default VT_B_TRANS_DUR 5 +param set-default VT_FW_DIFTHR_EN 7 +param set-default VT_FW_DIFTHR_S_Y 1 +param set-default VT_F_TRANS_DUR 1.5 +param set-default VT_TYPE 0 + +param set-default WV_EN 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 9235b2e66340..badd712b063f 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_quadtailsitter 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 3464c628694c..6b4042da8bb3 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -203,17 +203,15 @@ int GZBridge::init() PX4_WARN("failed to subscribe to %s", laser_scan_topic.c_str()); } -#if 0 - // Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed - std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name + - "/link/airspeed_link/sensor/air_speed/air_speed"; + // Airspeed: /world/$WORLD/model/$MODEL/link/base_link/sensor/airspeed_sensor/air_speed + std::string airspeed_topic = "/world/" + _world_name + "/model/" + _model_name + + "/link/base_link/sensor/airspeed_sensor/air_speed"; - if (!_node.Subscribe(airpressure_topic, &GZBridge::airspeedCallback, this)) { - PX4_ERR("failed to subscribe to %s", airpressure_topic.c_str()); + if (!_node.Subscribe(airspeed_topic, &GZBridge::airspeedCallback, this)) { + PX4_ERR("failed to subscribe to %s", airspeed_topic.c_str()); return PX4_ERROR; } -#endif // Air pressure: /world/$WORLD/model/$MODEL/link/base_link/sensor/air_pressure_sensor/air_pressure std::string air_pressure_topic = "/world/" + _world_name + "/model/" + _model_name + "/link/base_link/sensor/air_pressure_sensor/air_pressure"; @@ -426,8 +424,7 @@ void GZBridge::barometerCallback(const gz::msgs::FluidPressure &air_pressure) pthread_mutex_unlock(&_node_mutex); } -#if 0 -void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed) +void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed) { if (hrt_absolute_time() == 0) { return; @@ -452,7 +449,6 @@ void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed) pthread_mutex_unlock(&_node_mutex); } -#endif void GZBridge::imuCallback(const gz::msgs::IMU &imu) { diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index 8a832f7961b2..824c7d471633 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -102,7 +102,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void clockCallback(const gz::msgs::Clock &clock); - // void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure); + void airspeedCallback(const gz::msgs::AirSpeed &air_speed); void barometerCallback(const gz::msgs::FluidPressure &air_pressure); void imuCallback(const gz::msgs::IMU &imu); void poseInfoCallback(const gz::msgs::Pose_V &pose); @@ -123,7 +123,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S // Subscriptions uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; - //uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; + uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; uORB::Publication _obstacle_distance_pub{ORB_ID(obstacle_distance)}; uORB::Publication _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)}; uORB::Publication _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)}; diff --git a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp index 7b0d9556cadf..86fbbf29cd4c 100644 --- a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp +++ b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp @@ -195,7 +195,7 @@ int SensorAirspeedSim::print_usage(const char *reason) )DESCR_STR"); - PRINT_MODULE_USAGE_NAME("sensor_arispeed_sim", "system"); + PRINT_MODULE_USAGE_NAME("sensor_airspeed_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); From 4d21110cfb938455b21ad16c8463291094e9ec39 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Mon, 19 Aug 2024 13:36:04 +0200 Subject: [PATCH 640/652] Documentation - improved GCS parameter readablity (#23376) improved GCS parameter description Co-authored-by: Hamish Willee Co-authored-by: Silvan Fuhrer --- .../mc_pos_control/multicopter_altitude_mode_params.c | 2 +- .../mc_pos_control/multicopter_autonomous_params.c | 2 +- .../mc_pos_control/multicopter_position_mode_params.c | 11 +++++++---- 3 files changed, 9 insertions(+), 6 deletions(-) diff --git a/src/modules/mc_pos_control/multicopter_altitude_mode_params.c b/src/modules/mc_pos_control/multicopter_altitude_mode_params.c index 3f654fade71a..9174b1ef0d83 100644 --- a/src/modules/mc_pos_control/multicopter_altitude_mode_params.c +++ b/src/modules/mc_pos_control/multicopter_altitude_mode_params.c @@ -95,7 +95,7 @@ PARAM_DEFINE_INT32(MPC_ALT_MODE, 2); /** * Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) * - * Only used with MPC_POS_MODE 0 or MPC_ALT_MODE 2 + * Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2 * * @unit m/s * @min 0 diff --git a/src/modules/mc_pos_control/multicopter_autonomous_params.c b/src/modules/mc_pos_control/multicopter_autonomous_params.c index 8c97e779be32..e2e453d975ed 100644 --- a/src/modules/mc_pos_control/multicopter_autonomous_params.c +++ b/src/modules/mc_pos_control/multicopter_autonomous_params.c @@ -76,7 +76,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_DN, 1.5f); /** * Acceleration for autonomous and for manual modes * - * When piloting manually, this parameter is only used in MPC_POS_MODE 4. + * When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based. * * @unit m/s^2 * @min 2 diff --git a/src/modules/mc_pos_control/multicopter_position_mode_params.c b/src/modules/mc_pos_control/multicopter_position_mode_params.c index 56adad1144bf..a65ef4f5713d 100644 --- a/src/modules/mc_pos_control/multicopter_position_mode_params.c +++ b/src/modules/mc_pos_control/multicopter_position_mode_params.c @@ -35,12 +35,15 @@ * Position/Altitude mode variant * * The supported sub-modes are: - * 0 Sticks directly map to velocity setpoints without smoothing. + * - "Direct velocity": + * Sticks directly map to velocity setpoints without smoothing. * Also applies to vertical direction and Altitude mode. * Useful for velocity control tuning. - * 3 Sticks map to velocity but with maximum acceleration and jerk limits based on + * - "Smoothed velocity": + * Sticks map to velocity but with maximum acceleration and jerk limits based on * jerk optimized trajectory generator (different algorithm than 1). - * 4 Sticks map to acceleration and there's a virtual brake drag + * - "Acceleration based": + * Sticks map to acceleration and there's a virtual brake drag * * @value 0 Direct velocity * @value 3 Smoothed velocity @@ -122,7 +125,7 @@ PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.f); * * Setting this to the maximum value essentially disables the limit. * - * Only used with smooth MPC_POS_MODE 3 and 4. + * Only used with smooth MPC_POS_MODE Smoothed velocity and Acceleration based. * * @unit m/s^3 * @min 0.5 From 0481c04b2b274306d9505c00207c36ab26733dd9 Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Thu, 15 Aug 2024 12:51:24 -0600 Subject: [PATCH 641/652] Nuttx with backport (stm32h7x3x): Add External Power Supply option --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 5d74bc138955..39bb38d82b12 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 5d74bc138955e6f010a38e0f87f34e9a9019aecc +Subproject commit 39bb38d82b128a57d0ca40c25ba3ad6601ec0a83 From 746ae257689610f7d244e8c7c791450f9394a47d Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 19 Aug 2024 07:41:25 -0700 Subject: [PATCH 642/652] ci: replace build workflows (#23550) --- .editorconfig | 2 +- .github/workflows/build_all_targets.yml | 83 +++++++++++ .github/workflows/compile_linux.yml | 58 -------- .github/workflows/compile_linux_arm64.yml | 54 ------- .github/workflows/compile_nuttx.yml | 137 ----------------- Tools/ci_build_all_runner.sh | 19 +++ Tools/generate_board_targets_json.py | 170 +++++++++++++++++++++- 7 files changed, 268 insertions(+), 255 deletions(-) create mode 100644 .github/workflows/build_all_targets.yml delete mode 100644 .github/workflows/compile_linux.yml delete mode 100644 .github/workflows/compile_linux_arm64.yml delete mode 100644 .github/workflows/compile_nuttx.yml create mode 100755 Tools/ci_build_all_runner.sh diff --git a/.editorconfig b/.editorconfig index 683f0fdc5159..1ac25a4f5860 100644 --- a/.editorconfig +++ b/.editorconfig @@ -9,6 +9,6 @@ tab_width = 8 # Not in the official standard, but supported by many editors max_line_length = 120 -[*.yaml] +[*.yaml, *.yml] indent_style = space indent_size = 2 diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml new file mode 100644 index 000000000000..119236b3198e --- /dev/null +++ b/.github/workflows/build_all_targets.yml @@ -0,0 +1,83 @@ +name: Build all targets + +on: + push: + branches: + - 'main' + - 'stable' + - 'beta' + - 'release/*' + pull_request: + branches: + - '*' + +jobs: + group_targets: + name: Scan for Board Targets + runs-on: ubuntu-latest + outputs: + matrix: ${{ steps.set-matrix.outputs.matrix }} + timestamp: ${{ steps.set-timestamp.outputs.timestamp }} + steps: + - uses: actions/checkout@v4 + + - name: Install Python Dependencies + uses: py-actions/py-dependency-install@v4 + with: + path: "./Tools/setup/requirements.txt" + + - id: set-matrix + run: echo "::set-output name=matrix::$(./Tools/generate_board_targets_json.py --group)" + + - id: set-timestamp + run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")" + + setup: + name: ${{ matrix.group }} + runs-on: ubuntu-latest + needs: group_targets + strategy: + matrix: ${{ fromJson(needs.group_targets.outputs.matrix) }} + container: + image: ${{ matrix.container }} + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + + - name: ownership workaround + run: git config --system --add safe.directory '*' + + - name: ccache setup keys + uses: actions/cache@v4 + with: + path: ~/.ccache + key: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} + restore-keys: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} + + - name: setup ccache + run: | + mkdir -p ~/.ccache + echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf + echo "compression = true" >> ~/.ccache/ccache.conf + echo "compression_level = 6" >> ~/.ccache/ccache.conf + echo "max_size = 120M" >> ~/.ccache/ccache.conf + echo "hash_dir = false" >> ~/.ccache/ccache.conf + ccache -s + ccache -z + + - name: build target group + run: | + ./Tools/ci_build_all_runner.sh ${{matrix.targets}} + + - name: Upload px4 package + uses: actions/upload-artifact@v4 + with: + name: px4_${{matrix.group}}_build_artifacts + path: | + build/**/*.px4 + build/**/*.bin + compression-level: 0 + + - name: ccache post-run + run: ccache -s diff --git a/.github/workflows/compile_linux.yml b/.github/workflows/compile_linux.yml deleted file mode 100644 index 23e46deab7f3..000000000000 --- a/.github/workflows/compile_linux.yml +++ /dev/null @@ -1,58 +0,0 @@ -name: Compile Linux Targets - -on: - push: - branches: - - 'main' - - 'stable' - - 'beta' - - 'release/*' - pull_request: - branches: - - '*' - -jobs: - build: - runs-on: ubuntu-latest - container: px4io/px4-dev-armhf:2023-06-26 - strategy: - matrix: - config: [ - beaglebone_blue_default, - emlid_navio2_default, - px4_raspberrypi_default, - scumaker_pilotpi_default, - ] - steps: - - uses: actions/checkout@v1 - with: - token: ${{secrets.ACCESS_TOKEN}} - - name: ownership workaround - run: git config --system --add safe.directory '*' - - name: Prepare ccache timestamp - id: ccache_cache_timestamp - shell: cmake -P {0} - run: | - string(TIMESTAMP current_date "%Y-%m-%d-%H;%M;%S" UTC) - message("::set-output name=timestamp::${current_date}") - - name: ccache cache files - uses: actions/cache@v2 - with: - path: ~/.ccache - key: ${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: ${{matrix.config}}-ccache- - - name: setup ccache - run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 100M" >> ~/.ccache/ccache.conf - echo "hash_dir = false" >> ~/.ccache/ccache.conf - ccache -s - ccache -z - - - name: make ${{matrix.config}} - run: make ${{matrix.config}} - - name: ccache post-run - run: ccache -s diff --git a/.github/workflows/compile_linux_arm64.yml b/.github/workflows/compile_linux_arm64.yml deleted file mode 100644 index 5c1c318b411e..000000000000 --- a/.github/workflows/compile_linux_arm64.yml +++ /dev/null @@ -1,54 +0,0 @@ -name: Compile Linux ARM64 Targets - -on: - push: - branches: - - 'main' - - 'stable' - - 'beta' - - 'release/*' - pull_request: - branches: - - '*' - -jobs: - build: - runs-on: ubuntu-latest - container: px4io/px4-dev-aarch64:2022-08-12 - strategy: - matrix: - config: [ - scumaker_pilotpi_arm64, - ] - steps: - - uses: actions/checkout@v1 - with: - token: ${{secrets.ACCESS_TOKEN}} - - - name: Prepare ccache timestamp - id: ccache_cache_timestamp - shell: cmake -P {0} - run: | - string(TIMESTAMP current_date "%Y-%m-%d-%H;%M;%S" UTC) - message("::set-output name=timestamp::${current_date}") - - name: ccache cache files - uses: actions/cache@v2 - with: - path: ~/.ccache - key: ${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: ${{matrix.config}}-ccache- - - name: setup ccache - run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 100M" >> ~/.ccache/ccache.conf - echo "hash_dir = false" >> ~/.ccache/ccache.conf - ccache -s - ccache -z - - - name: make ${{matrix.config}} - run: make ${{matrix.config}} - - name: ccache post-run - run: ccache -s diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml deleted file mode 100644 index cc44c55ea252..000000000000 --- a/.github/workflows/compile_nuttx.yml +++ /dev/null @@ -1,137 +0,0 @@ -name: Compile Nuttx Targets - -on: - push: - branches: - - 'main' - - 'stable' - - 'beta' - - 'release/*' - pull_request: - branches: - - '*' - -jobs: - build: - runs-on: ubuntu-latest - container: px4io/px4-dev-nuttx-focal:2022-08-12 - strategy: - fail-fast: false - matrix: - config: [ - 3dr_ctrl-zero-h7-oem-revg, - airmind_mindpx-v2, - ark_can-flow, - ark_can-gps, - ark_can-rtk-gps, - ark_cannode, - ark_fmu-v6x, - ark_pi6x, - ark_septentrio-gps, - atl_mantis-edu, - av_x-v1, - bitcraze_crazyflie, - bitcraze_crazyflie21, - cuav_can-gps-v1, - cuav_nora, - cuav_x7pro, - cubepilot_cubeorange, - cubepilot_cubeorangeplus, - cubepilot_cubeyellow, - diatone_mamba-f405-mk2, - freefly_can-rtk-gps, - holybro_can-gps-v1, - holybro_durandal-v1, - holybro_kakutef7, - holybro_kakuteh7, - holybro_pix32v5, - matek_gnss-m9n-f4, - matek_h743, - matek_h743-mini, - matek_h743-slim, - modalai_fc-v1, - modalai_fc-v2, - mro_ctrl-zero-classic, - mro_ctrl-zero-f7, - mro_ctrl-zero-f7-oem, - mro_ctrl-zero-h7, - mro_ctrl-zero-h7-oem, - mro_pixracerpro, - mro_x21, - mro_x21-777, - nxp_fmuk66-e, - nxp_fmuk66-v3, - nxp_mr-canhubk3, - nxp_ucans32k146, - omnibus_f4sd, - px4_fmu-v2, - px4_fmu-v3, - px4_fmu-v4, - px4_fmu-v4pro, - px4_fmu-v5, - px4_fmu-v5x, - px4_fmu-v6c, - px4_fmu-v6u, - px4_fmu-v6x, - px4_fmu-v6xrt, - raspberrypi_pico, - sky-drones_smartap-airlink, - spracing_h7extreme, - uvify_core, - siyi_n7 - ] - steps: - - uses: actions/checkout@v1 - with: - token: ${{secrets.ACCESS_TOKEN}} - - - name: Prepare ccache timestamp - id: ccache_cache_timestamp - shell: cmake -P {0} - run: | - string(TIMESTAMP current_date "%Y-%m-%d-%H;%M;%S" UTC) - message("::set-output name=timestamp::${current_date}") - - name: ccache cache files - uses: actions/cache@v2 - with: - path: ~/.ccache - key: ${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: ${{matrix.config}}-ccache- - - name: setup ccache - run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 120M" >> ~/.ccache/ccache.conf - echo "hash_dir = false" >> ~/.ccache/ccache.conf - ccache -s - ccache -z - - - name: make all_variants_${{matrix.config}} - run: make all_variants_${{matrix.config}} - timeout-minutes: 45 - - name: make ${{matrix.config}} bloaty_compileunits - run: make ${{matrix.config}} bloaty_compileunits || true - - name: make ${{matrix.config}} bloaty_inlines - run: make ${{matrix.config}} bloaty_inlines || true - - name: make ${{matrix.config}} bloaty_segments - run: make ${{matrix.config}} bloaty_segments || true - - name: make ${{matrix.config}} bloaty_symbols - run: make ${{matrix.config}} bloaty_symbols || true - - name: make ${{matrix.config}} bloaty_templates - run: make ${{matrix.config}} bloaty_templates || true - - name: make ${{matrix.config}} bloaty_ram - run: make ${{matrix.config}} bloaty_ram || true - - name: make ${{matrix.config}} bloaty_compare_master - run: make ${{matrix.config}} bloaty_compare_master || true - - name: ccache post-run - run: ccache -s - - - name: Upload px4 package - uses: actions/upload-artifact@v2 - with: - name: px4_package_${{matrix.config}} - path: | - build/**/*.px4 - build/**/*.bin diff --git a/Tools/ci_build_all_runner.sh b/Tools/ci_build_all_runner.sh new file mode 100755 index 000000000000..bfb77e2623a9 --- /dev/null +++ b/Tools/ci_build_all_runner.sh @@ -0,0 +1,19 @@ +#!/bin/bash +# This script is meant to be used by the build_all.yml workflow in a github runner +# Please only modify if you know what you are doing +set -e + +echo "### :clock1: Build Times" >> $GITHUB_STEP_SUMMARY +targets=$1 +for target in ${targets//,/ } +do + echo "::group::Building: [${target}]" + start=$(date +%s) + make $target + stop=$(date +%s) + diff=$(($stop-$start)) + build_time="$(($diff /60/60))h $(($diff /60))m $(($diff % 60))s elapsed" + echo -e "\033[0;32mBuild Time: [$build_time]" + echo "* **$target** - $build_time" >> $GITHUB_STEP_SUMMARY + echo "::endgroup::" +done diff --git a/Tools/generate_board_targets_json.py b/Tools/generate_board_targets_json.py index 931d5c14776f..649b3fceefa6 100755 --- a/Tools/generate_board_targets_json.py +++ b/Tools/generate_board_targets_json.py @@ -23,11 +23,14 @@ help='Verbose Output') parser.add_argument('-p', '--pretty', dest='pretty', action='store_true', help='Pretty output instead of a single line') +parser.add_argument('-g', '--groups', dest='group', action='store_true', + help='Groups targets') args = parser.parse_args() verbose = args.verbose build_configs = [] +grouped_targets = {} excluded_boards = ['modalai_voxl2', 'px4_ros2'] # TODO: fix and enable excluded_manufacturers = ['atlflight'] excluded_platforms = ['qurt'] @@ -37,10 +40,27 @@ 'uavcanv1', # TODO: fix and enable ] +github_action_config = { 'include': build_configs } +extra_args = {} +if args.pretty: + extra_args['indent'] = 2 + +def chunks(arr, size): + # splits array into parts + for i in range(0, len(arr), size): + yield arr[i:i + size] + +def comma_targets(targets): + # turns array of targets into a comma split string + return ",".join(targets) + def process_target(px4board_file, target_name): + # reads through the board file and grabs + # useful information for building ret = None platform = None toolchain = None + group = None if px4board_file.endswith("default.px4board") or \ px4board_file.endswith("recovery.px4board") or \ @@ -63,22 +83,34 @@ def process_target(px4board_file, target_name): # get the container based on the platform and toolchain if platform == 'posix': container = 'px4io/px4-dev-base-focal:2021-09-08' + group = 'base' if toolchain: if toolchain.startswith('aarch64'): container = 'px4io/px4-dev-aarch64:2022-08-12' + group = 'aarch64' elif toolchain == 'arm-linux-gnueabihf': container = 'px4io/px4-dev-armhf:2023-06-26' + group = 'armhf' else: if verbose: print(f'unmatched toolchain: {toolchain}') elif platform == 'nuttx': container = 'px4io/px4-dev-nuttx-focal:2022-08-12' + group = 'nuttx' else: if verbose: print(f'unmatched platform: {platform}') ret = {'target': target_name, 'container': container} + if(args.group): + ret['arch'] = group return ret +# Look for board targets in the ./boards directory +if(verbose): + print("=======================") + print("= scanning for boards =") + print("=======================") + for manufacturer in os.scandir(os.path.join(source_dir, 'boards')): if not manufacturer.is_dir(): continue @@ -105,12 +137,140 @@ def process_target(px4board_file, target_name): if verbose: print(f'excluding label {label} ({target_name})') continue target = process_target(files.path, target_name) + if (args.group and target is not None): + if (target['arch'] not in grouped_targets): + grouped_targets[target['arch']] = {} + grouped_targets[target['arch']]['container'] = target['container'] + grouped_targets[target['arch']]['manufacturers'] = {} + if(manufacturer.name not in grouped_targets[target['arch']]['manufacturers']): + grouped_targets[target['arch']]['manufacturers'][manufacturer.name] = {} + grouped_targets[target['arch']]['manufacturers'][manufacturer.name] = [] + grouped_targets[target['arch']]['manufacturers'][manufacturer.name].append(target_name) if target is not None: build_configs.append(target) +if(verbose): + import pprint + print("============================") + print("= Boards found in ./boards =") + print("============================") + pprint.pp(grouped_targets) -github_action_config = { 'include': build_configs } -extra_args = {} -if args.pretty: - extra_args['indent'] = 2 -print(json.dumps(github_action_config, **extra_args)) +if (args.group): + # if we are using this script for grouping builds + # we loop trough the manufacturers list and split their targets + # if a manufacturer has more than a LIMIT of boards then we split that + # into sub groups such as "arch-manufacturer name-index" + # example: + # nuttx-px4-0 + # nuttx-px4-1 + # nuttx-px4-2 + # nuttx-ark-0 + # nuttx-ark-1 + # if the manufacturer doesn't have more targets than LIMIT then we add + # them to a generic group with the following structure "arch-index" + # example: + # nuttx-0 + # nuttx-1 + final_groups = [] + temp_group = [] + group_number = {} + last_man = '' + last_arch = '' + SPLIT_LIMIT = 10 + LOWER_LIMIT = 5 + for arch in grouped_targets: + if(last_arch == ''): + last_arch = arch + if(arch not in group_number): + group_number[arch] = 0 + + if(last_arch != arch and len(temp_group) > 0): + group_name = last_arch + "-" + str(group_number[last_arch]) + group_number[last_arch] += 1 + targets = comma_targets(temp_group) + final_groups.append({ + "container": grouped_targets[last_arch]['container'], + "targets": targets, + "arch": last_arch, + "group": group_name, + "len": len(temp_group) + }) + last_arch = arch + temp_group = [] + for man in grouped_targets[arch]['manufacturers']: + for tar in grouped_targets[arch]['manufacturers'][man]: + if(last_man != man): + man_len = len(grouped_targets[arch]['manufacturers'][man]) + if(man_len > LOWER_LIMIT and man_len < (SPLIT_LIMIT + 1)): + # Manufacturers can have their own group + group_name = arch + "-" + man + targets = comma_targets(grouped_targets[arch]['manufacturers'][man]) + last_man = man + final_groups.append({ + "container": grouped_targets[arch]['container'], + "targets": targets, + "arch": arch, + "group": group_name, + "len": len(grouped_targets[arch]['manufacturers'][man]) + }) + elif(man_len >= (SPLIT_LIMIT + 1)): + # Split big man groups into subgroups + # example: Pixhawk + chunk_limit = SPLIT_LIMIT + chunk_counter = 0 + for chunk in chunks(grouped_targets[arch]['manufacturers'][man], chunk_limit): + group_name = arch + "-" + man + "-" + str(chunk_counter) + targets = comma_targets(chunk) + last_man = man + final_groups.append({ + "container": grouped_targets[arch]['container'], + "targets": targets, + "arch": arch, + "group": group_name, + "len": len(chunk), + }) + chunk_counter += 1 + else: + temp_group.append(tar) + + if(last_arch != arch and len(temp_group) > 0): + group_name = last_arch + "-" + str(group_number[last_arch]) + group_number[last_arch] += 1 + targets = comma_targets(temp_group) + final_groups.append({ + "container": grouped_targets[last_arch]['container'], + "targets": targets, + "arch": last_arch, + "group": group_name, + "len": len(temp_group) + }) + last_arch = arch + temp_group = [] + if(len(temp_group) > (LOWER_LIMIT - 1)): + group_name = arch + "-" + str(group_number[arch]) + last_arch = arch + group_number[arch] += 1 + targets = comma_targets(temp_group) + final_groups.append({ + "container": grouped_targets[arch]['container'], + "targets": targets, + "arch": arch, + "group": group_name, + "len": len(temp_group) + }) + temp_group = [] + if(verbose): + import pprint + print("================") + print("= final_groups =") + print("================") + pprint.pp(final_groups) + + print("===============") + print("= JSON output =") + print("===============") + + print(json.dumps({ "include": final_groups }, **extra_args)) +else: + print(json.dumps(github_action_config, **extra_args)) From 072892fbefc1f4b3e4a3ef71f01f4b33316d5d1f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 22 Apr 2024 10:53:09 -0700 Subject: [PATCH 643/652] romfs: rcS: support storage on other then SD card --- ROMFS/px4fmu_common/init.d/rcS | 36 ++++++++++++++++++++-------------- 1 file changed, 21 insertions(+), 15 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 39eed1bcab4d..28804361d1ed 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -30,7 +30,7 @@ set LOGGER_BUF 8 set PARAM_FILE "" set PARAM_BACKUP_FILE "" set RC_INPUT_ARGS "" -set SDCARD_AVAILABLE no +set STORAGE_AVAILABLE no set SDCARD_EXT_PATH /fs/microsd/ext_autostart set SDCARD_FORMAT no set STARTUP_TUNE 1 @@ -62,11 +62,11 @@ then umount /fs/microsd else - set SDCARD_AVAILABLE yes + set STORAGE_AVAILABLE yes fi fi - if [ $SDCARD_AVAILABLE = no -o $SDCARD_FORMAT = yes ] + if [ $STORAGE_AVAILABLE = no -o $SDCARD_FORMAT = yes ] then echo "INFO [init] formatting /dev/mmcsd0" set STARTUP_TUNE 15 # tune 15 = SD_ERROR (overridden to SD_INIT if format + mount succeeds) @@ -77,7 +77,7 @@ then if mount -t vfat /dev/mmcsd0 /fs/microsd then - set SDCARD_AVAILABLE yes + set STORAGE_AVAILABLE yes set STARTUP_TUNE 14 # tune 14 = SD_INIT else echo "ERROR [init] card mount failed" @@ -86,16 +86,22 @@ then echo "ERROR [init] format failed" fi fi +else + # Is there a device mounted for storage + if mft query -q -k MTD -s MTD_PARAMETERS -v /mnt/microsd + then + set STORAGE_AVAILABLE yes + fi +fi - if [ $SDCARD_AVAILABLE = yes ] +if [ $STORAGE_AVAILABLE = yes ] +then + if hardfault_log check then - if hardfault_log check + set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE + if hardfault_log commit then - set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE - if hardfault_log commit - then - hardfault_log reset - fi + hardfault_log reset fi fi @@ -172,7 +178,7 @@ else fi fi - if [ $SDCARD_AVAILABLE = yes ] + if [ $STORAGE_AVAILABLE = yes ] then param select-backup $PARAM_BACKUP_FILE fi @@ -220,8 +226,8 @@ else if [ ${VEHICLE_TYPE} == none ] then - # Look for airframe on SD card - if [ $SDCARD_AVAILABLE = yes ] + # Use external startup file + if [ $STORAGE_AVAILABLE = yes ] then . ${R}etc/init.d/rc.autostart_ext else @@ -615,7 +621,7 @@ unset PARAM_FILE unset PARAM_BACKUP_FILE unset PARAM_DEFAULTS_VER unset RC_INPUT_ARGS -unset SDCARD_AVAILABLE +unset STORAGE_AVAILABLE unset SDCARD_EXT_PATH unset SDCARD_FORMAT unset STARTUP_TUNE From 07734c243ff74b6e5191471858fb32300879262e Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Mon, 5 Aug 2024 15:15:03 +0200 Subject: [PATCH 644/652] mtd: Initialized the RAMTRON speed with 30MHz --- platforms/nuttx/src/px4/common/px4_mtd.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/platforms/nuttx/src/px4/common/px4_mtd.cpp b/platforms/nuttx/src/px4/common/px4_mtd.cpp index 24d88ed3d89a..6723c35ecadb 100644 --- a/platforms/nuttx/src/px4/common/px4_mtd.cpp +++ b/platforms/nuttx/src/px4/common/px4_mtd.cpp @@ -75,11 +75,11 @@ static int ramtron_attach(mtd_instance_s &instance) return ENXIO; #else - /* start the RAMTRON driver, attempt 10 times */ + /* start the RAMTRON driver at 30MHz */ - int spi_speed_mhz = 10; + unsigned long spi_speed_hz = 30'000'000; - for (int i = 0; i < 10; i++) { + for (int i = 0; spi_speed_hz > 0; i++) { /* initialize the right spi */ struct spi_dev_s *spi = px4_spibus_initialize(px4_find_spi_bus(instance.devid)); @@ -90,7 +90,7 @@ static int ramtron_attach(mtd_instance_s &instance) /* this resets the spi bus, set correct bus speed again */ SPI_LOCK(spi, true); - SPI_SETFREQUENCY(spi, spi_speed_mhz * 1000 * 1000); + SPI_SETFREQUENCY(spi, spi_speed_hz); SPI_SETBITS(spi, 8); SPI_SETMODE(spi, SPIDEV_MODE3); SPI_SELECT(spi, instance.devid, false); @@ -108,7 +108,7 @@ static int ramtron_attach(mtd_instance_s &instance) } // try reducing speed for next attempt - spi_speed_mhz--; + spi_speed_hz -= 1'000'000; px4_usleep(10000); } @@ -118,7 +118,7 @@ static int ramtron_attach(mtd_instance_s &instance) return -EIO; } - int ret = instance.mtd_dev->ioctl(instance.mtd_dev, MTDIOC_SETSPEED, (unsigned long)spi_speed_mhz * 1000 * 1000); + int ret = instance.mtd_dev->ioctl(instance.mtd_dev, MTDIOC_SETSPEED, spi_speed_hz); if (ret != OK) { // FIXME: From the previous warning call, it looked like this should have been fatal error instead. Tried From c60b1d1a5f2b675bc6724642f038997a8d3921e0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 15 Jul 2024 15:04:26 +0200 Subject: [PATCH 645/652] board_hw_rev_ver: Support EEPROM-only HW IDs --- .../stm32_common/board_hw_info/board_hw_rev_ver.c | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c b/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c index 6d484c0a826f..1a505e98217f 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c @@ -73,7 +73,7 @@ static char hw_base_info[HW_INFO_SIZE] = {0}; /**************************************************************************** * Protected Functions ****************************************************************************/ - +#if !defined(BOARD_HAS_ONLY_EEPROM_VERSIONING) static int dn_to_ordinal(uint16_t dn) { /* Table is scaled for 12, so if ADC is in 16 bit mode @@ -111,6 +111,7 @@ static int dn_to_ordinal(uint16_t dn) return -1; } +#endif /* BOARD_HAS_ONLY_EEPROM_VERSIONING */ /************************************************************************************ * Name: read_id_dn @@ -143,7 +144,7 @@ static int dn_to_ordinal(uint16_t dn) * -EIO - FAiled to init or read the ADC * ************************************************************************************/ - +#if !defined(BOARD_HAS_ONLY_EEPROM_VERSIONING) static int read_id_dn(int *id, uint32_t gpio_drive, uint32_t gpio_sense, int adc_channel) { int rv = -EIO; @@ -328,9 +329,15 @@ static int read_id_dn(int *id, uint32_t gpio_drive, uint32_t gpio_sense, int adc stm32_configgpio(gpio_drive); return rv; } +#endif /* BOARD_HAS_ONLY_EEPROM_VERSIONING */ static int determine_hw_info(int *revision, int *version) { +#if defined(BOARD_HAS_ONLY_EEPROM_VERSIONING) + *revision = HW_ID_EEPROM; + *version = HW_ID_EEPROM; + return OK; +#else int dn; int rv = read_id_dn(&dn, GPIO_HW_REV_DRIVE, GPIO_HW_REV_SENSE, ADC_HW_REV_SENSE_CHANNEL); @@ -344,6 +351,7 @@ static int determine_hw_info(int *revision, int *version) } return rv; +#endif } /**************************************************************************** From ecfdbd2e60660a373c158544d4580b21d4f4059b Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Wed, 31 Jul 2024 14:36:49 +0200 Subject: [PATCH 646/652] littlefs: needs more stack when used --- .../px4_work_queue/WorkQueueManager.hpp | 2 +- src/modules/logger/Kconfig | 8 ++++++++ src/modules/logger/logger.cpp | 2 +- src/systemcmds/hardfault_log/CMakeLists.txt | 1 + src/systemcmds/param/CMakeLists.txt | 1 + 5 files changed, 12 insertions(+), 2 deletions(-) diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp index 761041fa0e83..68ac3f1ffea9 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp @@ -89,7 +89,7 @@ static constexpr wq_config_t ttyS9{"wq:ttyS9", 1728, -30}; static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1728, -31}; static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1728, -32}; -static constexpr wq_config_t lp_default{"wq:lp_default", 2000, -50}; +static constexpr wq_config_t lp_default{"wq:lp_default", 2350, -50}; static constexpr wq_config_t test1{"wq:test1", 2000, 0}; static constexpr wq_config_t test2{"wq:test2", 2000, 0}; diff --git a/src/modules/logger/Kconfig b/src/modules/logger/Kconfig index db2c5a75460e..985fd3d56ed1 100644 --- a/src/modules/logger/Kconfig +++ b/src/modules/logger/Kconfig @@ -10,3 +10,11 @@ menuconfig USER_LOGGER depends on BOARD_PROTECTED && MODULES_LOGGER ---help--- Put logger in userspace memory + +menuconfig LOGGER_STACK_SIZE + int "stack size of logger task" + default 3700 + depends on MODULES_LOGGER + ---help--- + Stack size of the logger task. Some configurations require more stack + than the default. diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index be66d5465c95..8d897a103a4d 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -176,7 +176,7 @@ int Logger::task_spawn(int argc, char *argv[]) _task_id = px4_task_spawn_cmd("logger", SCHED_DEFAULT, SCHED_PRIORITY_LOG_CAPTURE, - PX4_STACK_ADJUSTED(3700), + PX4_STACK_ADJUSTED(CONFIG_LOGGER_STACK_SIZE), (px4_main_t)&run_trampoline, (char *const *)argv); diff --git a/src/systemcmds/hardfault_log/CMakeLists.txt b/src/systemcmds/hardfault_log/CMakeLists.txt index fca7fc683929..8cd4ca9fea86 100644 --- a/src/systemcmds/hardfault_log/CMakeLists.txt +++ b/src/systemcmds/hardfault_log/CMakeLists.txt @@ -35,6 +35,7 @@ px4_add_module( MAIN hardfault_log COMPILE_FLAGS -Wno-cast-align # TODO: fix and enable + STACK_MAIN 4096 SRCS hardfault_log.c DEPENDS diff --git a/src/systemcmds/param/CMakeLists.txt b/src/systemcmds/param/CMakeLists.txt index 0a27cf958949..056401daf75e 100644 --- a/src/systemcmds/param/CMakeLists.txt +++ b/src/systemcmds/param/CMakeLists.txt @@ -35,6 +35,7 @@ px4_add_module( MAIN param COMPILE_FLAGS -Wno-array-bounds + STACK_MAIN 4096 SRCS param.cpp DEPENDS From f2f4488594f21b83ed9d717a250fd61b93a356ca Mon Sep 17 00:00:00 2001 From: Thomas Stauber <48206725+ThomasRigi@users.noreply.github.com> Date: Mon, 19 Aug 2024 17:14:12 +0200 Subject: [PATCH 647/652] drivers/gps: publish secondary instance satellite_info if main instance is advertised --- src/drivers/gps/gps.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index c1dd783be029..004be4cc8b90 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -1214,11 +1214,13 @@ GPS::publish() void GPS::publishSatelliteInfo() { - if (_instance == Instance::Main) { + if (_instance == Instance::Main || _is_gps_main_advertised.load()) { if (_p_report_sat_info != nullptr) { _report_sat_info_pub.publish(*_p_report_sat_info); } + _is_gps_main_advertised.store(true); + } else { //we don't publish satellite info for the secondary gps } From 98eae3cd4cc1fef11f12d50563d5bbfc5141d833 Mon Sep 17 00:00:00 2001 From: Beniamino Pozzan Date: Sun, 18 Aug 2024 10:09:29 +0100 Subject: [PATCH 648/652] fix: `make help` on Ubuntu 22.04 Ubuntu 22.04 uses make 4.3 which broke the current `make help` target Reference: https://stackoverflow.com/a/26339924 Signed-off-by: Beniamino Pozzan --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 37c61db1c0b3..5de475d79074 100644 --- a/Makefile +++ b/Makefile @@ -557,7 +557,7 @@ help: @echo "Usage: $(MAKE) " @echo "Where is one of:" @$(MAKE) -pRrq -f $(lastword $(MAKEFILE_LIST)) : 2>/dev/null | \ - awk -v RS= -F: '/^# File/,/^# Finished Make data base/ {if ($$1 !~ "^[#.]") {print $$1}}' | sort | \ + awk -v RS= -F: '/(^|\n)# Files(\n|$$)/,/(^|\n)# Finished Make data base/ {if ($$1 !~ "^[#.]") {print $$1}}' | sort | \ egrep -v -e '^[^[:alnum:]]' -e '^($(subst $(space),|,$(ALL_CONFIG_TARGETS)))$$' -e '_default$$' -e '^(Makefile)' @echo @echo "Or, $(MAKE) []" From 093117957948556b1e10808b942ea456a4b0526b Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 20 Aug 2024 13:27:12 +0200 Subject: [PATCH 649/652] ekf2: extract WMM update logic --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 32 +------------ src/modules/ekf2/EKF/ekf.h | 1 + src/modules/ekf2/EKF/ekf_helper.cpp | 48 +++++++++++++------ 3 files changed, 36 insertions(+), 45 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 da7fc4e16060..94fa6f04f381 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -98,37 +98,7 @@ void Ekf::collect_gps(const gnssSample &gps) const bool gps_rough_2d_fix = (gps.fix_type >= 2) && (gps.hacc < 1000); if (gps_rough_2d_fix && (_gps_checks_passed || !_NED_origin_initialised)) { - - // If we have good GPS data set the origin's WGS-84 position to the last gps fix -#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(gps.lat, gps.lon)); - const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(gps.lat, gps.lon)); - const float mag_strength_gps = get_mag_strength_gauss(gps.lat, gps.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 - + updateWmm(gps.lat, gps.lon); _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index f3f055434e62..a7c43567df52 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -259,6 +259,7 @@ 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; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index d88f7c400d92..ae3e9e355e0a 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -96,20 +96,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons _pos_ref.initReference(latitude, longitude, _time_delayed_us); _gps_alt_ref = altitude; -#if defined(CONFIG_EKF2_MAGNETOMETER) - const float mag_declination_gps = math::radians(get_mag_declination_degrees(latitude, longitude)); - const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(latitude, longitude)); - const float mag_strength_gps = get_mag_strength_gauss(latitude, longitude); - - if (PX4_ISFINITE(mag_declination_gps) && PX4_ISFINITE(mag_inclination_gps) && PX4_ISFINITE(mag_strength_gps)) { - _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 + updateWmm(current_lat, current_lon); _gpos_origin_eph = eph; _gpos_origin_epv = epv; @@ -144,6 +131,39 @@ 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; From f252e20eaec78972ff0723af26c922c3015aa6a6 Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Wed, 21 Aug 2024 01:36:08 +0200 Subject: [PATCH 650/652] Revert "Update GZBridge to be able to use gazebo airspeed. Add quadtailsitter. (#23455)" (#23583) This reverts commit 7e45f4915208b2d02e05e5741ff7456cf92120f9. Co-authored-by: jmackay2 <1.732mackay@gmail.com> --- .../1045_gazebo-classic_quadtailsitter | 2 +- .../airframes/4004_gz_standard_vtol | 2 + .../airframes/4014_gz_quadtailsitter | 92 ------------------- .../init.d-posix/airframes/CMakeLists.txt | 1 - src/modules/simulation/gz_bridge/GZBridge.cpp | 16 ++-- src/modules/simulation/gz_bridge/GZBridge.hpp | 4 +- .../sensor_airspeed_sim/SensorAirspeedSim.cpp | 2 +- 7 files changed, 16 insertions(+), 103 deletions(-) delete mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter index 9539ba6d7402..87afb523b1a7 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter @@ -33,7 +33,7 @@ param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 param set-default PWM_MAIN_FUNC5 0 -param set-default FD_FAIL_R 70 +parm set-default FD_FAIL_R 70 param set-default FW_P_TC 0.6 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 580b6da368de..96bb25d69a52 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -14,7 +14,9 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol} param set-default SIM_GZ_EN 1 param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 0 param set-default SENS_EN_MAGSIM 1 +param set-default SENS_EN_ARSPDSIM 1 # TODO: Enable motor failure detection when the # VTOL no longer reports 0A for all ESCs in SITL diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter deleted file mode 100644 index 699d1dacc521..000000000000 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter +++ /dev/null @@ -1,92 +0,0 @@ -#!/bin/sh -# -# @name Quadrotor + Tailsitter -# -# @type VTOL Quad Tailsitter -# - -. ${R}etc/init.d/rc.vtol_defaults - -PX4_SIMULATOR=${PX4_SIMULATOR:=gz} -PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} -PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadtailsitter} - -param set-default SIM_GZ_EN 1 - -param set-default SENS_EN_GPSSIM 1 -param set-default SENS_EN_BAROSIM 0 -param set-default SENS_EN_MAGSIM 1 -param set-default SENS_EN_ARSPDSIM 0 - -param set-default MAV_TYPE 20 - -param set-default CA_AIRFRAME 4 - -param set-default CA_ROTOR_COUNT 4 -param set-default CA_ROTOR0_PX 0.15 -param set-default CA_ROTOR0_PY 0.23 -param set-default CA_ROTOR0_KM 0.05 -param set-default CA_ROTOR1_PX -0.15 -param set-default CA_ROTOR1_PY -0.23 -param set-default CA_ROTOR1_KM 0.05 -param set-default CA_ROTOR2_PX 0.15 -param set-default CA_ROTOR2_PY -0.23 -param set-default CA_ROTOR2_KM -0.05 -param set-default CA_ROTOR3_PX -0.15 -param set-default CA_ROTOR3_PY 0.23 -param set-default CA_ROTOR3_KM -0.05 - -param set-default CA_SV_CS_COUNT 0 - -param set-default SIM_GZ_EC_FUNC1 101 -param set-default SIM_GZ_EC_MIN1 10 -param set-default SIM_GZ_EC_MAX1 1500 -param set-default SIM_GZ_EC_FUNC2 102 -param set-default SIM_GZ_EC_MIN2 10 -param set-default SIM_GZ_EC_MAX2 1500 -param set-default SIM_GZ_EC_FUNC3 103 -param set-default SIM_GZ_EC_MIN3 10 -param set-default SIM_GZ_EC_MAX3 1500 -param set-default SIM_GZ_EC_FUNC4 104 -param set-default SIM_GZ_EC_MIN4 10 -param set-default SIM_GZ_EC_MAX4 1500 - -param set-default FD_FAIL_R 70 - -param set-default FW_P_TC 0.6 - -param set-default FW_PR_I 0.3 -param set-default FW_PR_P 0.5 -param set-default FW_PSP_OFF 2 -param set-default FW_RR_FF 0.1 -param set-default FW_RR_I 0.1 -param set-default FW_RR_P 0.2 -param set-default FW_YR_FF 0 # make yaw rate controller very weak, only keep default P -param set-default FW_YR_I 0 -param set-default FW_THR_TRIM 0.35 -param set-default FW_THR_MAX 0.8 -param set-default FW_THR_MIN 0.05 -param set-default FW_T_CLMB_MAX 6 -param set-default FW_T_HRATE_FF 0.5 -param set-default FW_T_SINK_MAX 3 -param set-default FW_T_SINK_MIN 1.6 -param set-default FW_AIRSPD_STALL 10 -param set-default FW_AIRSPD_MIN 14 -param set-default FW_AIRSPD_TRIM 18 -param set-default FW_AIRSPD_MAX 22 - -param set-default MC_AIRMODE 2 -param set-default MAN_ARM_GESTURE 0 # required for yaw airmode -param set-default MC_ROLL_P 3 -param set-default MC_PITCH_P 3 -param set-default MC_ROLLRATE_P 0.3 -param set-default MC_PITCHRATE_P 0.3 - -param set-default VT_ARSP_TRANS 15 -param set-default VT_B_TRANS_DUR 5 -param set-default VT_FW_DIFTHR_EN 7 -param set-default VT_FW_DIFTHR_S_Y 1 -param set-default VT_F_TRANS_DUR 1.5 -param set-default VT_TYPE 0 - -param set-default WV_EN 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index badd712b063f..9235b2e66340 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -85,7 +85,6 @@ px4_add_romfs_files( 4011_gz_lawnmower 4012_gz_rover_ackermann 4013_gz_x500_lidar - 4014_gz_quadtailsitter 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 6b4042da8bb3..3464c628694c 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -203,15 +203,17 @@ int GZBridge::init() PX4_WARN("failed to subscribe to %s", laser_scan_topic.c_str()); } - // Airspeed: /world/$WORLD/model/$MODEL/link/base_link/sensor/airspeed_sensor/air_speed - std::string airspeed_topic = "/world/" + _world_name + "/model/" + _model_name + - "/link/base_link/sensor/airspeed_sensor/air_speed"; +#if 0 + // Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed + std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name + + "/link/airspeed_link/sensor/air_speed/air_speed"; - if (!_node.Subscribe(airspeed_topic, &GZBridge::airspeedCallback, this)) { - PX4_ERR("failed to subscribe to %s", airspeed_topic.c_str()); + if (!_node.Subscribe(airpressure_topic, &GZBridge::airspeedCallback, this)) { + PX4_ERR("failed to subscribe to %s", airpressure_topic.c_str()); return PX4_ERROR; } +#endif // Air pressure: /world/$WORLD/model/$MODEL/link/base_link/sensor/air_pressure_sensor/air_pressure std::string air_pressure_topic = "/world/" + _world_name + "/model/" + _model_name + "/link/base_link/sensor/air_pressure_sensor/air_pressure"; @@ -424,7 +426,8 @@ void GZBridge::barometerCallback(const gz::msgs::FluidPressure &air_pressure) pthread_mutex_unlock(&_node_mutex); } -void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed) +#if 0 +void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed) { if (hrt_absolute_time() == 0) { return; @@ -449,6 +452,7 @@ void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed) pthread_mutex_unlock(&_node_mutex); } +#endif void GZBridge::imuCallback(const gz::msgs::IMU &imu) { diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index 824c7d471633..8a832f7961b2 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -102,7 +102,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void clockCallback(const gz::msgs::Clock &clock); - void airspeedCallback(const gz::msgs::AirSpeed &air_speed); + // void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure); void barometerCallback(const gz::msgs::FluidPressure &air_pressure); void imuCallback(const gz::msgs::IMU &imu); void poseInfoCallback(const gz::msgs::Pose_V &pose); @@ -123,7 +123,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S // Subscriptions uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; - uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; + //uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; uORB::Publication _obstacle_distance_pub{ORB_ID(obstacle_distance)}; uORB::Publication _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)}; uORB::Publication _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)}; diff --git a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp index 86fbbf29cd4c..7b0d9556cadf 100644 --- a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp +++ b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp @@ -195,7 +195,7 @@ int SensorAirspeedSim::print_usage(const char *reason) )DESCR_STR"); - PRINT_MODULE_USAGE_NAME("sensor_airspeed_sim", "system"); + PRINT_MODULE_USAGE_NAME("sensor_arispeed_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); From 3478765c310d3d34fc139dbf62594c41da6f85a9 Mon Sep 17 00:00:00 2001 From: KonradRudin <98741601+KonradRudin@users.noreply.github.com> Date: Wed, 21 Aug 2024 09:08:36 +0200 Subject: [PATCH 651/652] Navigator: MissionFeasibilityCheck: Rework 1st waypoint check (#23568) * FeasibilityChecker: only warn when first waypoint is too far, but still accept mission as valid * feasiblityChecker: make distance to first waypoint check against home position instead of current position, so it is more constant during a flight * Apply suggestions from code review Co-authored-by: Silvan Fuhrer * feasibilityCheckerTest: update tests to not fail for first waypoint check * feasibilityChecker: make comment for 1stwaypointcheck event * Feasibility check unit test: fix comment Signed-off-by: Silvan Fuhrer --------- Signed-off-by: Silvan Fuhrer Co-authored-by: Silvan Fuhrer --- .../MissionFeasibility/FeasibilityChecker.cpp | 40 ++++++++----------- .../MissionFeasibility/FeasibilityChecker.hpp | 4 -- .../FeasibilityCheckerTest.cpp | 4 +- .../navigator/mission_feasibility_checker.cpp | 1 - 4 files changed, 19 insertions(+), 30 deletions(-) diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp index c684f0119d9b..c2b3a8119807 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp @@ -49,7 +49,6 @@ void FeasibilityChecker::reset() _mission_validity_failed = false; _takeoff_failed = false; _land_pattern_validity_failed = false; - _distance_first_waypoint_failed = false; _distance_between_waypoints_failed = false; _fixed_wing_land_approach_failed = false; _takeoff_land_available_failed = false; @@ -118,12 +117,6 @@ void FeasibilityChecker::updateData() _is_landed = land_detected.landed; } - if (_vehicle_global_position_sub.updated()) { - vehicle_global_position_s vehicle_global_position = {}; - _vehicle_global_position_sub.copy(&vehicle_global_position); - _current_position_lat_lon = matrix::Vector2d(vehicle_global_position.lat, vehicle_global_position.lon); - } - if (_rtl_status_sub.updated()) { rtl_status_s rtl_status = {}; _rtl_status_sub.copy(&rtl_status); @@ -199,8 +192,8 @@ void FeasibilityChecker::doCommonChecks(mission_item_s &mission_item, const int _distance_between_waypoints_failed = !checkDistancesBetweenWaypoints(mission_item); } - if (!_distance_first_waypoint_failed) { - _distance_first_waypoint_failed = !checkHorizontalDistanceToFirstWaypoint(mission_item); + if (!_first_waypoint_found) { + checkHorizontalDistanceToFirstWaypoint(mission_item); } if (!_takeoff_failed) { @@ -631,31 +624,32 @@ bool FeasibilityChecker::hasMissionBothOrNeitherTakeoffAndLanding() bool FeasibilityChecker::checkHorizontalDistanceToFirstWaypoint(mission_item_s &mission_item) { if (_param_mis_dist_1wp > FLT_EPSILON && - (_current_position_lat_lon.isAllFinite()) && !_first_waypoint_found && + (_home_lat_lon.isAllFinite()) && MissionBlock::item_contains_position(mission_item)) { _first_waypoint_found = true; - float dist_to_1wp_from_current_pos = 1e6f; - - if (_current_position_lat_lon.isAllFinite()) { - dist_to_1wp_from_current_pos = get_distance_to_next_waypoint( - mission_item.lat, mission_item.lon, - _current_position_lat_lon(0), _current_position_lat_lon(1)); - } + const float dist_to_1wp_from_home_pos = get_distance_to_next_waypoint( + mission_item.lat, mission_item.lon, + _home_lat_lon(0), _home_lat_lon(1)); - if (dist_to_1wp_from_current_pos < _param_mis_dist_1wp) { + if (dist_to_1wp_from_home_pos < _param_mis_dist_1wp) { return true; } else { /* item is too far from current position */ mavlink_log_critical(_mavlink_log_pub, - "First waypoint too far away: %dm, %d max\t", - (int)dist_to_1wp_from_current_pos, (int)_param_mis_dist_1wp); - events::send(events::ID("navigator_mis_first_wp_too_far"), {events::Log::Error, events::LogInternal::Info}, - "First waypoint too far away: {1m} (maximum: {2m})", (uint32_t)dist_to_1wp_from_current_pos, - (uint32_t)_param_mis_dist_1wp); + "First waypoint far away from home: %dm. Correct mission loaded?\t", + (int)dist_to_1wp_from_home_pos); + /* EVENT + * @description + * + * This check can be configured via MIS_DIST_1WP parameter. + * + */ + events::send(events::ID("navigator_mis_first_wp_far"), {events::Log::Warning, events::LogInternal::Info}, + "First waypoint far away from Home: {1m} Correct mission loaded?", (uint32_t)dist_to_1wp_from_home_pos); return false; } diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp index fd18cbcfb68e..d0905d363545 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp @@ -78,7 +78,6 @@ class FeasibilityChecker : public ModuleParams bool someCheckFailed() { return _takeoff_failed || - _distance_first_waypoint_failed || _distance_between_waypoints_failed || _land_pattern_validity_failed || _fixed_wing_land_approach_failed || @@ -97,7 +96,6 @@ class FeasibilityChecker : public ModuleParams uORB::Subscription _home_pos_sub{ORB_ID(home_position)}; uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _land_detector_sub{ORB_ID(vehicle_land_detected)}; - uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; uORB::Subscription _rtl_status_sub{ORB_ID(rtl_status)}; // parameters @@ -110,14 +108,12 @@ class FeasibilityChecker : public ModuleParams float _home_alt_msl{NAN}; bool _has_vtol_approach{false}; matrix::Vector2d _home_lat_lon = matrix::Vector2d((double)NAN, (double)NAN); - matrix::Vector2d _current_position_lat_lon = matrix::Vector2d((double)NAN, (double)NAN); VehicleType _vehicle_type{VehicleType::RotaryWing}; // internal flags to keep track of which checks failed bool _mission_validity_failed{false}; bool _takeoff_failed{false}; bool _land_pattern_validity_failed{false}; - bool _distance_first_waypoint_failed{false}; bool _distance_between_waypoints_failed{false}; bool _fixed_wing_land_approach_failed{false}; bool _takeoff_land_available_failed{false}; diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp b/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp index 0de54f33766c..43662441488a 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp @@ -170,9 +170,9 @@ TEST_F(FeasibilityCheckerTest, check_dist_first_waypoint) mission_item.lat = lat_new; mission_item.lon = lon_new; - // THEN: fail + // THEN: pass checker.processNextItem(mission_item, 0, 1); - ASSERT_EQ(checker.someCheckFailed(), true); + ASSERT_EQ(checker.someCheckFailed(), false); // BUT WHEN: valid current position fist WP 499m away from current checker.reset(); diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index dc2420d55bf5..8049df1236cf 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -41,7 +41,6 @@ */ #include "mission_feasibility_checker.h" -#include "MissionFeasibility/FeasibilityChecker.hpp" #include "mission_block.h" #include "navigator.h" From cc108366053d5e1904cad8a855854e6af78d8e63 Mon Sep 17 00:00:00 2001 From: Jordan Leiber Date: Wed, 21 Aug 2024 09:49:08 -0400 Subject: [PATCH 652/652] calculate esc_rpm in rpm instead of rad per second auto formatting on vertiq telem manager --- src/drivers/actuators/vertiq_io/vertiq_telemetry_manager.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/actuators/vertiq_io/vertiq_telemetry_manager.cpp b/src/drivers/actuators/vertiq_io/vertiq_telemetry_manager.cpp index 0c5bc85ca8a5..91df70639d30 100644 --- a/src/drivers/actuators/vertiq_io/vertiq_telemetry_manager.cpp +++ b/src/drivers/actuators/vertiq_io/vertiq_telemetry_manager.cpp @@ -113,7 +113,8 @@ uint16_t VertiqTelemetryManager::UpdateTelemetry() // also update our internal report for logging _esc_status.esc[_current_module_id_target_index].esc_address = _module_ids_in_use[_number_of_module_ids_for_telem]; _esc_status.esc[_current_module_id_target_index].timestamp = time_now; - _esc_status.esc[_current_module_id_target_index].esc_rpm = telem_response.speed; + _esc_status.esc[_current_module_id_target_index].esc_rpm = telem_response.speed * 60.0f * M_1_PI_F * + 0.5f; //We get back rad/s, convert to rpm _esc_status.esc[_current_module_id_target_index].esc_voltage = telem_response.voltage * 0.01; _esc_status.esc[_current_module_id_target_index].esc_current = telem_response.current * 0.01; _esc_status.esc[_current_module_id_target_index].esc_power =